Skip to content

Commit a3c0f0e

Browse files
Saiawe2024saiawe2021
authored andcommitted
Add Drive base Preferences
Co-Authored-By: pranavdasan
1 parent 8400252 commit a3c0f0e

File tree

4 files changed

+44
-28
lines changed

4 files changed

+44
-28
lines changed

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -178,4 +178,5 @@ logs/
178178
ctre_sim/
179179

180180
networktables.json
181+
networktables.json.bck
181182
simgui*.json

src/main/java/frc/robot/Robot.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,8 @@
44

55
package frc.robot;
66

7+
import com.nrg948.preferences.RobotPreferences;
8+
79
import edu.wpi.first.wpilibj.TimedRobot;
810
import edu.wpi.first.wpilibj2.command.Command;
911
import edu.wpi.first.wpilibj2.command.CommandScheduler;
@@ -25,6 +27,8 @@ public class Robot extends TimedRobot {
2527
*/
2628
@Override
2729
public void robotInit() {
30+
RobotPreferences.init("frc.robot");
31+
2832
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
2933
// autonomous chooser on the dashboard.
3034
m_robotContainer = new RobotContainer();

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

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,9 @@
44

55
package frc.robot;
66

7+
import com.nrg948.preferences.RobotPreferences;
8+
import com.nrg948.preferences.RobotPreferencesLayout;
9+
710
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
811
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
912
import edu.wpi.first.wpilibj2.command.Command;
@@ -23,6 +26,7 @@
2326
* the robot (including
2427
* subsystems, commands, and trigger mappings) should be declared here.
2528
*/
29+
@RobotPreferencesLayout(groupName = "Preferences", column = 0, row = 0, width = 2, height = 1)
2630
public class RobotContainer {
2731
// The robot's subsystems and commands are defined here...
2832
private final Subsystems m_subsystems = new Subsystems();
@@ -82,6 +86,8 @@ public void initShuffleboard(){
8286

8387
m_autonomous.addShuffleboardLayout(operatorTab);
8488

89+
RobotPreferences.addShuffleBoardTab();
90+
8591
m_subsystems.drivetrain.addShuffleboardTab();
8692
}
8793
}

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

Lines changed: 33 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,9 @@
1414
import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue;
1515
import com.ctre.phoenix6.signals.NeutralModeValue;
1616
import com.kauailabs.navx.frc.AHRS;
17+
import com.nrg948.preferences.RobotPreferences;
18+
import com.nrg948.preferences.RobotPreferencesLayout;
19+
import com.nrg948.preferences.RobotPreferencesValue;
1720
import com.revrobotics.CANSparkMax;
1821
import com.revrobotics.CANSparkBase.IdleMode;
1922
import com.revrobotics.CANSparkLowLevel.MotorType;
@@ -54,9 +57,11 @@
5457
import frc.robot.util.SwerveModuleVelocities;
5558
import frc.robot.util.SwerveModuleVoltages;
5659

60+
@RobotPreferencesLayout(groupName = "Drive", column = 0, row = 1, width = 2, height = 3)
5761
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);
6065

6166
public static boolean ENABLE_DRIVE_TAB = true;
6267

@@ -68,49 +73,49 @@ public class SwerveSubsystem extends SubsystemBase {
6873

6974
// 4 pairs of motors for drive & steering.
7075
private final TalonFX frontLeftDriveMotor = new TalonFX(
71-
PARAMETERS.getMotorId(SwerveMotors.FrontLeftDrive));
76+
PARAMETERS.getValue().getMotorId(SwerveMotors.FrontLeftDrive));
7277
private final CANSparkMax frontLeftSteeringMotor = new CANSparkMax(
73-
PARAMETERS.getMotorId(SwerveMotors.FrontLeftSteering), MotorType.kBrushless);
78+
PARAMETERS.getValue().getMotorId(SwerveMotors.FrontLeftSteering), MotorType.kBrushless);
7479

7580
private final TalonFX frontRightDriveMotor = new TalonFX(
76-
PARAMETERS.getMotorId(SwerveMotors.FrontRightDrive));
81+
PARAMETERS.getValue().getMotorId(SwerveMotors.FrontRightDrive));
7782
private final CANSparkMax frontRightSteeringMotor = new CANSparkMax(
78-
PARAMETERS.getMotorId(SwerveMotors.FrontRightSteering), MotorType.kBrushless);
83+
PARAMETERS.getValue().getMotorId(SwerveMotors.FrontRightSteering), MotorType.kBrushless);
7984

8085
private final TalonFX backLeftDriveMotor = new TalonFX(
81-
PARAMETERS.getMotorId(SwerveMotors.BackLeftDrive));
86+
PARAMETERS.getValue().getMotorId(SwerveMotors.BackLeftDrive));
8287
private final CANSparkMax backLeftSteeringMotor = new CANSparkMax(
83-
PARAMETERS.getMotorId(SwerveMotors.BackLeftSteering), MotorType.kBrushless);
88+
PARAMETERS.getValue().getMotorId(SwerveMotors.BackLeftSteering), MotorType.kBrushless);
8489

8590
private final TalonFX backRightDriveMotor = new TalonFX(
86-
PARAMETERS.getMotorId(SwerveMotors.BackRightDrive));
91+
PARAMETERS.getValue().getMotorId(SwerveMotors.BackRightDrive));
8792
private final CANSparkMax backRightSteeringMotor = new CANSparkMax(
88-
PARAMETERS.getMotorId(SwerveMotors.BackRightSteering), MotorType.kBrushless);
93+
PARAMETERS.getValue().getMotorId(SwerveMotors.BackRightSteering), MotorType.kBrushless);
8994

9095
// 4 CANcoders for the steering angle.
9196
private final CANcoder frontLeftAngle = new CANcoder(
92-
PARAMETERS.getAngleEncoderId(SwerveAngleEncoder.FrontLeft));
97+
PARAMETERS.getValue().getAngleEncoderId(SwerveAngleEncoder.FrontLeft));
9398
private final CANcoder frontRightAngle = new CANcoder(
94-
PARAMETERS.getAngleEncoderId(SwerveAngleEncoder.FrontRight));
99+
PARAMETERS.getValue().getAngleEncoderId(SwerveAngleEncoder.FrontRight));
95100
private final CANcoder backLeftAngle = new CANcoder(
96-
PARAMETERS.getAngleEncoderId(SwerveAngleEncoder.BackLeft));
101+
PARAMETERS.getValue().getAngleEncoderId(SwerveAngleEncoder.BackLeft));
97102
private final CANcoder backRightAngle = new CANcoder(
98-
PARAMETERS.getAngleEncoderId(SwerveAngleEncoder.BackRight));
103+
PARAMETERS.getValue().getAngleEncoderId(SwerveAngleEncoder.BackRight));
99104

100105
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");
102107
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");
104109
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");
106111
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");
108113

109114
private final SwerveModule[] modules = { frontLeftModule, frontRightModule, backLeftModule, backRightModule };
110115

111116
private final AHRS ahrs = new AHRS(SPI.Port.kMXP, NAVX_UPDATE_FREQUENCY_HZ);
112117

113-
private final SwerveDriveKinematics kinematics = PARAMETERS.getKinematics();
118+
private final SwerveDriveKinematics kinematics = PARAMETERS.getValue().getKinematics();
114119

115120
private final SwerveDrive drivetrain;
116121
private final SwerveDrivePoseEstimator odometry;
@@ -166,10 +171,10 @@ private static SwerveModule createSwerveModule(
166171
wheelAngleConfig.MagnetSensor.MagnetOffset = angleOffset/360.0;
167172
wheelAngleConfigurator.apply(wheelAngleConfig);
168173

169-
final double metersPerRotation = (PARAMETERS.getWheelDiameter() * Math.PI) / PARAMETERS.getDriveGearRatio();
174+
final double metersPerRotation = (PARAMETERS.getValue().getWheelDiameter() * Math.PI) / PARAMETERS.getValue().getDriveGearRatio();
170175

171176
return new SwerveModule(
172-
PARAMETERS,
177+
PARAMETERS.getValue(),
173178
driveMotor,
174179
() -> driveMotor.getPosition().refresh().getValueAsDouble() * metersPerRotation,
175180
// The TalonFX reports the velocity in pulses per 100ms, so we need to
@@ -187,7 +192,7 @@ public SwerveSubsystem() {
187192

188193
initializeSensorState();
189194

190-
drivetrain = new SwerveDrive(PARAMETERS, modules, () -> getOrientation());
195+
drivetrain = new SwerveDrive(PARAMETERS.getValue(), modules, () -> getOrientation());
191196
odometry = new SwerveDrivePoseEstimator(
192197
kinematics, getOrientation(), drivetrain.getModulesPositions(), new Pose2d());
193198
}
@@ -234,7 +239,7 @@ private void updateSensorState() {
234239
* @return The maximum drive speed.
235240
*/
236241
public double getMaxSpeed() {
237-
return PARAMETERS.getMaxDriveSpeed();
242+
return PARAMETERS.getValue().getMaxDriveSpeed();
238243
}
239244

240245
/**
@@ -243,7 +248,7 @@ public double getMaxSpeed() {
243248
* @return The maximum drive acceleration.
244249
*/
245250
public double getMaxAcceleration() {
246-
return PARAMETERS.getMaxDriveAcceleration();
251+
return PARAMETERS.getValue().getMaxDriveAcceleration();
247252
}
248253

249254
/**
@@ -263,7 +268,7 @@ public SwerveDriveKinematics getKinematics() {
263268
* swerve drive kinematics constraints when following a trajectory.
264269
*/
265270
public SwerveDriveKinematicsConstraint getKinematicsConstraint() {
266-
return PARAMETERS.getKinematicsConstraint();
271+
return PARAMETERS.getValue().getKinematicsConstraint();
267272
}
268273

269274
/**
@@ -285,7 +290,7 @@ public TrapezoidProfile.Constraints getDriveConstraints() {
285290
* the goal robot orientation.
286291
*/
287292
public TrapezoidProfile.Constraints getRotationalConstraints() {
288-
return PARAMETERS.getRotationalConstraints();
293+
return PARAMETERS.getValue().getRotationalConstraints();
289294
}
290295

291296
/**
@@ -294,7 +299,7 @@ public TrapezoidProfile.Constraints getRotationalConstraints() {
294299
* @return The wheel base radius in meters.
295300
*/
296301
public double getWheelBaseRadius(){
297-
return PARAMETERS.getWheelBaseRadius();
302+
return PARAMETERS.getValue().getWheelBaseRadius();
298303
}
299304

300305
/**
@@ -504,7 +509,7 @@ public void periodic() {
504509

505510
ArrayList<Pose2d> modulePoses = new ArrayList<Pose2d>(4);
506511

507-
for (Translation2d wheelPosition : PARAMETERS.getWheelPositions()) {
512+
for (Translation2d wheelPosition : PARAMETERS.getValue().getWheelPositions()) {
508513
modulePoses.add(
509514
new Pose2d(
510515
wheelPosition.rotateBy(robotPose.getRotation())

0 commit comments

Comments
 (0)