Skip to content

Commit 14bbe33

Browse files
committed
compiles + spotless
1 parent 5ee2c43 commit 14bbe33

File tree

9 files changed

+144
-133
lines changed

9 files changed

+144
-133
lines changed
Lines changed: 85 additions & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -1,34 +1,30 @@
11
package frc.lib.monitor;
22

3-
import com.ctre.phoenix6.hardware.CANcoder;
43
import com.ctre.phoenix6.hardware.ParentDevice;
5-
import com.ctre.phoenix6.hardware.TalonFX;
64
import com.reduxrobotics.canand.CanandDevice;
7-
import com.reduxrobotics.sensors.canandmag.Canandmag;
85
import com.revrobotics.spark.SparkBase;
9-
import com.revrobotics.spark.SparkMax;
106
import edu.wpi.first.wpilibj.*;
117
import edu.wpi.first.wpilibj.event.EventLoop;
128
import edu.wpi.first.wpilibj2.command.CommandScheduler;
139
import edu.wpi.first.wpilibj2.command.Commands;
1410
import edu.wpi.first.wpilibj2.command.button.Trigger;
1511
import frc.lib.util.Capture;
16-
import frc.robot.subsystems.drive.swerveModule.encoder.EncoderIOHelium;
17-
import lombok.Getter;
18-
1912
import java.util.function.BooleanSupplier;
13+
import lombok.Getter;
2014

2115
/**
22-
* A class designed to passively monitor and report device connection issues.
23-
* Creates 2 NT Alerts, (ActiveHardwareAlerts and StickyHardwareAlerts)
16+
* A class designed to passively monitor and report device connection issues. Creates 2 NT Alerts,
17+
* (ActiveHardwareAlerts and StickyHardwareAlerts)
2418
*/
2519
public class HardwareWatchdog {
2620
@Getter public static final HardwareWatchdog instance = new HardwareWatchdog();
2721

2822
private final EventLoop eventLoop = new EventLoop();
2923

30-
// String concatenations are slow, and there really is no need to update the alert more frequently
31-
// This only impacts the while active periodic alert updates, and does not impact when the appearance or disappearance of the alert occurs
24+
// String concatenations are slow, and there really is no need to update the alert more
25+
// frequently
26+
// This only impacts the while active periodic alert updates, and does not impact when the
27+
// appearance or disappearance of the alert occurs
3228
// Or the start/stop times
3329
private static final double alertUpdatePeriod = .2;
3430

@@ -38,80 +34,110 @@ public class HardwareWatchdog {
3834
private static final String groupActive = "ActiveHardwareAlerts";
3935
private static final String groupSticky = "StickyHardwareAlerts";
4036

41-
4237
private HardwareWatchdog() {
4338
var timer = new Timer();
4439
timer.start();
4540

46-
CommandScheduler.getInstance().getDefaultButtonLoop().bind(
47-
() -> {
48-
if (timer.get() > gracePeriod) {eventLoop.poll();}
49-
}
50-
);
41+
CommandScheduler.getInstance()
42+
.getDefaultButtonLoop()
43+
.bind(
44+
() -> {
45+
if (timer.get() > gracePeriod) {
46+
eventLoop.poll();
47+
}
48+
});
5149
}
5250

5351
public void registerCTREDevice(ParentDevice device, Class<?> parent) {
54-
registerDevice(device::isConnected, device.getClass().getSimpleName() + " " + device.getDeviceID(), parent);
52+
registerDevice(
53+
device::isConnected,
54+
device.getClass().getSimpleName() + " " + device.getDeviceID(),
55+
parent);
5556
}
5657

5758
public void registerSpark(SparkBase spark, Class<?> parent) {
58-
registerDevice(() -> !spark.getFaults().can && spark.getFirmwareVersion() != 0, "SparkMax " + spark.getDeviceId(), parent);
59+
registerDevice(
60+
() -> !spark.getFaults().can && spark.getFirmwareVersion() != 0,
61+
"SparkMax " + spark.getDeviceId(),
62+
parent);
5963
}
6064

6165
public void registerDutyCycleEncoder(DutyCycleEncoder encoder, Class<?> parent) {
62-
registerDevice(encoder::isConnected, "DutyCycleEncoder " + encoder.getSourceChannel(), parent);
66+
registerDevice(
67+
encoder::isConnected, "DutyCycleEncoder " + encoder.getSourceChannel(), parent);
6368
}
6469

6570
public void registerReduxDevice(CanandDevice device, Class<?> parent) {
66-
registerDevice(device::isConnected, device.getClass().getSimpleName() + " " + device.getAddress().getDeviceId(), parent);
71+
registerDevice(
72+
device::isConnected,
73+
device.getClass().getSimpleName() + " " + device.getAddress().getDeviceId(),
74+
parent);
6775
}
6876

6977
public void registerDevice(BooleanSupplier isConnected, String name, Class<?> parent) {
70-
String deviceDescriptor = String.format("\"%s\" belonging to \"%s\"", name, parent.getSimpleName());
78+
String deviceDescriptor =
79+
String.format("\"%s\" belonging to \"%s\"", name, parent.getSimpleName());
7180

72-
Capture<Alert> alert = new Capture<>(new Alert(groupActive, "deviceDisconnectAlert", Alert.AlertType.kWarning));
81+
Capture<Alert> alert =
82+
new Capture<>(
83+
new Alert(groupActive, "deviceDisconnectAlert", Alert.AlertType.kWarning));
7384
Capture<Alert> stickyAlert = new Capture<>(null);
7485

7586
Capture<Double> disconnectedAt = new Capture<>(-1.0);
7687

7788
var updateTimer = new Timer();
7889

7990
// On disconnect
80-
new Trigger(eventLoop, isConnected).negate().whileTrue(
81-
Commands.startRun(() -> {
82-
updateTimer.restart();
83-
disconnectedAt.inner = Timer.getTimestamp();
84-
85-
// Create a new sticky alert, this way old ones persist
86-
stickyAlert.inner = new Alert(groupSticky, "deviceDisconnectStickyAlert", Alert.AlertType.kWarning);
87-
88-
alert.inner.set(true);
89-
stickyAlert.inner.set(true);
90-
}, () -> {
91-
if (updateTimer.advanceIfElapsed(alertUpdatePeriod)) {
92-
var timeDisconnected = Timer.getTimestamp() - disconnectedAt.get();
93-
94-
var text = String.format(
95-
"Device %s has been disconnected for %.2f seconds (since %.2f)",
96-
deviceDescriptor, timeDisconnected, disconnectedAt.get()
97-
);
98-
99-
alert.inner.setText(text);
100-
stickyAlert.inner.setText(text);
101-
}
102-
}).finallyDo(() ->
103-
{
104-
alert.get().set(false);
105-
106-
var stickyText = String.format(
107-
"Device %s was disconnected for %.2f seconds (from %.2f to %.2f)",
108-
deviceDescriptor, Timer.getTimestamp() - disconnectedAt.get(), disconnectedAt.get(), Timer.getTimestamp()
109-
);
110-
111-
stickyAlert.inner.setText(stickyText);
112-
updateTimer.stop();
113-
})
114-
.ignoringDisable(true)
115-
);
91+
new Trigger(eventLoop, isConnected)
92+
.negate()
93+
.whileTrue(
94+
Commands.startRun(
95+
() -> {
96+
updateTimer.restart();
97+
disconnectedAt.inner = Timer.getTimestamp();
98+
99+
// Create a new sticky alert, this way old ones persist
100+
stickyAlert.inner =
101+
new Alert(
102+
groupSticky,
103+
"deviceDisconnectStickyAlert",
104+
Alert.AlertType.kWarning);
105+
106+
alert.inner.set(true);
107+
stickyAlert.inner.set(true);
108+
},
109+
() -> {
110+
if (updateTimer.advanceIfElapsed(alertUpdatePeriod)) {
111+
var timeDisconnected =
112+
Timer.getTimestamp() - disconnectedAt.get();
113+
114+
var text =
115+
String.format(
116+
"Device %s has been disconnected for %.2f seconds (since %.2f)",
117+
deviceDescriptor,
118+
timeDisconnected,
119+
disconnectedAt.get());
120+
121+
alert.inner.setText(text);
122+
stickyAlert.inner.setText(text);
123+
}
124+
})
125+
.finallyDo(
126+
() -> {
127+
alert.get().set(false);
128+
129+
var stickyText =
130+
String.format(
131+
"Device %s was disconnected for %.2f seconds (from %.2f to %.2f)",
132+
deviceDescriptor,
133+
Timer.getTimestamp()
134+
- disconnectedAt.get(),
135+
disconnectedAt.get(),
136+
Timer.getTimestamp());
137+
138+
stickyAlert.inner.setText(stickyText);
139+
updateTimer.stop();
140+
})
141+
.ignoringDisable(true));
116142
}
117143
}

src/main/java/frc/lib/util/PeriodicExecutor.java

Lines changed: 22 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -1,19 +1,16 @@
11
package frc.lib.util;
22

33
import frc.robot.Constants;
4-
import lombok.Getter;
5-
import lombok.NonNull;
6-
74
import java.util.ArrayList;
85
import java.util.List;
6+
import lombok.Getter;
7+
import lombok.NonNull;
98

109
public class PeriodicExecutor {
11-
/**
12-
* -- GETTER --
13-
* Returns the singleton instance of the PeriodicExecutor.
14-
*/
10+
/** -- GETTER -- Returns the singleton instance of the PeriodicExecutor. */
1511
@Getter
16-
private static final PeriodicExecutor instance = new PeriodicExecutor(Constants.LOOP_PERIOD_SEC);
12+
private static final PeriodicExecutor instance =
13+
new PeriodicExecutor(Constants.LOOP_PERIOD_SEC);
1714

1815
double basePeriod;
1916
int loopCount;
@@ -24,38 +21,37 @@ private PeriodicExecutor(double basePeriod) {
2421
}
2522

2623
/**
27-
* Schedules a callback to be run periodically with a specified period and optional phase offset.
24+
* Schedules a callback to be run periodically with a specified period and optional phase
25+
* offset.
2826
*
29-
* <p>The callback will be executed at most once every {@code periodSeconds}, aligned to the executor's
30-
* internal base period (typically the robot's main loop period). The offset can be used to stagger
31-
* execution relative to the loop count, which is useful for load balancing or phasing tasks.</p>
27+
* <p>The callback will be executed at most once every {@code periodSeconds}, aligned to the
28+
* executor's internal base period (typically the robot's main loop period). The offset can be
29+
* used to stagger execution relative to the loop count, which is useful for load balancing or
30+
* phasing tasks.
3231
*
3332
* @param callback the Runnable to execute periodically (must not be null)
34-
* @param periodSeconds the interval in seconds between successive executions (must be ≥ base period)
35-
* @param offsetSeconds the delay in seconds before the first eligible execution (will be aligned to the base period).
36-
* If this is greater than {@code periodSeconds} than the offset will be {@code offsetSeconds % periodSeconds}
37-
* @throws IllegalArgumentException if {@code periodSeconds} is less than the base execution period
33+
* @param periodSeconds the interval in seconds between successive executions (must be ≥ base
34+
* period)
35+
* @param offsetSeconds the delay in seconds before the first eligible execution (will be
36+
* aligned to the base period). If this is greater than {@code periodSeconds} than the
37+
* offset will be {@code offsetSeconds % periodSeconds}
38+
* @throws IllegalArgumentException if {@code periodSeconds} is less than the base execution
39+
* period
3840
*/
39-
public void addPeriodicSeconds(@NonNull Runnable callback, double periodSeconds, double offsetSeconds) {
41+
public void addPeriodicSeconds(
42+
@NonNull Runnable callback, double periodSeconds, double offsetSeconds) {
4043
if (periodSeconds < basePeriod) {
4144
throw new IllegalArgumentException("Period: " + periodSeconds + " is too short");
4245
}
4346

4447
addPeriodicCycles(
4548
callback,
4649
(int) Math.max(1, Math.round(periodSeconds / basePeriod)),
47-
(int) Math.round(offsetSeconds / basePeriod)
48-
);
50+
(int) Math.round(offsetSeconds / basePeriod));
4951
}
5052

5153
public void addPeriodicCycles(@NonNull Runnable callback, int periodLoops, int offsetLoops) {
52-
callbacks.add(
53-
new PeriodicRunnable(
54-
callback,
55-
periodLoops,
56-
offsetLoops
57-
)
58-
);
54+
callbacks.add(new PeriodicRunnable(callback, periodLoops, offsetLoops));
5955
}
6056

6157
public void addPeriodicSeconds(Runnable callback, double periodSeconds) {

src/main/java/frc/lib/util/StaggeredExecutor.java

Lines changed: 10 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,12 @@
11
package frc.lib.util;
22

3-
import lombok.Getter;
4-
import lombok.NonNull;
5-
63
import java.util.ArrayList;
74
import java.util.List;
5+
import lombok.Getter;
6+
import lombok.NonNull;
87

98
public class StaggeredExecutor {
10-
@Getter
11-
public static final StaggeredExecutor instance = new StaggeredExecutor();
12-
9+
@Getter public static final StaggeredExecutor instance = new StaggeredExecutor();
1310

1411
private List<StaggeredRunnable> toSchedule = new ArrayList<>();
1512

@@ -20,14 +17,15 @@ public void addStaggeredRunnable(@NonNull Runnable callback, double period) {
2017
}
2118

2219
public void scheduleAll() {
23-
double avgPeriod = toSchedule.stream().mapToDouble(sr -> sr.periodSeconds).sum() / toSchedule.size();
20+
double avgPeriod =
21+
toSchedule.stream().mapToDouble(sr -> sr.periodSeconds).sum() / toSchedule.size();
2422

2523
for (int i = 0; i < toSchedule.size(); i++) {
26-
PeriodicExecutor.getInstance().addPeriodicSeconds(
27-
toSchedule.get(i).runnable,
28-
toSchedule.get(i).periodSeconds,
29-
(avgPeriod / toSchedule.size()) * i
30-
);
24+
PeriodicExecutor.getInstance()
25+
.addPeriodicSeconds(
26+
toSchedule.get(i).runnable,
27+
toSchedule.get(i).periodSeconds,
28+
(avgPeriod / toSchedule.size()) * i);
3129
}
3230
}
3331

src/main/java/frc/robot/Constants.java

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@
2222
import frc.lib.util.SwerveModuleConstants;
2323
import java.util.Arrays;
2424
import java.util.List;
25-
import java.util.function.DoubleUnaryOperator;
2625

2726
/**
2827
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
@@ -166,8 +165,8 @@ public static class Kraken {
166165
public static final double MAX_SPEED = 4.6; // TODO: This must be tuned to specific robot
167166

168167
/**
169-
* Theoretical value can be calculated by dividing MAX_LINEAR_SPEED by the distance between the center of
170-
* rotation and the wheel.
168+
* Theoretical value can be calculated by dividing MAX_LINEAR_SPEED by the distance between
169+
* the center of rotation and the wheel.
171170
*/
172171
public static final double MAX_ANGULAR_VELOCITY =
173172
10.0; // TODO: This must be tuned to specific robot

src/main/java/frc/robot/RobotContainer.java

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -43,11 +43,9 @@
4343
import frc.robot.subsystems.intake.IntakeIOSpark;
4444
import frc.robot.subsystems.superstructure.Superstructure;
4545
import frc.robot.subsystems.superstructure.elevator.Elevator;
46-
import frc.robot.subsystems.superstructure.elevator.ElevatorIO;
4746
import frc.robot.subsystems.superstructure.elevator.ElevatorIOKraken;
4847
import frc.robot.subsystems.superstructure.elevator.ElevatorIOSpark;
4948
import frc.robot.subsystems.superstructure.wrist.Wrist;
50-
import frc.robot.subsystems.superstructure.wrist.WristIO;
5149
import frc.robot.subsystems.superstructure.wrist.WristIOKraken;
5250
import frc.robot.subsystems.superstructure.wrist.WristIOSpark;
5351
import frc.robot.subsystems.vision.Vision;
@@ -56,7 +54,6 @@
5654
import frc.robot.subsystems.winch.WinchIOSpark;
5755
import java.util.Set;
5856
import org.littletonrobotics.junction.Logger;
59-
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
6057

6158
/**
6259
* This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -92,7 +89,6 @@ public RobotContainer() {
9289
Shuffleboard.getTab("Drive")
9390
.add("ResetOdometry", Commands.runOnce(() -> drive.resetOdometry(new Pose2d())));
9491

95-
9692
autoChooser = new AutoChooser();
9793
SmartDashboard.putData("autoChooser", autoChooser);
9894

@@ -316,9 +312,7 @@ private void configureButtonBindings() {
316312
.schedule();
317313
}
318314

319-
private void configureAutoCommands() {
320-
321-
}
315+
private void configureAutoCommands() {}
322316

323317
public Command getAutonomousCommand() {
324318
Logger.recordOutput("selectedAuto", autoChooser.selectedCommand().getName());

src/main/java/frc/robot/subsystems/climber/ClimberIOKraken.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ public ClimberIOKraken() {
7575

7676
HardwareWatchdog.getInstance().registerCTREDevice(leftMotor, this.getClass());
7777
HardwareWatchdog.getInstance().registerCTREDevice(rightMotor, this.getClass());
78-
78+
7979
HardwareWatchdog.getInstance().registerDutyCycleEncoder(absEncoder, this.getClass());
8080
}
8181

0 commit comments

Comments
 (0)