Skip to content
This repository was archived by the owner on Feb 16, 2026. It is now read-only.
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 11 additions & 1 deletion src/main/java/swervelib/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@
/**
* Swerve Drive class representing and controlling the swerve drive.
*/
public class SwerveDrive
public class SwerveDrive implements AutoCloseable
{

/**
Expand Down Expand Up @@ -334,6 +334,16 @@ public SwerveDrive(
HAL.report(kResourceType_RobotDrive, kRobotDriveSwerve_YAGSL);
}

@Override
public void close() {
imu.close();
tunerXRecommendation.close();

for (var module : swerveModules) {
module.close();
}
}

/**
* Update the cache validity period for the robot.
*
Expand Down
9 changes: 8 additions & 1 deletion src/main/java/swervelib/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
/**
* The Swerve Module class which represents and controls Swerve Modules for the swerve drive.
*/
public class SwerveModule
public class SwerveModule implements AutoCloseable
{

/**
Expand Down Expand Up @@ -267,6 +267,13 @@ public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfigurat
"swerve/modules/" + configuration.name + "/Angle Setpoint").publish();
}

@Override
public void close() {
angleMotor.close();
driveMotor.close();
absoluteEncoder.close();
}

/**
* Get the default {@link SimpleMotorFeedforward} for the swerve module drive motor.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,12 @@ public AnalogAbsoluteEncoderSwerve(AnalogInput encoder)
AlertType.kWarning);
}

@Override
public void close()
{
encoder.close();
}

/**
* Construct the Encoder given the analog input channel.
*
Expand Down
6 changes: 6 additions & 0 deletions src/main/java/swervelib/encoders/CANCoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,12 @@ public CANCoderSwerve(int id, String canbus)
AlertType.kWarning);
}

@Override
public void close()
{
encoder.close();
}

/**
* Reset the encoder to factory defaults.
*/
Expand Down
6 changes: 6 additions & 0 deletions src/main/java/swervelib/encoders/CanAndMagSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,12 @@ public CanAndMagSwerve(int canid)
settings = encoder.getSettings();
}

@Override
public void close()
{
encoder.close();
}

/**
* Reset the encoder to factory defaults.
* <p>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,12 @@ public DIODutyCycleEncoderSwerve(int pin)

}

@Override
public void close()
{
encoder.close();
}

/**
* Configure the inversion state of the encoder.
*
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/swervelib/encoders/SparkFlexEncoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,15 @@ public SparkFlexEncoderSwerve(SwerveMotor motor, int conversionFactor)
}
}

@Override
public void close()
{
// SPARK Flex encoder gets closed with the motor
// I don't think an encoder getting closed should
// close the entire motor so i will keep this empty
// sparkFlex.close();
}

/**
* Run the configuration until it succeeds or times out.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,15 @@ public SparkMaxAnalogEncoderSwerve(SwerveMotor motor, double maxVoltage)

}

@Override
public void close()
{
// SPARK MAX Analog encoder gets closed with the motor
// I don't think an encoder getting closed should
// close the entire motor so i will keep this empty
// sparkMax.close();
}

/**
* Run the configuration until it succeeds or times out.
*
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/swervelib/encoders/SparkMaxEncoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,15 @@ public SparkMaxEncoderSwerve(SwerveMotor motor, int conversionFactor)
}
}

@Override
public void close()
{
// SPARK MAX encoder gets closed with the motor
// I don't think an encoder getting closed should
// close the entire motor so i will keep this empty
// sparkFlex.close();
}

/**
* Run the configuration until it succeeds or times out.
*
Expand Down
8 changes: 7 additions & 1 deletion src/main/java/swervelib/encoders/SwerveAbsoluteEncoder.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,15 @@
/**
* Swerve abstraction class to define a standard interface with absolute encoders for swerve modules..
*/
public abstract class SwerveAbsoluteEncoder
public abstract class SwerveAbsoluteEncoder implements AutoCloseable
{

// This is a bit weird because some encoders are closable
// while some get closed with the motor controller
// so for some encoders this will be an empty function
@Override
public abstract void close();

/**
* The maximum amount of times the swerve encoder will attempt to configure itself if failures occur.
*/
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/swervelib/encoders/TalonSRXEncoderSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,15 @@ public TalonSRXEncoderSwerve(SwerveMotor motor, FeedbackDevice feedbackDevice)
}
}

@Override
public void close()
{
// TalonSRX encoder gets closed with the motor
// I don't think an encoder getting closed should
// close the entire motor so i will keep this empty
// sparkFlex.close();
}

@Override
public void factoryDefault()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,15 @@ public ThriftyNovaEncoderSwerve(SwerveMotor motor)
motor.setAbsoluteEncoder(null);
}

@Override
public void close()
{
// ThriftyNova encoder gets closed with the motor
// I don't think an encoder getting closed should
// close the entire motor so i will keep this empty
// sparkFlex.close();
}

/**
* Set factory default.
*/
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/swervelib/imu/ADIS16448Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,11 @@ public ADIS16448Swerve()
SmartDashboard.putData(imu);
}

@Override
public void close() {
imu.close();
}

/**
* Reset IMU to factory default.
*/
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/swervelib/imu/ADIS16470Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,11 @@ public ADIS16470Swerve()
SmartDashboard.putData(imu);
}

@Override
public void close() {
imu.close();
}

/**
* Reset IMU to factory default.
*/
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/swervelib/imu/ADXRS450Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,11 @@ public ADXRS450Swerve()
SmartDashboard.putData(imu);
}

@Override
public void close() {
imu.close();
}

/**
* Reset IMU to factory default.
*/
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/swervelib/imu/AnalogGyroSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,11 @@ public AnalogGyroSwerve(int channel)
SmartDashboard.putData(imu);
}

@Override
public void close() {
imu.close();
}

/**
* Reset IMU to factory default.
*/
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/swervelib/imu/NavXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,10 @@ public NavXSwerve(NavXComType port)
}
}

@Override
public void close() {
imu.close();
}

/**
* Reset offset to current gyro reading. Does not call NavX({@link AHRS#reset()}) because it has been reported to be
Expand Down
6 changes: 6 additions & 0 deletions src/main/java/swervelib/imu/Pigeon2Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,12 @@ public Pigeon2Swerve(int canid)
this(canid, "");
}

@Override
public void close() {
imu.close();
}


/**
* Reset {@link Pigeon2} to factory default.
*/
Expand Down
6 changes: 6 additions & 0 deletions src/main/java/swervelib/imu/PigeonSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,12 @@ public PigeonSwerve(int canid)
SmartDashboard.putData(imu);
}

@Override
public void close() {
imu.close();
}


/**
* Reset IMU to factory default.
*/
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/swervelib/imu/PigeonViaTalonSRXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,11 @@ public PigeonViaTalonSRXSwerve(int canid)
SmartDashboard.putData(imu);
}

@Override
public void close() {
imu.close();
}

/**
* Reset IMU to factory default.
*/
Expand Down
5 changes: 4 additions & 1 deletion src/main/java/swervelib/imu/SwerveIMU.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,12 @@
/**
* Swerve IMU abstraction to define a standard interface with a swerve drive.
*/
public abstract class SwerveIMU
public abstract class SwerveIMU implements AutoCloseable
{

@Override
public abstract void close();

/**
* Reset IMU to factory default.
*/
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/swervelib/motors/SparkFlexSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,11 @@ private void configureSparkFlex(Supplier<REVLibError> config)
failureConfiguring.set(true);
}

@Override
public void close() {
motor.close();
}

/**
* Get the current configuration of the {@link SparkFlex}
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,11 @@ private void configureSparkMax(Supplier<REVLibError> config)
failureConfiguringAlert.set(true);
}

@Override
public void close() {
motor.close();
}

/**
* Get the current configuration of the {@link SparkMax}
*
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/swervelib/motors/SparkMaxSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,11 @@ private void configureSparkMax(Supplier<REVLibError> config)
DriverStation.reportWarning("Failure configuring motor " + motor.getDeviceId(), true);
}

@Override
public void close() {
motor.close();
}

/**
* Get the current configuration of the {@link SparkMax}
*
Expand Down
5 changes: 4 additions & 1 deletion src/main/java/swervelib/motors/SwerveMotor.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,12 @@
/**
* Swerve motor abstraction which defines a standard interface for motors within a swerve module.
*/
public abstract class SwerveMotor
public abstract class SwerveMotor implements AutoCloseable
{

@Override
public abstract void close();

/**
* The maximum amount of times the swerve motor will attempt to configure a motor if failures occur.
*/
Expand Down
6 changes: 6 additions & 0 deletions src/main/java/swervelib/motors/TalonFXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,12 @@ public void factoryDefaults()
}
}

@Override
public void close() {
motor.close();
}


/**
* Clear the sticky faults on the motor controller.
*/
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/swervelib/motors/TalonSRXSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,11 @@ public TalonSRXSwerve(int id, boolean isDriveMotor, DCMotor motorType)
this(new WPI_TalonSRX(id), isDriveMotor, motorType);
}

@Override
public void close() {
motor.close();
}

/**
* Configure the factory defaults.
*/
Expand Down
Loading