Skip to content
This repository has been archived by the owner on Jan 13, 2025. It is now read-only.

Commit

Permalink
Fixes to BearSwerve sim
Browse files Browse the repository at this point in the history
  • Loading branch information
rcahoon committed Nov 2, 2024
1 parent 0f2d73b commit 1ef8599
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,7 @@ public void modelReset(Pose2d pose) {
* @param dtSeconds size of the discrete step to take
*/
public void update(double dtSeconds) {
if (dtSeconds == 0.0) return;

Pose2d fieldRF = new Pose2d(); // global origin
Transform2d fieldToRobot = new Transform2d(fieldRF, m_curPose);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,9 @@ public class SwerveModuleSim {
private SimpleMotorWithMassModel m_azmthMotor;
private MotorGearboxWheelSim m_wheelMotor;

private final double m_azimuthEncGearRatio; //Motor-to-azimuth-encoder reduction
private final double m_wheelEncGearRatio; //Motor-to-wheel-encoder reduction
private final double m_azimuthEncGearRatio; //Encoder-to-azimuth reduction
private final double m_azimuthMotorGearRatio; //Motor-to-azimuth reduction
private final double m_wheelEncGearRatio; //Encoder-to-wheel reduction
private final double m_treadStaticFricForce;
private final double m_treadKineticFricForce;
//TODO - make the "how much grease" factor configurable?
Expand Down Expand Up @@ -72,6 +73,7 @@ public SwerveModuleSim(
m_wheelGearboxLossFactor);

this.m_azimuthEncGearRatio = azimuthEncGearRatio;
this.m_azimuthMotorGearRatio = azimuthGearRatio;
this.m_wheelEncGearRatio = wheelEncGearRatio;
this.m_treadStaticFricForce = treadStaticCoefFric * moduleNormalForce;
this.m_treadKineticFricForce = treadKineticCoefFric * moduleNormalForce;
Expand Down Expand Up @@ -109,19 +111,19 @@ public double getWheelEncoderPositionRev() {
}

public double getAzimuthMotorPositionRev(){
return m_azmthMotor.getMechanismPositionRev();
return m_azmthMotor.getMechanismPositionRev() * m_azimuthMotorGearRatio;
}

public double getAzimuthMotorVelocityRPM(){
return m_azmthMotor.getMechanismSpeed_RPM();
return m_azmthMotor.getMechanismSpeed_RPM() * m_azimuthMotorGearRatio;
}

public double getAzimuthEncoderVelocityRPM(){
return m_azmthMotor.getMechanismSpeed_RPM() * m_azimuthEncGearRatio;
}

public double getWheelEncoderVelocityRPM(){
return m_azmthMotor.getMechanismSpeed_RPM() * m_wheelEncGearRatio;
return m_wheelMotor.getWheelSpeed_RPM() * m_wheelEncGearRatio;
}

void reset(Pose2d initModulePose) {
Expand Down

0 comments on commit 1ef8599

Please sign in to comment.