Skip to content

Commit 7b00d4c

Browse files
committed
Code celanup
1 parent f0431c4 commit 7b00d4c

File tree

9 files changed

+29
-21
lines changed

9 files changed

+29
-21
lines changed

src/main/java/org/lasarobotics/drive/SwervePoseEstimatorService.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -174,7 +174,7 @@ public SwervePoseEstimatorService(Matrix<N3,N1> odometryStdDev, IMU imu, SwerveM
174174
m_yawAngle = (isIMUConnected) ? m_imu.getRotation2d() :
175175
m_yawAngle.plus(new Rotation2d(m_kinematics.toTwist2d(moduleDeltas).dtheta));
176176
var yawRate = (isIMUConnected) ? m_imu.getYawRate() :
177-
Units.Radians.of(m_yawAngle.minus(previousYawAngle).getRadians()).divide(Units.Microseconds.of(m_currentTimestamp - m_previousTimestamp));
177+
Units.Radians.of(m_yawAngle.minus(previousYawAngle).getRadians()).div(Units.Microseconds.of(m_currentTimestamp - m_previousTimestamp));
178178

179179
// If no cameras or yaw rate is too high, just update pose based on odometry and exit
180180
if (m_cameras.isEmpty() || yawRate.gte(VISION_ANGULAR_VELOCITY_THRESHOLD)) {

src/main/java/org/lasarobotics/drive/TractionControlController.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ public TractionControlController(Dimensionless staticCoF,
9393
this.m_staticCoF = staticCoF.in(Units.Value);
9494
this.m_dynamicCoF = dynamicCoF.in(Units.Value);
9595
this.m_optimalSlipRatio = MathUtil.clamp(optimalSlipRatio.in(Units.Value), MIN_SLIP_RATIO, MAX_SLIP_RATIO);
96-
this.m_mass = mass.divide(4).in(Units.Kilograms);
96+
this.m_mass = mass.div(4).in(Units.Kilograms);
9797
this.m_maxLinearVelocity = Math.floor(maxLinearSpeed.in(Units.MetersPerSecond) * 1000) / 1000;
9898
this.m_maxAcceleration = m_staticCoF * Units.Gs.one().in(Units.MetersPerSecondPerSecond);
9999
this.m_maxPredictedSlipRatio = (m_maxAcceleration * GlobalConstants.ROBOT_LOOP_HZ.in(Units.Hertz))
@@ -154,7 +154,7 @@ & isEnabled()
154154

155155
// Get desired acceleration
156156
var desiredAcceleration = velocityRequest.minus(inertialVelocity.times(oppositeDirection ? -1 : +1))
157-
.divide(GlobalConstants.ROBOT_LOOP_HZ.asPeriod());
157+
.div(GlobalConstants.ROBOT_LOOP_HZ.asPeriod());
158158

159159
// Get sigmoid value
160160
double sigmoid = 1 / (1 + Math.exp(-SIGMOID_K * MathUtil.clamp(2 * (currentSlipRatio - m_optimalSlipRatio) - 1, -1.0, +1.0)));

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ public class DriveWheel {
1515
public final Dimensionless dynamicCoF;
1616

1717
private DriveWheel(Distance diameter, Dimensionless staticCoF, Dimensionless dynamicCoF) {
18-
this.radius = diameter.divide(2);
18+
this.radius = diameter.div(2);
1919
this.diameter = diameter;
2020
this.staticCoF = staticCoF;
2121
this.dynamicCoF = dynamicCoF;

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -410,8 +410,8 @@ protected void antiTip() {
410410
// Drive to counter tipping motion
411411
drive(
412412
ControlCentricity.ROBOT_CENTRIC,
413-
DRIVE_MAX_LINEAR_SPEED.divide(4).times(Math.cos(direction)),
414-
DRIVE_MAX_LINEAR_SPEED.divide(4).times(Math.sin(direction)),
413+
DRIVE_MAX_LINEAR_SPEED.div(4).times(Math.cos(direction)),
414+
DRIVE_MAX_LINEAR_SPEED.div(4).times(Math.sin(direction)),
415415
Units.DegreesPerSecond.of(0.0)
416416
);
417417
}

src/main/java/org/lasarobotics/hardware/generic/Analog.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ public static class AnalogInputs {
4646

4747
private ID m_id;
4848
private Frequency m_updateRate;
49-
private AnalogInputsAutoLogged m_inputs;
49+
private volatile AnalogInputsAutoLogged m_inputs;
5050

5151
/**
5252
* Create an Analog object
@@ -59,6 +59,7 @@ public Analog(Analog.ID id, Frequency updateRate) {
5959
this.m_inputs = new AnalogInputsAutoLogged();
6060

6161
// Update inputs on init
62+
updateInputs();
6263
periodic();
6364

6465
// Register device with manager
@@ -82,7 +83,6 @@ public Frequency getUpdateRate() {
8283
*/
8384
@Override
8485
protected void periodic() {
85-
updateInputs();
8686
Logger.processInputs(m_id.name, m_inputs);
8787
}
8888

@@ -92,7 +92,7 @@ protected void periodic() {
9292
*/
9393
@Override
9494
public AnalogInputsAutoLogged getInputs() {
95-
return m_inputs;
95+
synchronized (m_inputs) { return m_inputs; }
9696
}
9797

9898
@Override

src/main/java/org/lasarobotics/hardware/generic/Compressor.java

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
import org.lasarobotics.hardware.LoggableHardware;
88
import org.lasarobotics.hardware.PurpleManager;
99
import org.littletonrobotics.junction.AutoLog;
10+
import org.littletonrobotics.junction.Logger;
1011

1112
import edu.wpi.first.wpilibj.PneumaticsModuleType;
1213

@@ -41,7 +42,7 @@ public static class CompressorInputs {
4142
private edu.wpi.first.wpilibj.Compressor m_compressor;
4243

4344
private ID m_id;
44-
private CompressorInputsAutoLogged m_inputs;
45+
private volatile CompressorInputsAutoLogged m_inputs;
4546

4647
/**
4748
* Create a Compressor object with built-in logging
@@ -67,6 +68,13 @@ public Compressor(Compressor.ID id, int module) {
6768
public Compressor(Compressor.ID id) {
6869
this.m_id = id;
6970
this.m_compressor = new edu.wpi.first.wpilibj.Compressor(m_id.moduleType);
71+
72+
// Update inputs on init
73+
updateInputs();
74+
periodic();
75+
76+
// Register device with manager
77+
PurpleManager.add(this);
7078
}
7179

7280
/**
@@ -114,7 +122,7 @@ protected void updateInputs() {
114122
*/
115123
@Override
116124
protected void periodic() {
117-
updateInputs();
125+
Logger.processInputs(m_id.name, m_inputs);
118126
}
119127

120128
/**
@@ -123,7 +131,7 @@ protected void periodic() {
123131
*/
124132
@Override
125133
public CompressorInputsAutoLogged getInputs() {
126-
return m_inputs;
134+
synchronized (m_inputs) { return m_inputs; }
127135
}
128136

129137
/**

src/main/java/org/lasarobotics/hardware/generic/LimitSwitch.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ public static class LimitSwitchInputs {
6161
private ID m_id;
6262
private SwitchPolarity m_switchPolarity;
6363
private Frequency m_updateRate;
64-
private LimitSwitchInputsAutoLogged m_inputs;
64+
private volatile LimitSwitchInputsAutoLogged m_inputs;
6565

6666
/**
6767
* Create a limit switch object with built-in logging
@@ -77,6 +77,7 @@ public LimitSwitch(LimitSwitch.ID id, SwitchPolarity switchPolarity, Frequency u
7777
this.m_inputs = new LimitSwitchInputsAutoLogged();
7878

7979
// Update inputs on init
80+
updateInputs();
8081
periodic();
8182

8283
// Register device with manager
@@ -95,7 +96,6 @@ protected void updateInputs() {
9596
*/
9697
@Override
9798
protected void periodic() {
98-
updateInputs();
9999
Logger.processInputs(m_id.name, m_inputs);
100100
}
101101

@@ -110,7 +110,7 @@ public Frequency getUpdateRate() {
110110
*/
111111
@Override
112112
public LimitSwitchInputsAutoLogged getInputs() {
113-
return m_inputs;
113+
synchronized (m_inputs) { return m_inputs; }
114114
}
115115

116116
@Override

src/test/java/org/lasarobotics/drive/TractionControlTest.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ public void limitSlip() {
4545
var outputSpeed = Units.MetersPerSecond.of(100.0);
4646
for (int i = 0; i < GlobalConstants.ROBOT_LOOP_HZ.times(2).in(Units.Hertz); i++) {
4747
Timer.delay(GlobalConstants.ROBOT_LOOP_HZ.asPeriod().in(Units.Seconds));
48-
outputSpeed = m_tractionControlController.calculate(MAX_LINEAR_SPEED, Units.MetersPerSecond.of(0.0), MAX_LINEAR_SPEED.divide(2));
48+
outputSpeed = m_tractionControlController.calculate(MAX_LINEAR_SPEED, Units.MetersPerSecond.of(0.0), MAX_LINEAR_SPEED.div(2));
4949
}
5050

5151
// Verify behavior
@@ -86,7 +86,7 @@ public void disable() {
8686
m_tractionControlController.disableTractionControl();
8787

8888
// Simulate scenario
89-
var outputSpeed = m_tractionControlController.calculate(MAX_LINEAR_SPEED, Units.MetersPerSecond.of(0.0), MAX_LINEAR_SPEED.divide(2));
89+
var outputSpeed = m_tractionControlController.calculate(MAX_LINEAR_SPEED, Units.MetersPerSecond.of(0.0), MAX_LINEAR_SPEED.div(2));
9090

9191
// Verify behavior
9292
assertFalse(m_tractionControlController.isSlipping());

src/test/java/org/lasarobotics/drive/swerve/parent/REVSwerveModuleTest.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -204,10 +204,10 @@ public void setup() {
204204
@DisplayName("Test if module location is set correctly")
205205
public void moduleLocation() {
206206
// Check if all module locations are set
207-
assertEquals(new Translation2d(WHEELBASE.divide(+2), TRACK_WIDTH.divide(+2)), m_lFrontModule.getModuleCoordinate());
208-
assertEquals(new Translation2d(WHEELBASE.divide(+2), TRACK_WIDTH.divide(-2)), m_rFrontModule.getModuleCoordinate());
209-
assertEquals(new Translation2d(WHEELBASE.divide(-2), TRACK_WIDTH.divide(+2)), m_lRearModule.getModuleCoordinate());
210-
assertEquals(new Translation2d(WHEELBASE.divide(-2), TRACK_WIDTH.divide(-2)), m_rRearModule.getModuleCoordinate());
207+
assertEquals(new Translation2d(WHEELBASE.div(+2), TRACK_WIDTH.div(+2)), m_lFrontModule.getModuleCoordinate());
208+
assertEquals(new Translation2d(WHEELBASE.div(+2), TRACK_WIDTH.div(-2)), m_rFrontModule.getModuleCoordinate());
209+
assertEquals(new Translation2d(WHEELBASE.div(-2), TRACK_WIDTH.div(+2)), m_lRearModule.getModuleCoordinate());
210+
assertEquals(new Translation2d(WHEELBASE.div(-2), TRACK_WIDTH.div(-2)), m_rRearModule.getModuleCoordinate());
211211
}
212212

213213
@Test

0 commit comments

Comments
 (0)