Skip to content

Commit 6648f49

Browse files
Provided support for shuffleboard usage.
* Now, we can use shuffleboard to observe the differential drive's inputs and outputs. * The shuffleboard can only manipulate values from its LiveWindow interface when the robot is in testing mode.
1 parent d85aa97 commit 6648f49

File tree

3 files changed

+121
-15
lines changed

3 files changed

+121
-15
lines changed

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

+13
Original file line numberDiff line numberDiff line change
@@ -136,5 +136,18 @@ private WheelIndex(int label) {
136136
* we see.
137137
*/
138138
public static final int CAN_CODER_CAN_OFFSET = 8;
139+
140+
/**
141+
* PID Constants for the Pivot Motors
142+
* TODO: Find the PID Constants for the Pivot Motors.
143+
*/
144+
public static final double PIVOT_MOTOR_P = 0.1;
145+
public static final double PIVOT_MOTOR_I = 0;
146+
public static final double PIVOT_MOTOR_D = 0;
147+
148+
/**
149+
* We are assuming that we can assign CANCoders IDs just like we can assign
150+
* Spark Maxes IDs.
151+
*/
139152
}
140153
}

src/main/java/frc/robot/subsystems/DriveSubsystem.java

+95-15
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import java.util.ArrayList;
44
import java.util.Arrays;
55
import java.util.List;
6+
import java.util.function.BiConsumer;
67

78
import com.ctre.phoenix6.hardware.CANcoder;
89
import com.revrobotics.spark.SparkMax;
@@ -13,20 +14,22 @@
1314
import com.revrobotics.spark.config.SparkMaxConfig;
1415
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
1516

17+
import edu.wpi.first.math.controller.PIDController;
1618
import edu.wpi.first.math.kinematics.ChassisSpeeds;
1719
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
1820
import edu.wpi.first.math.kinematics.SwerveModuleState;
21+
import edu.wpi.first.util.sendable.SendableBuilder;
1922
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
2023
import edu.wpi.first.wpilibj.motorcontrol.PWMMotorController;
2124
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
2225
import edu.wpi.first.wpilibj2.command.SubsystemBase;
2326
import frc.robot.Constants;
2427
import frc.robot.Constants.*;
2528
import frc.robot.Constants.DriveConstants.DriveType;
29+
import frc.robot.Constants.DriveConstants.WheelIndex;
2630

2731
public class DriveSubsystem extends SubsystemBase {
2832

29-
3033
private InputSubsystem input;
3134
private double maxDriveSpeed;
3235
private double maxTurnSpeed;
@@ -80,6 +83,13 @@ public class DriveSubsystem extends SubsystemBase {
8083
12 // BACK_LEFT
8184
};
8285

86+
/**
87+
* PID controllers. We'll use four PID Controllers with the same constants
88+
* for each pivot motor. We'll use the CANCoder's absolute angle as the measurement.
89+
*/
90+
91+
private List<PIDController> pivotMotorPIDControllers;
92+
8393
/**
8494
* Intended to be owned by the RobotContainer and to be used by
8595
* RobotContainer's commands
@@ -154,6 +164,13 @@ public DriveSubsystem(InputSubsystem inputSubsystem, DriveType driveType) {
154164
new CANcoder(Constants.DriveConstants.CAN_CODER_CAN_OFFSET + BACK_RIGHT),
155165
new CANcoder(Constants.DriveConstants.CAN_CODER_CAN_OFFSET + BACK_LEFT)
156166
});
167+
168+
pivotMotorPIDControllers = Arrays.asList(new PIDController[] {
169+
new PIDController(Constants.DriveConstants.PIVOT_MOTOR_P, Constants.DriveConstants.PIVOT_MOTOR_I, Constants.DriveConstants.PIVOT_MOTOR_D),
170+
new PIDController(Constants.DriveConstants.PIVOT_MOTOR_P, Constants.DriveConstants.PIVOT_MOTOR_I, Constants.DriveConstants.PIVOT_MOTOR_D),
171+
new PIDController(Constants.DriveConstants.PIVOT_MOTOR_P, Constants.DriveConstants.PIVOT_MOTOR_I, Constants.DriveConstants.PIVOT_MOTOR_D),
172+
new PIDController(Constants.DriveConstants.PIVOT_MOTOR_P, Constants.DriveConstants.PIVOT_MOTOR_I, Constants.DriveConstants.PIVOT_MOTOR_D)
173+
});
157174
break;
158175
}
159176
}
@@ -172,6 +189,70 @@ private static double getConversionFactor() {
172189
return (2 * Math.PI * Constants.DriveConstants.SWERVE_MODULE_WHEEL_RADIUS_METERS) / 60;
173190
}
174191

192+
@FunctionalInterface
193+
public interface TriConsumer<T1,T2,T3> {
194+
public void accept(T1 t1, T2 t2, T3 t3);
195+
}
196+
197+
/**
198+
* Determines the set of values we'll send to and from the shuffleboard.
199+
* @param builder The object that will be used to send values to the shuffleboard.
200+
*/
201+
@Override
202+
public void initSendable(SendableBuilder builder) {
203+
TriConsumer<List<SparkMax>, String, WheelIndex> addMotorHelper = (motors, name, index) -> {
204+
builder.addDoubleProperty(name,
205+
() -> motors.get(index.label).get(),
206+
(speed) -> motors.get(index.label).set(speed));
207+
};
208+
builder.setSmartDashboardType(this.driveType.toString() == "DIFFERENTIAL_DRIVE" ? "DifferentialDrive" : "SwerveDrive");
209+
switch (driveType) {
210+
case DIFFERENTIAL_DRIVE:
211+
212+
// Add the differential drive motors to the shuffleboard.
213+
addMotorHelper.accept(differentialDriveMotors, "FR Motor", WheelIndex.FRONT_RIGHT);
214+
addMotorHelper.accept(differentialDriveMotors, "FL Motor", WheelIndex.FRONT_LEFT);
215+
addMotorHelper.accept(differentialDriveMotors, "BR Motor", WheelIndex.BACK_RIGHT);
216+
addMotorHelper.accept(differentialDriveMotors, "BL Motor", WheelIndex.BACK_LEFT);
217+
break;
218+
case SWERVE_DRIVE:
219+
220+
// Add the swerve drive motors to the shuffleboard.
221+
addMotorHelper.accept(swerveDriveMotors, "FR Drive", WheelIndex.FRONT_RIGHT);
222+
addMotorHelper.accept(swerveDriveMotors, "FL Drive", WheelIndex.FRONT_LEFT);
223+
addMotorHelper.accept(swerveDriveMotors, "BR Drive", WheelIndex.BACK_RIGHT);
224+
addMotorHelper.accept(swerveDriveMotors, "BL Drive", WheelIndex.BACK_LEFT);
225+
226+
// Add the swerve pivot motors to the shuffleboard.
227+
addMotorHelper.accept(swervePivotMotors, "FR Pivot", WheelIndex.FRONT_RIGHT);
228+
addMotorHelper.accept(swervePivotMotors, "FL Pivot", WheelIndex.FRONT_LEFT);
229+
addMotorHelper.accept(swervePivotMotors, "BR Pivot", WheelIndex.BACK_RIGHT);
230+
addMotorHelper.accept(swervePivotMotors, "BL Pivot", WheelIndex.BACK_LEFT);
231+
break;
232+
}
233+
builder.setActuator(true);
234+
builder.setSafeState(this::disable);
235+
super.initSendable(builder);
236+
}
237+
238+
/**
239+
* Calling this function removes the shuffleboard's ability to write values
240+
* to the motors. This is called by our sendable interface so that the only
241+
* time a shuffleboard live window can set motor speeds, is during test
242+
* mode.
243+
*/
244+
void disable() {
245+
switch (driveType) {
246+
case DIFFERENTIAL_DRIVE:
247+
differentialDriveMotors.forEach(SparkMax::disable);
248+
break;
249+
case SWERVE_DRIVE:
250+
swerveDriveMotors.forEach(SparkMax::disable);
251+
swervePivotMotors.forEach(SparkMax::disable);
252+
break;
253+
}
254+
}
255+
175256
/**
176257
* Update the position of the drive according to human input (during teleop)
177258
* or according to the current trajectory (during autonomous).
@@ -203,20 +284,19 @@ public void periodic() {
203284

204285
SwerveModuleState[] swerveStates = kinematics.toSwerveModuleStates(movement);
205286

206-
// Scenario: FRONT_LEFT swerve module
207-
// - It is currently facing at 90 degrees (so it points right.)
208-
// - According to human input, we need it to point at -45
209-
// degrees (45 degrees left of center).
210-
// - If we ASK the swerve module "what is your angle", the
211-
// RelativeEncoder will tell us "why, 21.82 degrees, of
212-
// course." Because since the robot turned on, the module has
213-
// rotated 21.82 degrees.
214-
// - PROBLEM: 21.82 does not equal 90.
215-
// * The swerve module is unaware of its own absolute angle.
216-
// * Only one entity holds that source of truth: the CANCoder.
217-
218-
// Solution.SEPEHR:
219-
// 1. Have a PID controller
287+
double[] CANCoderAngles = new double[4];
288+
for (int i = 0; i < 4; i++) {
289+
var temporary = swerveCANCODER.get(i).getAbsolutePosition();
290+
temporary.refresh();
291+
CANCoderAngles[i] = temporary.getValueAsDouble();
292+
}
293+
294+
// TODO: Use the CANCoder's measurements for the PID
295+
// controllers. We still don't have the idea of goal angles (our
296+
// setpoint) yet.
297+
//
298+
// Later, we should InItsendable to send our piviot angles to
299+
// the suffleboard for easier debugging.
220300

221301
break;
222302
default:

src/main/java/frc/robot/subsystems/InputSubsystem.java

+13
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
import edu.wpi.first.math.MathUtil;
44
import edu.wpi.first.math.filter.SlewRateLimiter;
5+
import edu.wpi.first.util.sendable.SendableBuilder;
56
import edu.wpi.first.wpilibj.Joystick;
67
import edu.wpi.first.wpilibj.Timer;
78
import edu.wpi.first.wpilibj.XboxController;
@@ -294,6 +295,18 @@ private boolean assignJoystick(Joystick j) {
294295
return success;
295296
}
296297

298+
/**
299+
* Writes the input values to the shuffleboard.
300+
*/
301+
@Override
302+
public void initSendable(SendableBuilder builder) {
303+
builder.setSmartDashboardType("InputSubsystem");
304+
builder.addDoubleProperty("Turn", this::getTurn, null);
305+
builder.addDoubleProperty("ForwardBack", this::getForwardBack, null);
306+
builder.addDoubleProperty("LeftRight", this::getLeftRight, null);
307+
// super.initSendable(builder);
308+
}
309+
297310
// TODO We need to call the controller check every few seconds during
298311
// periodic, and we need to combine the xbox controller, the main joystick,
299312
// and the secondary joystick into the 3 degrees of freedom: forward-back,

0 commit comments

Comments
 (0)