14
14
import com .ctre .phoenix6 .signals .AbsoluteSensorRangeValue ;
15
15
import com .ctre .phoenix6 .signals .NeutralModeValue ;
16
16
import com .kauailabs .navx .frc .AHRS ;
17
+ import com .nrg948 .preferences .RobotPreferences ;
18
+ import com .nrg948 .preferences .RobotPreferencesLayout ;
19
+ import com .nrg948 .preferences .RobotPreferencesValue ;
17
20
import com .revrobotics .CANSparkMax ;
18
21
import com .revrobotics .CANSparkBase .IdleMode ;
19
22
import com .revrobotics .CANSparkLowLevel .MotorType ;
54
57
import frc .robot .util .SwerveModuleVelocities ;
55
58
import frc .robot .util .SwerveModuleVoltages ;
56
59
60
+ @ RobotPreferencesLayout (groupName = "Drive" , column = 0 , row = 1 , width = 2 , height = 3 )
57
61
public class SwerveSubsystem extends SubsystemBase {
58
-
59
- public static SwerveDriveParameters PARAMETERS = SwerveDriveParameters .RookieBase2023 ;
62
+ @ RobotPreferencesValue
63
+ public static RobotPreferences .EnumValue <SwerveDriveParameters > PARAMETERS =
64
+ new RobotPreferences .EnumValue <SwerveDriveParameters >("Drive" , "Robot Base" , SwerveDriveParameters .PracticeBase2024 );
60
65
61
66
public static boolean ENABLE_DRIVE_TAB = true ;
62
67
@@ -68,49 +73,49 @@ public class SwerveSubsystem extends SubsystemBase {
68
73
69
74
// 4 pairs of motors for drive & steering.
70
75
private final TalonFX frontLeftDriveMotor = new TalonFX (
71
- PARAMETERS .getMotorId (SwerveMotors .FrontLeftDrive ));
76
+ PARAMETERS .getValue (). getMotorId (SwerveMotors .FrontLeftDrive ));
72
77
private final CANSparkMax frontLeftSteeringMotor = new CANSparkMax (
73
- PARAMETERS .getMotorId (SwerveMotors .FrontLeftSteering ), MotorType .kBrushless );
78
+ PARAMETERS .getValue (). getMotorId (SwerveMotors .FrontLeftSteering ), MotorType .kBrushless );
74
79
75
80
private final TalonFX frontRightDriveMotor = new TalonFX (
76
- PARAMETERS .getMotorId (SwerveMotors .FrontRightDrive ));
81
+ PARAMETERS .getValue (). getMotorId (SwerveMotors .FrontRightDrive ));
77
82
private final CANSparkMax frontRightSteeringMotor = new CANSparkMax (
78
- PARAMETERS .getMotorId (SwerveMotors .FrontRightSteering ), MotorType .kBrushless );
83
+ PARAMETERS .getValue (). getMotorId (SwerveMotors .FrontRightSteering ), MotorType .kBrushless );
79
84
80
85
private final TalonFX backLeftDriveMotor = new TalonFX (
81
- PARAMETERS .getMotorId (SwerveMotors .BackLeftDrive ));
86
+ PARAMETERS .getValue (). getMotorId (SwerveMotors .BackLeftDrive ));
82
87
private final CANSparkMax backLeftSteeringMotor = new CANSparkMax (
83
- PARAMETERS .getMotorId (SwerveMotors .BackLeftSteering ), MotorType .kBrushless );
88
+ PARAMETERS .getValue (). getMotorId (SwerveMotors .BackLeftSteering ), MotorType .kBrushless );
84
89
85
90
private final TalonFX backRightDriveMotor = new TalonFX (
86
- PARAMETERS .getMotorId (SwerveMotors .BackRightDrive ));
91
+ PARAMETERS .getValue (). getMotorId (SwerveMotors .BackRightDrive ));
87
92
private final CANSparkMax backRightSteeringMotor = new CANSparkMax (
88
- PARAMETERS .getMotorId (SwerveMotors .BackRightSteering ), MotorType .kBrushless );
93
+ PARAMETERS .getValue (). getMotorId (SwerveMotors .BackRightSteering ), MotorType .kBrushless );
89
94
90
95
// 4 CANcoders for the steering angle.
91
96
private final CANcoder frontLeftAngle = new CANcoder (
92
- PARAMETERS .getAngleEncoderId (SwerveAngleEncoder .FrontLeft ));
97
+ PARAMETERS .getValue (). getAngleEncoderId (SwerveAngleEncoder .FrontLeft ));
93
98
private final CANcoder frontRightAngle = new CANcoder (
94
- PARAMETERS .getAngleEncoderId (SwerveAngleEncoder .FrontRight ));
99
+ PARAMETERS .getValue (). getAngleEncoderId (SwerveAngleEncoder .FrontRight ));
95
100
private final CANcoder backLeftAngle = new CANcoder (
96
- PARAMETERS .getAngleEncoderId (SwerveAngleEncoder .BackLeft ));
101
+ PARAMETERS .getValue (). getAngleEncoderId (SwerveAngleEncoder .BackLeft ));
97
102
private final CANcoder backRightAngle = new CANcoder (
98
- PARAMETERS .getAngleEncoderId (SwerveAngleEncoder .BackRight ));
103
+ PARAMETERS .getValue (). getAngleEncoderId (SwerveAngleEncoder .BackRight ));
99
104
100
105
private final SwerveModule frontLeftModule = createSwerveModule (
101
- frontLeftDriveMotor , frontLeftSteeringMotor , frontLeftAngle , PARAMETERS .getAngleOffset (SwerveAngleEncoder .FrontLeft ), "Front Left" );
106
+ frontLeftDriveMotor , frontLeftSteeringMotor , frontLeftAngle , PARAMETERS .getValue (). getAngleOffset (SwerveAngleEncoder .FrontLeft ), "Front Left" );
102
107
private final SwerveModule frontRightModule = createSwerveModule (
103
- frontRightDriveMotor , frontRightSteeringMotor , frontRightAngle ,PARAMETERS .getAngleOffset (SwerveAngleEncoder .FrontRight ), "Front Right" );
108
+ frontRightDriveMotor , frontRightSteeringMotor , frontRightAngle ,PARAMETERS .getValue (). getAngleOffset (SwerveAngleEncoder .FrontRight ), "Front Right" );
104
109
private final SwerveModule backLeftModule = createSwerveModule (
105
- backLeftDriveMotor , backLeftSteeringMotor , backLeftAngle , PARAMETERS .getAngleOffset (SwerveAngleEncoder .BackLeft ), "Back Left" );
110
+ backLeftDriveMotor , backLeftSteeringMotor , backLeftAngle , PARAMETERS .getValue (). getAngleOffset (SwerveAngleEncoder .BackLeft ), "Back Left" );
106
111
private final SwerveModule backRightModule = createSwerveModule (
107
- backRightDriveMotor , backRightSteeringMotor , backRightAngle , PARAMETERS .getAngleOffset (SwerveAngleEncoder .BackRight ), "Back Right" );
112
+ backRightDriveMotor , backRightSteeringMotor , backRightAngle , PARAMETERS .getValue (). getAngleOffset (SwerveAngleEncoder .BackRight ), "Back Right" );
108
113
109
114
private final SwerveModule [] modules = { frontLeftModule , frontRightModule , backLeftModule , backRightModule };
110
115
111
116
private final AHRS ahrs = new AHRS (SPI .Port .kMXP , NAVX_UPDATE_FREQUENCY_HZ );
112
117
113
- private final SwerveDriveKinematics kinematics = PARAMETERS .getKinematics ();
118
+ private final SwerveDriveKinematics kinematics = PARAMETERS .getValue (). getKinematics ();
114
119
115
120
private final SwerveDrive drivetrain ;
116
121
private final SwerveDrivePoseEstimator odometry ;
@@ -166,10 +171,10 @@ private static SwerveModule createSwerveModule(
166
171
wheelAngleConfig .MagnetSensor .MagnetOffset = angleOffset /360.0 ;
167
172
wheelAngleConfigurator .apply (wheelAngleConfig );
168
173
169
- final double metersPerRotation = (PARAMETERS .getWheelDiameter () * Math .PI ) / PARAMETERS .getDriveGearRatio ();
174
+ final double metersPerRotation = (PARAMETERS .getValue (). getWheelDiameter () * Math .PI ) / PARAMETERS . getValue () .getDriveGearRatio ();
170
175
171
176
return new SwerveModule (
172
- PARAMETERS ,
177
+ PARAMETERS . getValue () ,
173
178
driveMotor ,
174
179
() -> driveMotor .getPosition ().refresh ().getValueAsDouble () * metersPerRotation ,
175
180
// The TalonFX reports the velocity in pulses per 100ms, so we need to
@@ -187,7 +192,7 @@ public SwerveSubsystem() {
187
192
188
193
initializeSensorState ();
189
194
190
- drivetrain = new SwerveDrive (PARAMETERS , modules , () -> getOrientation ());
195
+ drivetrain = new SwerveDrive (PARAMETERS . getValue () , modules , () -> getOrientation ());
191
196
odometry = new SwerveDrivePoseEstimator (
192
197
kinematics , getOrientation (), drivetrain .getModulesPositions (), new Pose2d ());
193
198
}
@@ -234,7 +239,7 @@ private void updateSensorState() {
234
239
* @return The maximum drive speed.
235
240
*/
236
241
public double getMaxSpeed () {
237
- return PARAMETERS .getMaxDriveSpeed ();
242
+ return PARAMETERS .getValue (). getMaxDriveSpeed ();
238
243
}
239
244
240
245
/**
@@ -243,7 +248,7 @@ public double getMaxSpeed() {
243
248
* @return The maximum drive acceleration.
244
249
*/
245
250
public double getMaxAcceleration () {
246
- return PARAMETERS .getMaxDriveAcceleration ();
251
+ return PARAMETERS .getValue (). getMaxDriveAcceleration ();
247
252
}
248
253
249
254
/**
@@ -263,7 +268,7 @@ public SwerveDriveKinematics getKinematics() {
263
268
* swerve drive kinematics constraints when following a trajectory.
264
269
*/
265
270
public SwerveDriveKinematicsConstraint getKinematicsConstraint () {
266
- return PARAMETERS .getKinematicsConstraint ();
271
+ return PARAMETERS .getValue (). getKinematicsConstraint ();
267
272
}
268
273
269
274
/**
@@ -285,7 +290,7 @@ public TrapezoidProfile.Constraints getDriveConstraints() {
285
290
* the goal robot orientation.
286
291
*/
287
292
public TrapezoidProfile .Constraints getRotationalConstraints () {
288
- return PARAMETERS .getRotationalConstraints ();
293
+ return PARAMETERS .getValue (). getRotationalConstraints ();
289
294
}
290
295
291
296
/**
@@ -294,7 +299,7 @@ public TrapezoidProfile.Constraints getRotationalConstraints() {
294
299
* @return The wheel base radius in meters.
295
300
*/
296
301
public double getWheelBaseRadius (){
297
- return PARAMETERS .getWheelBaseRadius ();
302
+ return PARAMETERS .getValue (). getWheelBaseRadius ();
298
303
}
299
304
300
305
/**
@@ -504,7 +509,7 @@ public void periodic() {
504
509
505
510
ArrayList <Pose2d > modulePoses = new ArrayList <Pose2d >(4 );
506
511
507
- for (Translation2d wheelPosition : PARAMETERS .getWheelPositions ()) {
512
+ for (Translation2d wheelPosition : PARAMETERS .getValue (). getWheelPositions ()) {
508
513
modulePoses .add (
509
514
new Pose2d (
510
515
wheelPosition .rotateBy (robotPose .getRotation ())
0 commit comments