Skip to content

Commit 3be2661

Browse files
Update stuff (#7)
* Implement Full Logging and Drivetrain Subsystem (#1) * Da Code * Add alerts on drive spark maxes * Add Config Changes from Meeting * Other lil bs * Add automatic brake disable on robot disable * add odometry * add SIM module * Add DriveCommands * Update RobotContainer.java * Formatting fixes * Misc Fixes * Add low voltage warning for DT * Add velocity scalars for DT * Update PID Coefficents and fix odometry issues * Update URCL.json --------- Fix CI Co-Authored-By: Talon540-root <[email protected]> * Increase voltage warning on battery and add CAN error alert * clean * Fix Modules Falsely Reporting as Disconnected * Cleanup typing, make errors more obvious * Cleanup dashboard setting stuff * Update sim characterization constants to be more accurate, stops a massive overshooting for some reason * Log drive motor temps * Formatting fixes * Inline tuning mode alert * Rename RobotState to PoseEstimator Because only vision and drive will interact with pose (and purely position) and no other robot state is tracked, it makes more sense for this to be renammed to reflect that. * Refactor abstract alerts into util class to later roll into LEDs * Update Phoenix6 to 2025.2.2 * Refactor code structure to not over-expose subsystem specific stuff * Shorten name for drive temp * Fix red alliance drive commands bug * Update WPILIB to 2025.3.1 --------- Co-authored-by: Talon540-root <[email protected]>
1 parent 9325f68 commit 3be2661

15 files changed

+338
-263
lines changed

build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
plugins {
22
id "java"
3-
id "edu.wpi.first.GradleRIO" version "2025.2.1"
3+
id "edu.wpi.first.GradleRIO" version "2025.3.1"
44
id "com.peterabeles.gversion" version "1.10.3"
55
id "com.diffplug.spotless" version "7.0.2"
66
id "io.freefair.lombok" version "8.11"

src/main/java/frc/robot/RobotState.java renamed to src/main/java/frc/robot/PoseEstimator.java

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -11,32 +11,32 @@
1111
import edu.wpi.first.math.kinematics.SwerveModulePosition;
1212
import edu.wpi.first.math.numbers.N1;
1313
import edu.wpi.first.math.numbers.N3;
14-
import frc.robot.subsystems.drive.DriveConstants;
14+
import frc.robot.subsystems.drive.DriveBase;
1515
import lombok.Getter;
1616
import org.littletonrobotics.junction.AutoLogOutput;
1717

18-
public class RobotState {
18+
public class PoseEstimator {
1919
// Standard deviations of the pose estimate (x position in meters, y position in meters, and
2020
// heading in radians).
2121
// Increase these numbers to trust your state estimate less.
2222
private static final Matrix<N3, N1> odometryStateStdDevs = VecBuilder.fill(0.003, 0.003, 0.002);
2323
private static final double poseBufferSizeSec = 2.0;
2424

25-
private static RobotState instance;
25+
private static PoseEstimator instance;
2626

27-
public static RobotState getInstance() {
27+
public static PoseEstimator getInstance() {
2828
if (instance == null) {
29-
instance = new RobotState();
29+
instance = new PoseEstimator();
3030
}
3131
return instance;
3232
}
3333

3434
@Getter
35-
@AutoLogOutput(key = "RobotState/OdometryPose")
35+
@AutoLogOutput(key = "PoseEstimator/OdometryPose")
3636
private Pose2d odometryPose = new Pose2d();
3737

3838
@Getter
39-
@AutoLogOutput(key = "RobotState/EstimatedPose")
39+
@AutoLogOutput(key = "PoseEstimator/EstimatedPose")
4040
private Pose2d estimatedPose = new Pose2d();
4141

4242
private final TimeInterpolatableBuffer<Pose2d> poseBuffer =
@@ -55,12 +55,12 @@ public static RobotState getInstance() {
5555
// Assume gyro starts at zero
5656
private Rotation2d gyroOffset = new Rotation2d();
5757

58-
private RobotState() {
58+
private PoseEstimator() {
5959
for (int i = 0; i < 3; ++i) {
6060
qStdDevs.set(i, 0, Math.pow(odometryStateStdDevs.get(i, 0), 2));
6161
}
6262

63-
kinematics = new SwerveDriveKinematics(DriveConstants.moduleTranslations);
63+
kinematics = new SwerveDriveKinematics(DriveBase.getModuleTranslations());
6464
}
6565

6666
public void resetPose(Pose2d pose) {

src/main/java/frc/robot/Robot.java

Lines changed: 2 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -13,14 +13,12 @@
1313

1414
package frc.robot;
1515

16-
import edu.wpi.first.math.filter.Debouncer;
17-
import edu.wpi.first.wpilibj.Alert;
18-
import edu.wpi.first.wpilibj.Alert.AlertType;
1916
import edu.wpi.first.wpilibj.DriverStation;
2017
import edu.wpi.first.wpilibj.RobotController;
2118
import edu.wpi.first.wpilibj.Threads;
2219
import edu.wpi.first.wpilibj2.command.Command;
2320
import edu.wpi.first.wpilibj2.command.CommandScheduler;
21+
import frc.robot.util.AlertsUtil;
2422
import frc.robot.util.LoggerUtil;
2523
import org.littletonrobotics.junction.LogFileUtil;
2624
import org.littletonrobotics.junction.LoggedRobot;
@@ -37,20 +35,9 @@
3735
* project.
3836
*/
3937
public class Robot extends LoggedRobot {
40-
private static final double LOW_VOLTAGE_WARNING_THRESHOLD = 11.75;
41-
4238
private Command autonomousCommand;
4339
private final RobotContainer robotContainer;
4440

45-
// System Alerts
46-
private final Alert canErrorAlert =
47-
new Alert("CAN errors detected, robot may not be controllable.", AlertType.kError);
48-
private final Debouncer canErrorDebouncer = new Debouncer(0.5);
49-
50-
private final Alert lowBatteryVoltageAlert =
51-
new Alert("Battery voltage is too low, change the battery", Alert.AlertType.kWarning);
52-
private final Debouncer batteryVoltageDebouncer = new Debouncer(1.5);
53-
5441
public Robot() {
5542
super(Constants.kLoopPeriodSecs);
5643

@@ -100,16 +87,7 @@ public void robotPeriodic() {
10087
// Run command scheduler
10188
CommandScheduler.getInstance().run();
10289

103-
// Check CAN status
104-
var canStatus = RobotController.getCANStatus();
105-
canErrorAlert.set(
106-
canErrorDebouncer.calculate(
107-
canStatus.transmitErrorCount > 0 || canStatus.receiveErrorCount > 0));
108-
109-
// Update Battery Voltage Alert
110-
lowBatteryVoltageAlert.set(
111-
batteryVoltageDebouncer.calculate(
112-
RobotController.getBatteryVoltage() <= LOW_VOLTAGE_WARNING_THRESHOLD));
90+
AlertsUtil.getInstance().periodic();
11391

11492
// Return to normal thread priority
11593
Threads.setCurrentThreadPriority(false, 10);

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

Lines changed: 9 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -2,18 +2,18 @@
22

33
import edu.wpi.first.math.geometry.Pose2d;
44
import edu.wpi.first.math.geometry.Rotation2d;
5-
import edu.wpi.first.wpilibj.Alert;
65
import edu.wpi.first.wpilibj2.command.Command;
76
import edu.wpi.first.wpilibj2.command.Commands;
87
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
98
import frc.robot.commands.DriveCommands;
109
import frc.robot.subsystems.drive.*;
10+
import frc.robot.util.AlertsUtil;
1111
import frc.robot.util.AllianceFlipUtil;
1212
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
1313

1414
public class RobotContainer {
15-
// Load RobotState class
16-
private final RobotState robotState = RobotState.getInstance();
15+
// Load PoseEstimator class
16+
private final PoseEstimator poseEstimator = PoseEstimator.getInstance();
1717

1818
// Subsystems
1919
private final DriveBase driveBase;
@@ -59,14 +59,12 @@ public RobotContainer() {
5959
autoChooser = new LoggedDashboardChooser<>("Auto Choices");
6060

6161
if (Constants.TUNING_MODE) {
62-
new Alert("Robot in Tuning Mode", Alert.AlertType.kInfo).set(true);
63-
6462
// Set up Characterization routines
6563
autoChooser.addOption(
66-
"Drive Wheel Radius Characterization",
67-
DriveCommands.wheelRadiusCharacterization(driveBase));
64+
"Drive Wheel Radius Characterization", driveBase.wheelRadiusCharacterization());
6865
autoChooser.addOption(
69-
"Drive Simple FF Characterization", DriveCommands.feedforwardCharacterization(driveBase));
66+
"Drive Simple FF Characterization", driveBase.feedforwardCharacterization());
67+
}
7068
}
7169

7270
configureButtonBindings();
@@ -94,16 +92,16 @@ private void configureButtonBindings() {
9492
// Switch to X pattern when X button is pressed
9593
controller.x().onTrue(Commands.runOnce(driveBase::stopWithX, driveBase));
9694

97-
// Reset gyro to 0° when B button is pressed
95+
// Reset gyro to 0° when B button is pressed
9896
controller
9997
.b()
10098
.onTrue(
10199
Commands.runOnce(
102100
() ->
103-
RobotState.getInstance()
101+
PoseEstimator.getInstance()
104102
.resetPose(
105103
new Pose2d(
106-
RobotState.getInstance().getEstimatedPose().getTranslation(),
104+
PoseEstimator.getInstance().getEstimatedPose().getTranslation(),
107105
AllianceFlipUtil.apply(new Rotation2d()))),
108106
driveBase)
109107
.ignoringDisable(true));

0 commit comments

Comments
 (0)