@@ -31,9 +31,9 @@ public static final class DriveConstants {
31
31
public static final double kMaxAngularSpeed = 2 * Math .PI ; // radians per second
32
32
33
33
// Chassis configuration
34
- public static final double kTrackWidth = Units .inchesToMeters (26.5 );;
34
+ public static final double kTrackWidth = Units .inchesToMeters (26.5 );
35
35
// 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 );
37
37
// Distance between front and back wheels on robot
38
38
public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics (
39
39
new Translation2d (kWheelBase / 2 , kTrackWidth / 2 ),
@@ -62,21 +62,28 @@ public static final class DriveConstants {
62
62
}
63
63
64
64
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.
65
72
public static final boolean kTurningEncoderInverted = true ;
66
73
67
74
// 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 ;
71
76
public static final double kWheelDiameterMeters = 0.0762 ;
72
77
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 ;
75
82
76
83
public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math .PI )
77
- / ( double ) kDrivingMotorReduction ; // meters
84
+ / kDrivingMotorReduction ; // meters
78
85
public static final double kDrivingEncoderVelocityFactor = ((kWheelDiameterMeters * Math .PI )
79
- / ( double ) kDrivingMotorReduction ) / 60.0 ; // meters per second
86
+ / kDrivingMotorReduction ) / 60.0 ; // meters per second
80
87
81
88
public static final double kTurningEncoderPositionFactor = (2 * Math .PI ); // radians
82
89
public static final double kTurningEncoderVelocityFactor = (2 * Math .PI ) / 60.0 ; // radians per second
@@ -87,7 +94,7 @@ public static final class ModuleConstants {
87
94
public static final double kDrivingP = 0.04 ;
88
95
public static final double kDrivingI = 0 ;
89
96
public static final double kDrivingD = 0 ;
90
- public static final double kDrivingFF = 1 / kDriveTrainFreeSpeed ;
97
+ public static final double kDrivingFF = 1 / kDriveWheelFreeSpeedRps ;
91
98
public static final double kDrivingMinOutput = -1 ;
92
99
public static final double kDrivingMaxOutput = 1 ;
93
100
@@ -123,4 +130,8 @@ public static final class AutoConstants {
123
130
public static final TrapezoidProfile .Constraints kThetaControllerConstraints = new TrapezoidProfile .Constraints (
124
131
kMaxAngularSpeedRadiansPerSecond , kMaxAngularSpeedRadiansPerSecondSquared );
125
132
}
133
+
134
+ public static final class NeoMotorConstants {
135
+ public static final double kFreeSpeedRpm = 5676 ;
136
+ }
126
137
}
0 commit comments