Skip to content

Commit e717f12

Browse files
author
NoahAndrews
committed
Document free speed units, clarify which motors are being discussed
1 parent 246230c commit e717f12

1 file changed

Lines changed: 4 additions & 4 deletions

File tree

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

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -68,12 +68,12 @@ public static final class ModuleConstants {
6868

6969
// Calculations required for driving motor conversion factors and feed forward
7070
public static final double kPinionTeeth = 14; // Adjust this to match your configuration!
71-
public static final double kMotorFreeSpeed = 5676 / 60;
71+
public static final double kDrivingMotorFreeSpeedRps = 5676 / 60;
7272
public static final double kDrivingMotorReduction = 990 / (kPinionTeeth * 15);
7373
public static final double kWheelDiameterMeters = 0.0762;
7474
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
75-
public static final double kDriveTrainFreeSpeed = (kMotorFreeSpeed * kWheelCircumferenceMeters)
76-
/ kDrivingMotorReduction; // calculated motor free speed
75+
public static final double kDriveTrainFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
76+
/ kDrivingMotorReduction; // calculated from the motor free speed
7777

7878
public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math.PI)
7979
/ kDrivingMotorReduction; // meters
@@ -89,7 +89,7 @@ public static final class ModuleConstants {
8989
public static final double kDrivingP = 0.04;
9090
public static final double kDrivingI = 0;
9191
public static final double kDrivingD = 0;
92-
public static final double kDrivingFF = 1 / kDriveTrainFreeSpeed;
92+
public static final double kDrivingFF = 1 / kDriveTrainFreeSpeedRps;
9393
public static final double kDrivingMinOutput = -1;
9494
public static final double kDrivingMaxOutput = 1;
9595

0 commit comments

Comments
 (0)