Skip to content

Commit 4e216b7

Browse files
author
Noah Andrews
authored
Merge pull request REVrobotics#5 from REVrobotics/cleanup
2 parents 1738f88 + 62d753a commit 4e216b7

File tree

2 files changed

+26
-15
lines changed

2 files changed

+26
-15
lines changed

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

Lines changed: 21 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -31,9 +31,9 @@ public static final class DriveConstants {
3131
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
3232

3333
// Chassis configuration
34-
public static final double kTrackWidth = Units.inchesToMeters(26.5);;
34+
public static final double kTrackWidth = Units.inchesToMeters(26.5);
3535
// Distance between centers of right and left wheels on robot
36-
public static final double kWheelBase = Units.inchesToMeters(26.5);;
36+
public static final double kWheelBase = Units.inchesToMeters(26.5);
3737
// Distance between front and back wheels on robot
3838
public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
3939
new Translation2d(kWheelBase / 2, kTrackWidth / 2),
@@ -62,21 +62,28 @@ public static final class DriveConstants {
6262
}
6363

6464
public static final class ModuleConstants {
65+
// The MAXSwerve module can be configured with one of three pinion gears: 12T, 13T, or 14T.
66+
// This changes the drive speed of the module (a pinion gear with more teeth will result in a
67+
// robot that drives faster).
68+
public static final int kDrivingMotorPinionTeeth = 14;
69+
70+
// Invert the turning encoder, since the output shaft rotates in the opposite direction of
71+
// the steering motor in the MAXSwerve Module.
6572
public static final boolean kTurningEncoderInverted = true;
6673

6774
// Calculations required for driving motor conversion factors and feed forward
68-
public static final double kPinionTeeth = 14; // Adjust this to match your configuration!
69-
public static final double kMotorFreeSpeed = 5676 / 60;
70-
public static final double kDrivingMotorReduction = 990 / (kPinionTeeth * 15);
75+
public static final double kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60;
7176
public static final double kWheelDiameterMeters = 0.0762;
7277
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
73-
public static final double kDriveTrainFreeSpeed = (kMotorFreeSpeed * kWheelCircumferenceMeters)
74-
/ kDrivingMotorReduction; // calculated motor free speed
78+
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
79+
public static final double kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15);
80+
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
81+
/ kDrivingMotorReduction;
7582

7683
public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math.PI)
77-
/ (double) kDrivingMotorReduction; // meters
84+
/ kDrivingMotorReduction; // meters
7885
public static final double kDrivingEncoderVelocityFactor = ((kWheelDiameterMeters * Math.PI)
79-
/ (double) kDrivingMotorReduction) / 60.0; // meters per second
86+
/ kDrivingMotorReduction) / 60.0; // meters per second
8087

8188
public static final double kTurningEncoderPositionFactor = (2 * Math.PI); // radians
8289
public static final double kTurningEncoderVelocityFactor = (2 * Math.PI) / 60.0; // radians per second
@@ -87,7 +94,7 @@ public static final class ModuleConstants {
8794
public static final double kDrivingP = 0.04;
8895
public static final double kDrivingI = 0;
8996
public static final double kDrivingD = 0;
90-
public static final double kDrivingFF = 1 / kDriveTrainFreeSpeed;
97+
public static final double kDrivingFF = 1 / kDriveWheelFreeSpeedRps;
9198
public static final double kDrivingMinOutput = -1;
9299
public static final double kDrivingMaxOutput = 1;
93100

@@ -123,4 +130,8 @@ public static final class AutoConstants {
123130
public static final TrapezoidProfile.Constraints kThetaControllerConstraints = new TrapezoidProfile.Constraints(
124131
kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
125132
}
133+
134+
public static final class NeoMotorConstants {
135+
public static final double kFreeSpeedRpm = 5676;
136+
}
126137
}

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

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ public MAXSwerveModule(int drivingCANId, int turningCANId, double chassisAngular
4040
m_drivingSparkMax = new CANSparkMax(drivingCANId, MotorType.kBrushless);
4141
m_turningSparkMax = new CANSparkMax(turningCANId, MotorType.kBrushless);
4242

43-
// Factory reset so we get the SPARKS MAX to a known state before configuring
43+
// Factory reset, so we get the SPARKS MAX to a known state before configuring
4444
// them. This is useful in case a SPARK MAX is swapped out.
4545
m_drivingSparkMax.restoreFactoryDefaults();
4646
m_turningSparkMax.restoreFactoryDefaults();
@@ -65,8 +65,8 @@ public MAXSwerveModule(int drivingCANId, int turningCANId, double chassisAngular
6565
m_turningEncoder.setPositionConversionFactor(ModuleConstants.kTurningEncoderPositionFactor);
6666
m_turningEncoder.setVelocityConversionFactor(ModuleConstants.kTurningEncoderVelocityFactor);
6767

68-
// Invert the turning encoder since the output shaft is inverse of the motor in
69-
// the MAXSwerve Module.
68+
// Invert the turning encoder, since the output shaft rotates in the opposite direction of
69+
// the steering motor in the MAXSwerve Module.
7070
m_turningEncoder.setInverted(ModuleConstants.kTurningEncoderInverted);
7171

7272
// Enable PID wrap around for the turning motor. This will allow the PID
@@ -77,7 +77,7 @@ public MAXSwerveModule(int drivingCANId, int turningCANId, double chassisAngular
7777
m_turningPIDController.setPositionPIDWrappingMinInput(ModuleConstants.kTurningEncoderPositionPIDMinInput);
7878
m_turningPIDController.setPositionPIDWrappingMaxInput(ModuleConstants.kTurningEncoderPositionPIDMaxInput);
7979

80-
// Set the PID gains for the driving motor. Note these are example gains and you
80+
// Set the PID gains for the driving motor. Note these are example gains, and you
8181
// may need to tune them for your own robot!
8282
m_drivingPIDController.setP(ModuleConstants.kDrivingP);
8383
m_drivingPIDController.setI(ModuleConstants.kDrivingI);
@@ -86,7 +86,7 @@ public MAXSwerveModule(int drivingCANId, int turningCANId, double chassisAngular
8686
m_drivingPIDController.setOutputRange(ModuleConstants.kDrivingMinOutput,
8787
ModuleConstants.kDrivingMaxOutput);
8888

89-
// Set the PID gains for the turning motor. Note these are example gains and you
89+
// Set the PID gains for the turning motor. Note these are example gains, and you
9090
// may need to tune them for your own robot!
9191
m_turningPIDController.setP(ModuleConstants.kTurningP);
9292
m_turningPIDController.setI(ModuleConstants.kTurningI);

0 commit comments

Comments
 (0)