Skip to content

Commit c797e4f

Browse files
committed
refactor: rename phoenixTimeSyncSignalRefresher to odometrySignalRefresher
1 parent d2ab399 commit c797e4f

File tree

5 files changed

+17
-21
lines changed

5 files changed

+17
-21
lines changed

src/main/java/org/team1540/robot2024/Robot.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,7 @@ public void robotPeriodic() {
8989
// This must be called from the robot's periodic block in order for anything in
9090
// the Command-based framework to work.
9191
CommandScheduler.getInstance().run();
92-
if (Constants.currentMode == Constants.Mode.REAL) robotContainer.timeSyncSignalRefresher.periodic();
92+
if (Constants.currentMode == Constants.Mode.REAL) robotContainer.odometrySignalRefresher.periodic();
9393
}
9494

9595
/**

src/main/java/org/team1540/robot2024/RobotContainer.java

+6-6
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ public class RobotContainer {
3838
// Dashboard inputs
3939
public final LoggedDashboardChooser<Command> autoChooser;
4040

41-
public final PhoenixTimeSyncSignalRefresher timeSyncSignalRefresher = new PhoenixTimeSyncSignalRefresher(SwerveConfig.CAN_BUS);
41+
public final PhoenixTimeSyncSignalRefresher odometrySignalRefresher = new PhoenixTimeSyncSignalRefresher(SwerveConfig.CAN_BUS);
4242

4343
// TODO: testing dashboard inputs, remove for comp
4444
public final LoggedDashboardNumber leftFlywheelSetpoint = new LoggedDashboardNumber("Shooter/Flywheels/leftSetpoint", 6000);
@@ -53,11 +53,11 @@ public RobotContainer() {
5353
// Real robot, instantiate hardware IO implementations
5454
drivetrain =
5555
new Drivetrain(
56-
new GyroIOPigeon2(timeSyncSignalRefresher),
57-
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.FRONT_LEFT, SwerveFactory.SwerveCorner.FRONT_LEFT), timeSyncSignalRefresher),
58-
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.FRONT_RIGHT, SwerveFactory.SwerveCorner.FRONT_RIGHT), timeSyncSignalRefresher),
59-
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.BACK_LEFT, SwerveFactory.SwerveCorner.BACK_LEFT), timeSyncSignalRefresher),
60-
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.BACK_RIGHT, SwerveFactory.SwerveCorner.BACK_RIGHT), timeSyncSignalRefresher));
56+
new GyroIOPigeon2(odometrySignalRefresher),
57+
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.FRONT_LEFT, SwerveFactory.SwerveCorner.FRONT_LEFT), odometrySignalRefresher),
58+
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.FRONT_RIGHT, SwerveFactory.SwerveCorner.FRONT_RIGHT), odometrySignalRefresher),
59+
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.BACK_LEFT, SwerveFactory.SwerveCorner.BACK_LEFT), odometrySignalRefresher),
60+
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(SwerveConfig.BACK_RIGHT, SwerveFactory.SwerveCorner.BACK_RIGHT), odometrySignalRefresher));
6161
shooter = new Shooter(new ShooterPivotIOTalonFX(), new FlywheelsIOTalonFX());
6262
break;
6363

src/main/java/org/team1540/robot2024/subsystems/drive/GyroIOPigeon2.java

+5-5
Original file line numberDiff line numberDiff line change
@@ -18,22 +18,22 @@ public class GyroIOPigeon2 implements GyroIO {
1818
private final StatusSignal<Double> yaw = pigeon.getYaw();
1919
private final StatusSignal<Double> yawVelocity = pigeon.getAngularVelocityZDevice();
2020

21-
private final PhoenixTimeSyncSignalRefresher timeSyncSignalRefresher;
21+
private final PhoenixTimeSyncSignalRefresher odometrySignalRefresher;
2222

23-
public GyroIOPigeon2(PhoenixTimeSyncSignalRefresher timeSyncSignalRefresher) {
23+
public GyroIOPigeon2(PhoenixTimeSyncSignalRefresher odometrySignalRefresher) {
2424
pigeon.getConfigurator().apply(new Pigeon2Configuration());
2525
pigeon.getConfigurator().setYaw(0.0);
2626
yaw.setUpdateFrequency(100.0);
2727
yawVelocity.setUpdateFrequency(100.0);
2828
pigeon.optimizeBusUtilization();
2929

30-
this.timeSyncSignalRefresher = timeSyncSignalRefresher;
31-
timeSyncSignalRefresher.registerSignals(yaw, yawVelocity);
30+
this.odometrySignalRefresher = odometrySignalRefresher;
31+
odometrySignalRefresher.registerSignals(yaw, yawVelocity);
3232
}
3333

3434
@Override
3535
public void updateInputs(GyroIOInputs inputs) {
36-
timeSyncSignalRefresher.refreshSignals();
36+
odometrySignalRefresher.refreshSignals();
3737
inputs.connected = BaseStatusSignal.isAllGood(yaw, yawVelocity);
3838
inputs.yawPosition = Rotation2d.fromDegrees(yaw.getValueAsDouble());
3939
inputs.yawVelocityRadPerSec = Units.degreesToRadians(yawVelocity.getValueAsDouble());

src/main/java/org/team1540/robot2024/subsystems/drive/ModuleIOTalonFX.java

+5-5
Original file line numberDiff line numberDiff line change
@@ -43,9 +43,9 @@ public class ModuleIOTalonFX implements ModuleIO {
4343
private final StatusSignal<Double> turnAppliedVolts;
4444
private final StatusSignal<Double> turnCurrent;
4545

46-
private final PhoenixTimeSyncSignalRefresher timeSyncSignalRefresher;
46+
private final PhoenixTimeSyncSignalRefresher odometrySignalRefresher;
4747

48-
public ModuleIOTalonFX(SwerveFactory.SwerveModuleHW hw, PhoenixTimeSyncSignalRefresher timeSyncSignalRefresher) {
48+
public ModuleIOTalonFX(SwerveFactory.SwerveModuleHW hw, PhoenixTimeSyncSignalRefresher odometrySignalRefresher) {
4949
driveTalon = hw.driveMotor;
5050
turnTalon = hw.turnMotor;
5151
cancoder = hw.cancoder;
@@ -77,14 +77,14 @@ public ModuleIOTalonFX(SwerveFactory.SwerveModuleHW hw, PhoenixTimeSyncSignalRef
7777
driveTalon.optimizeBusUtilization();
7878
turnTalon.optimizeBusUtilization();
7979

80-
this.timeSyncSignalRefresher = timeSyncSignalRefresher;
80+
this.odometrySignalRefresher = odometrySignalRefresher;
8181

82-
timeSyncSignalRefresher.registerSignals(drivePosition, turnPosition);
82+
odometrySignalRefresher.registerSignals(drivePosition, turnPosition);
8383
}
8484

8585
@Override
8686
public void updateInputs(ModuleIOInputs inputs) {
87-
timeSyncSignalRefresher.refreshSignals();
87+
odometrySignalRefresher.refreshSignals();
8888
BaseStatusSignal.refreshAll(
8989
driveVelocity,
9090
driveAppliedVolts,

src/main/java/org/team1540/robot2024/util/PhoenixTimeSyncSignalRefresher.java

-4
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,9 @@
44
import com.ctre.phoenix6.CANBus;
55
import com.ctre.phoenix6.StatusCode;
66
import edu.wpi.first.wpilibj.DriverStation;
7-
import edu.wpi.first.wpilibj.Timer;
8-
import org.team1540.robot2024.Constants;
97

108
import java.util.Arrays;
119

12-
import static org.team1540.robot2024.Constants.SwerveConfig.*;
13-
1410
/**
1511
* Helper class for refreshing CANivore TimeSynced status signals.
1612
*/

0 commit comments

Comments
 (0)