Skip to content

Commit 6da89f0

Browse files
committed
Add waggle stick subsystem
1 parent 08cb95f commit 6da89f0

File tree

3 files changed

+80
-0
lines changed

3 files changed

+80
-0
lines changed

src/main/java/frc/robot/Constants.java

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
import org.lasarobotics.drive.MAXSwerveModule;
1111
import org.lasarobotics.hardware.kauailabs.NavX2;
1212
import org.lasarobotics.hardware.revrobotics.Spark;
13+
import org.lasarobotics.hardware.revrobotics.SparkPIDConfig;
1314
import org.lasarobotics.led.LEDStrip;
1415
import org.lasarobotics.utils.PIDConstants;
1516

@@ -20,6 +21,7 @@
2021
import edu.wpi.first.math.geometry.Transform3d;
2122
import edu.wpi.first.math.geometry.Translation2d;
2223
import edu.wpi.first.math.geometry.Translation3d;
24+
import edu.wpi.first.math.trajectory.TrapezoidProfile;
2325
import edu.wpi.first.units.Units;
2426
import frc.robot.subsystems.drive.PurplePathPose;
2527
import frc.robot.subsystems.vision.AprilTagCamera.Resolution;
@@ -123,6 +125,19 @@ public static class VisionHardware {
123125
public static final Rotation2d CAMERA_OBJECT_FOV = Rotation2d.fromDegrees(79.7);
124126
}
125127

128+
public static class WiggleStick {
129+
public static final SparkPIDConfig WIGGLE_STICK_CONFIG = new SparkPIDConfig(
130+
new PIDConstants(0.2, 0, 0, 0),
131+
false,
132+
false,
133+
1.0,
134+
0.0,
135+
15.0,
136+
true
137+
);
138+
public static final TrapezoidProfile.Constraints CONSTRAINTS = new TrapezoidProfile.Constraints(10, 20);
139+
}
140+
126141
public static class SmartDashboard {
127142
public static final String SMARTDASHBOARD_DEFAULT_TAB = "SmartDashboard";
128143
public static final String SMARTDASHBOARD_AUTO_MODE = "Auto Mode";

src/main/java/frc/robot/RobotContainer.java

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
import edu.wpi.first.wpilibj2.command.Command;
1111
import edu.wpi.first.wpilibj2.command.Commands;
1212
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
13+
import frc.robot.subsystems.WaggleSubsystem;
1314
import frc.robot.subsystems.drive.DriveSubsystem;
1415

1516
public class RobotContainer {
@@ -24,6 +25,8 @@ public class RobotContainer {
2425
Constants.Drive.DRIVE_LOOKAHEAD
2526
);
2627

28+
private static final WaggleSubsystem WIGGLE_STICK = new WaggleSubsystem(Constants.WiggleStick.WIGGLE_STICK_CONFIG, Constants.WiggleStick.CONSTRAINTS);
29+
2730
private static final CommandXboxController PRIMARY_CONTROLLER = new CommandXboxController(Constants.HID.PRIMARY_CONTROLLER_PORT);
2831

2932
public RobotContainer() {
@@ -58,6 +61,10 @@ private void configureBindings() {
5861
PRIMARY_CONTROLLER.b().whileTrue(DRIVE_SUBSYSTEM.goToPoseCommand(Constants.Field.SOURCE));
5962

6063
PRIMARY_CONTROLLER.povLeft().onTrue(DRIVE_SUBSYSTEM.resetPoseCommand(() -> new Pose2d()));
64+
65+
// POV left/right - wiggle stick
66+
PRIMARY_CONTROLLER.povLeft().onTrue(WIGGLE_STICK.setPositionCommand(0.0));
67+
PRIMARY_CONTROLLER.povRight().onTrue(WIGGLE_STICK.setPositionCommand(15.0));
6168
}
6269

6370
/**
Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
// Copyright (c) FIRST and other WPILib contributors.
2+
// Open Source Software; you can modify and/or share it under the terms of
3+
// the WPILib BSD license file in the root directory of this project.
4+
5+
package frc.robot.subsystems;
6+
7+
import org.lasarobotics.hardware.revrobotics.Spark;
8+
import org.lasarobotics.hardware.revrobotics.Spark.FeedbackSensor;
9+
import org.lasarobotics.hardware.revrobotics.Spark.MotorKind;
10+
import org.lasarobotics.hardware.revrobotics.SparkPIDConfig;
11+
12+
import com.revrobotics.CANSparkBase.IdleMode;
13+
14+
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
15+
import edu.wpi.first.wpilibj2.command.Command;
16+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
17+
18+
19+
public class WaggleSubsystem extends SubsystemBase {
20+
Spark m_motor;
21+
SparkPIDConfig m_config;
22+
Constraints m_constraint;
23+
24+
/** Creates a new wiggleStick. */
25+
public WaggleSubsystem(SparkPIDConfig config, Constraints constraint) {
26+
m_motor = new Spark(new Spark.ID("wiggleStick", 20), MotorKind.NEO);
27+
m_config = config;
28+
m_constraint = constraint;
29+
30+
double conversionFactor = 1.0;
31+
m_motor.initializeSparkPID(config, FeedbackSensor.NEO_ENCODER);
32+
m_motor.setPositionConversionFactor(FeedbackSensor.NEO_ENCODER, conversionFactor);
33+
m_motor.setVelocityConversionFactor(FeedbackSensor.NEO_ENCODER, conversionFactor);
34+
35+
m_motor.enablePIDWrapping(0.0, 15.0);
36+
m_motor.setIdleMode(IdleMode.kCoast);
37+
m_motor.resetEncoder();
38+
}
39+
40+
public void setPosition(double position) {
41+
m_motor.smoothMotion(position, m_constraint);
42+
}
43+
44+
public double getPosition() {
45+
return m_motor.getInputs().encoderPosition;
46+
}
47+
48+
public Command setPositionCommand(double position) {
49+
return runOnce(() -> setPosition(position));
50+
51+
}
52+
53+
@Override
54+
public void periodic() {
55+
// This method will be called once per scheduler run
56+
m_motor.periodic();
57+
}
58+
}

0 commit comments

Comments
 (0)