Skip to content

Commit

Permalink
Improve sim behavior
Browse files Browse the repository at this point in the history
I forgot that the DCMotorSim objects were modeling the motor shaft rotations, not the output shaft. This caused the CANCoder position to rotate ~26 times faster than they should've, leading to instability.
  • Loading branch information
Gold856 committed Jan 27, 2025
1 parent 0e6c228 commit f3b82d7
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 9 deletions.
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,12 @@ public static final class DriveConstants {

public static final double kTeleopMaxVoltage = 12;
public static final double kTeleopMaxTurnVoltage = 7.2;
public static final double kGearRatio = 6.12;
public static final double kDriveGearRatio = 6.12;
public static final double kSteerGearRatio = 150.0 / 7;
public static final double kWheelDiameter = Units.inchesToMeters(4);
public static final double kWheelCircumference = Math.PI * kWheelDiameter;

public static final double kMetersPerMotorRotation = kWheelCircumference / kGearRatio;
public static final double kMetersPerMotorRotation = kWheelCircumference / kDriveGearRatio;

// https://docs.wpilib.org/en/latest/docs/software/basic-programming/coordinate-system.html
public static final Translation2d kFrontLeftLocation = new Translation2d(0.381, 0.381);
Expand Down
13 changes: 6 additions & 7 deletions src/main/java/frc/robot/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,9 @@ public SwerveModule(int canId, int drivePort, int steerPort) {
if (RobotBase.isSimulation()) {
m_driveMotorModel = new DCMotorSim(
LinearSystemId.createDCMotorSystem(kV / (2 * Math.PI), kA / (2 * Math.PI)),
DCMotor.getKrakenX60(1).withReduction(kGearRatio));
DCMotor.getKrakenX60(1).withReduction(kDriveGearRatio));
m_steerMotorModel = new DCMotorSim(
LinearSystemId.createDCMotorSystem(kV / (2 * Math.PI), 0.0001 / (2 * Math.PI)),
LinearSystemId.createDCMotorSystem(kV / (2 * Math.PI), kA / (2 * Math.PI)),
DCMotor.getKrakenX60(1));
} else {
m_driveMotorModel = null;
Expand Down Expand Up @@ -155,14 +155,13 @@ private void updateSim() {
m_driveMotorModel.update(0.02);
driveMotorState.setRotorVelocity(m_driveMotorModel.getAngularVelocityRPM() / 60);
driveMotorState.setRawRotorPosition(m_driveMotorModel.getAngularPositionRotations());

var encoderSimState = m_CANCoder.getSimState();
// These used to be CAN IDs, but apparently any other value causes complete
// destabilization of the swerve sim. Do not touch.
m_steerMotorSim.iterate(30, 32, 0.02);
m_steerMotorModel.setInputVoltage(m_steerMotorSim.getAppliedOutput() * 12);
m_steerMotorModel.update(0.02);
encoderSimState.setRawPosition(m_steerMotorModel.getAngularPositionRotations());
encoderSimState.setVelocity(m_steerMotorModel.getAngularVelocityRPM());
m_steerMotorSim.iterate(m_steerMotorModel.getAngularVelocityRPM(), 12, 0.02);
encoderSimState.setRawPosition(m_steerMotorModel.getAngularPositionRotations() / kSteerGearRatio);
encoderSimState.setVelocity(m_steerMotorModel.getAngularVelocityRPM() / 60 / kSteerGearRatio);
}
}
}

0 comments on commit f3b82d7

Please sign in to comment.