Skip to content

Commit 8832d4d

Browse files
committed
Log odometry in parent class
1 parent dc4c820 commit 8832d4d

File tree

3 files changed

+17
-7
lines changed

3 files changed

+17
-7
lines changed

src/main/java/org/lasarobotics/drive/swerve/SwerveModule.java

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313

1414
import org.apache.commons.math3.geometry.euclidean.twod.Vector2D;
1515
import org.lasarobotics.drive.TractionControlController;
16+
import org.littletonrobotics.junction.Logger;
1617

1718
import edu.wpi.first.math.geometry.Rotation2d;
1819
import edu.wpi.first.math.geometry.Translation2d;
@@ -73,8 +74,11 @@ public Rotation2d getLockPosition() {
7374
}
7475
}
7576

77+
private static final String ODOMETER_LOG_ENTRY = "/Odometer";
78+
7679
private double m_runningOdometer;
7780
private String m_odometerOutputPath;
81+
private String m_driveMotorName;
7882

7983
private Location m_location;
8084
private GearRatio m_gearRatio;
@@ -98,6 +102,7 @@ public SwerveModule(Location location,
98102
this.m_driveWheel = driveWheel;
99103
this.m_zeroOffset = new Rotation2d(zeroOffset);
100104
this.m_runningOdometer = 0.0;
105+
this.m_driveMotorName = driveMotorName;
101106
this.m_autoLock = true;
102107
COSINE_CORRECTION = RobotBase.isReal() ? 1 : 0;
103108

@@ -263,6 +268,15 @@ protected SwerveModuleState getDesiredState(SwerveModuleState requestedState, Ro
263268
return desiredState;
264269
}
265270

271+
/**
272+
* Log outputs
273+
* <p>
274+
* Call this in child class
275+
*/
276+
protected void logOutputs() {
277+
Logger.recordOutput(m_driveMotorName + ODOMETER_LOG_ENTRY, m_runningOdometer);
278+
}
279+
266280
/**
267281
* Get drive wheel installed on module
268282
* @return Drive wheel

src/main/java/org/lasarobotics/drive/swerve/parent/CTRESwerveModule.java

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,6 @@ public Hardware(TalonFX driveMotor, TalonFX rotateMotor, CANcoder canCoder) {
7676
private final Current ROTATE_MOTOR_CURRENT_LIMIT = Units.Amps.of(20.0);
7777

7878
private static final String IS_SLIPPING_LOG_ENTRY = "/IsSlipping";
79-
private static final String ODOMETER_LOG_ENTRY = "/Odometer";
8079
private static final String ROTATE_ERROR_LOG_ENTRY = "/RotateError";
8180
private static final String MAX_LINEAR_VELOCITY_LOG_ENTRY = "/MaxLinearVelocity";
8281
private static final double MAX_AUTO_LOCK_TIME = 10.0;
@@ -104,7 +103,6 @@ public Hardware(TalonFX driveMotor, TalonFX rotateMotor, CANcoder canCoder) {
104103
private SwerveModule.GearRatio m_gearRatio;
105104
private double m_driveConversionFactor;
106105
private double m_autoLockTime;
107-
private double m_runningOdometer;
108106
private final boolean m_isPhoenixPro;
109107

110108
private Instant m_autoLockTimer;
@@ -172,7 +170,6 @@ public CTRESwerveModule(Hardware swerveHardware,
172170
this.m_autoLockTime = MathUtil.clamp(autoLockTime.in(Units.Milliseconds), 0.0, MAX_AUTO_LOCK_TIME * 1000);
173171
this.m_previousRotatePosition = m_zeroOffset.plus(m_location.getLockPosition());
174172
this.m_autoLockTimer = Instant.now();
175-
this.m_runningOdometer = 0.0;
176173
this.m_rotatePositionSetter = new PositionVoltage(Units.Radians.zero());
177174
this.m_driveVelocitySetter = new VelocityVoltage(Units.RotationsPerSecond.zero());
178175

@@ -328,8 +325,8 @@ private AngularVelocity linearToAngularVelocity(LinearVelocity velocity) {
328325
* Call this method periodically
329326
*/
330327
private void periodic() {
328+
super.logOutputs();
331329
Logger.recordOutput(m_driveMotor.getID().name + IS_SLIPPING_LOG_ENTRY, isSlipping());
332-
Logger.recordOutput(m_driveMotor.getID().name + ODOMETER_LOG_ENTRY, m_runningOdometer);
333330
Logger.recordOutput(m_rotateMotor.getID().name + ROTATE_ERROR_LOG_ENTRY, m_desiredState.angle.minus(Rotation2d.fromRadians(m_rotateMotor.getInputs().selectedSensorPosition.in(Units.Radians))));
334331
}
335332

@@ -498,7 +495,7 @@ public void set(SwerveModuleState state) {
498495
m_previousRotatePosition = m_desiredState.angle;
499496

500497
// 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));
502499
}
503500

504501
@Override

src/main/java/org/lasarobotics/drive/swerve/parent/REVSwerveModule.java

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,6 @@ public Hardware(Spark driveMotor, Spark rotateMotor) {
7373
private final Current ROTATE_MOTOR_CURRENT_LIMIT = Units.Amps.of(20.0);
7474

7575
private static final String IS_SLIPPING_LOG_ENTRY = "/IsSlipping";
76-
private static final String ODOMETER_LOG_ENTRY = "/Odometer";
7776
private static final String ROTATE_ERROR_LOG_ENTRY = "/RotateError";
7877
private static final String MAX_LINEAR_VELOCITY_LOG_ENTRY = "/MaxLinearVelocity";
7978
private static final double MAX_AUTO_LOCK_TIME = 10.0;
@@ -280,8 +279,8 @@ void updateSimPosition() {
280279
* Call this method periodically
281280
*/
282281
private void periodic() {
282+
super.logOutputs();
283283
Logger.recordOutput(m_driveMotor.getID().name + IS_SLIPPING_LOG_ENTRY, isSlipping());
284-
Logger.recordOutput(m_driveMotor.getID().name + ODOMETER_LOG_ENTRY, getRunningOdometer());
285284
Logger.recordOutput(m_rotateMotor.getID().name + ROTATE_ERROR_LOG_ENTRY, m_desiredState.angle.minus(Rotation2d.fromRadians(m_rotateMotor.getInputs().absoluteEncoderPosition)));
286285
}
287286

0 commit comments

Comments
 (0)