@@ -76,7 +76,6 @@ public Hardware(TalonFX driveMotor, TalonFX rotateMotor, CANcoder canCoder) {
76
76
private final Current ROTATE_MOTOR_CURRENT_LIMIT = Units .Amps .of (20.0 );
77
77
78
78
private static final String IS_SLIPPING_LOG_ENTRY = "/IsSlipping" ;
79
- private static final String ODOMETER_LOG_ENTRY = "/Odometer" ;
80
79
private static final String ROTATE_ERROR_LOG_ENTRY = "/RotateError" ;
81
80
private static final String MAX_LINEAR_VELOCITY_LOG_ENTRY = "/MaxLinearVelocity" ;
82
81
private static final double MAX_AUTO_LOCK_TIME = 10.0 ;
@@ -104,7 +103,6 @@ public Hardware(TalonFX driveMotor, TalonFX rotateMotor, CANcoder canCoder) {
104
103
private SwerveModule .GearRatio m_gearRatio ;
105
104
private double m_driveConversionFactor ;
106
105
private double m_autoLockTime ;
107
- private double m_runningOdometer ;
108
106
private final boolean m_isPhoenixPro ;
109
107
110
108
private Instant m_autoLockTimer ;
@@ -172,7 +170,6 @@ public CTRESwerveModule(Hardware swerveHardware,
172
170
this .m_autoLockTime = MathUtil .clamp (autoLockTime .in (Units .Milliseconds ), 0.0 , MAX_AUTO_LOCK_TIME * 1000 );
173
171
this .m_previousRotatePosition = m_zeroOffset .plus (m_location .getLockPosition ());
174
172
this .m_autoLockTimer = Instant .now ();
175
- this .m_runningOdometer = 0.0 ;
176
173
this .m_rotatePositionSetter = new PositionVoltage (Units .Radians .zero ());
177
174
this .m_driveVelocitySetter = new VelocityVoltage (Units .RotationsPerSecond .zero ());
178
175
@@ -328,8 +325,8 @@ private AngularVelocity linearToAngularVelocity(LinearVelocity velocity) {
328
325
* Call this method periodically
329
326
*/
330
327
private void periodic () {
328
+ super .logOutputs ();
331
329
Logger .recordOutput (m_driveMotor .getID ().name + IS_SLIPPING_LOG_ENTRY , isSlipping ());
332
- Logger .recordOutput (m_driveMotor .getID ().name + ODOMETER_LOG_ENTRY , m_runningOdometer );
333
330
Logger .recordOutput (m_rotateMotor .getID ().name + ROTATE_ERROR_LOG_ENTRY , m_desiredState .angle .minus (Rotation2d .fromRadians (m_rotateMotor .getInputs ().selectedSensorPosition .in (Units .Radians ))));
334
331
}
335
332
@@ -498,7 +495,7 @@ public void set(SwerveModuleState state) {
498
495
m_previousRotatePosition = m_desiredState .angle ;
499
496
500
497
// Increment odometer
501
- m_runningOdometer += Math .abs (m_desiredState .speedMetersPerSecond ) * GlobalConstants .ROBOT_LOOP_HZ .asPeriod ().in (Units .Seconds );
498
+ super . incrementOdometer ( Math .abs (m_desiredState .speedMetersPerSecond ) * GlobalConstants .ROBOT_LOOP_HZ .asPeriod ().in (Units .Seconds ) );
502
499
}
503
500
504
501
@ Override
0 commit comments