From d67c47cf7b0e370d950659064ef02809601c1d7c Mon Sep 17 00:00:00 2001 From: blueskinlizard Date: Sun, 21 Sep 2025 14:46:40 -0500 Subject: [PATCH 1/2] Actually call resetToAbsolute --- .../robot/generic/subsystems/drive/Drive.java | 16 ++++++++++++---- .../robot/generic/subsystems/drive/Module.java | 4 ++++ .../frc/robot/generic/util/SwerveBuilder.java | 1 + 3 files changed, 17 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/generic/subsystems/drive/Drive.java b/src/main/java/frc/robot/generic/subsystems/drive/Drive.java index c61932d..1b3f979 100644 --- a/src/main/java/frc/robot/generic/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/generic/subsystems/drive/Drive.java @@ -40,6 +40,7 @@ import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.robot.Constants; @@ -78,10 +79,7 @@ public Drive( ModuleIO blModuleIO, ModuleIO brModuleIO) { this.gyroIO = gyroIO; - modules[0] = new Module(flModuleIO, 0); - modules[1] = new Module(frModuleIO, 1); - modules[2] = new Module(blModuleIO, 2); - modules[3] = new Module(brModuleIO, 3); + // Usage reporting for swerve template HAL.report(tResourceType.kResourceType_RobotDrive, tInstances.kRobotDriveSwerve_AdvantageKit); @@ -320,4 +318,14 @@ public double getMaxLinearSpeedMetersPerSec() { public double getMaxAngularSpeedRadPerSec() { return maxSpeedMetersPerSec / driveBaseRadius; } + // Reset ModuleIO to absolute position based on module array + // Made this a method for implementation into the SwerveBuilder class (that's also why it returns command not void) + public Command resetModulesToAbsolute(){ + // Added getter as the code was a bit more readable than just manually reseting each instance + return Commands.runOnce(() ->{ + for(Module module : modules) { + module.getModuleIO().resetToAbsolute(); + } + }, this); + } } diff --git a/src/main/java/frc/robot/generic/subsystems/drive/Module.java b/src/main/java/frc/robot/generic/subsystems/drive/Module.java index 2882b0c..ea7afc4 100644 --- a/src/main/java/frc/robot/generic/subsystems/drive/Module.java +++ b/src/main/java/frc/robot/generic/subsystems/drive/Module.java @@ -128,4 +128,8 @@ public double getWheelRadiusCharacterizationPosition() { public double getFFCharacterizationVelocity() { return inputs.driveVelocityRadPerSec; } + // Gets moduleio instance + public ModuleIO getModuleIO(){ + return io; + } } diff --git a/src/main/java/frc/robot/generic/util/SwerveBuilder.java b/src/main/java/frc/robot/generic/util/SwerveBuilder.java index 33d7466..3d1d9a4 100644 --- a/src/main/java/frc/robot/generic/util/SwerveBuilder.java +++ b/src/main/java/frc/robot/generic/util/SwerveBuilder.java @@ -75,6 +75,7 @@ public static Drive buildDefaultDrive(CommandXboxController driveController) { drive.setPose( new Pose2d(drive.getPose().getTranslation(), new Rotation2d())), drive) + .andThen(drive.resetModulesToAbsolute()) // Resets modules when button pressed .ignoringDisable(true)); return drive; } From 1be12fe514c69032333cb59f5eb6c8f0ef2eee92 Mon Sep 17 00:00:00 2001 From: blueskinlizard Date: Sun, 21 Sep 2025 14:50:03 -0500 Subject: [PATCH 2/2] Readded modules that were accidentally deleted & actually called function --- src/main/java/frc/robot/generic/subsystems/drive/Drive.java | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/main/java/frc/robot/generic/subsystems/drive/Drive.java b/src/main/java/frc/robot/generic/subsystems/drive/Drive.java index 1b3f979..87d5fc6 100644 --- a/src/main/java/frc/robot/generic/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/generic/subsystems/drive/Drive.java @@ -80,6 +80,12 @@ public Drive( ModuleIO brModuleIO) { this.gyroIO = gyroIO; + modules[0] = new Module(flModuleIO, 0); + modules[1] = new Module(frModuleIO, 1); + modules[2] = new Module(blModuleIO, 2); + modules[3] = new Module(brModuleIO, 3); + + resetModulesToAbsolute(); // Usage reporting for swerve template HAL.report(tResourceType.kResourceType_RobotDrive, tInstances.kRobotDriveSwerve_AdvantageKit);