Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
31 changes: 21 additions & 10 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,9 @@ public static final class DriveConstants {
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second

// Chassis configuration
public static final double kTrackWidth = Units.inchesToMeters(26.5);;
public static final double kTrackWidth = Units.inchesToMeters(26.5);
// Distance between centers of right and left wheels on robot
public static final double kWheelBase = Units.inchesToMeters(26.5);;
public static final double kWheelBase = Units.inchesToMeters(26.5);
// Distance between front and back wheels on robot
public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
new Translation2d(kWheelBase / 2, kTrackWidth / 2),
Expand Down Expand Up @@ -62,21 +62,28 @@ public static final class DriveConstants {
}

public static final class ModuleConstants {
// The MAXSwerve module can be configured with one of three pinion gears: 12T, 13T, or 14T.
// This changes the drive speed of the module (a pinion gear with more teeth will result in a
// robot that drives faster).
public static final int kDrivingMotorPinionTeeth = 14;

// Invert the turning encoder, since the output shaft rotates in the opposite direction of
// the steering motor in the MAXSwerve Module.
public static final boolean kTurningEncoderInverted = true;

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

public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math.PI)
/ (double) kDrivingMotorReduction; // meters
/ kDrivingMotorReduction; // meters
public static final double kDrivingEncoderVelocityFactor = ((kWheelDiameterMeters * Math.PI)
/ (double) kDrivingMotorReduction) / 60.0; // meters per second
/ kDrivingMotorReduction) / 60.0; // meters per second

public static final double kTurningEncoderPositionFactor = (2 * Math.PI); // radians
public static final double kTurningEncoderVelocityFactor = (2 * Math.PI) / 60.0; // radians per second
Expand All @@ -87,7 +94,7 @@ public static final class ModuleConstants {
public static final double kDrivingP = 0.04;
public static final double kDrivingI = 0;
public static final double kDrivingD = 0;
public static final double kDrivingFF = 1 / kDriveTrainFreeSpeed;
public static final double kDrivingFF = 1 / kDriveWheelFreeSpeedRps;
public static final double kDrivingMinOutput = -1;
public static final double kDrivingMaxOutput = 1;

Expand Down Expand Up @@ -123,4 +130,8 @@ public static final class AutoConstants {
public static final TrapezoidProfile.Constraints kThetaControllerConstraints = new TrapezoidProfile.Constraints(
kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
}

public static final class NeoMotorConstants {
public static final double kFreeSpeedRpm = 5676;
}
}
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/subsystems/MAXSwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ public MAXSwerveModule(int drivingCANId, int turningCANId, double chassisAngular
m_drivingSparkMax = new CANSparkMax(drivingCANId, MotorType.kBrushless);
m_turningSparkMax = new CANSparkMax(turningCANId, MotorType.kBrushless);

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

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

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

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

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