From f7777eac04a304bd6b46b6749dcff895fdb76cbd Mon Sep 17 00:00:00 2001 From: spderman3333 Date: Fri, 10 Oct 2025 17:27:52 -0700 Subject: [PATCH 1/7] Fixed the disable method in MotorSubystem (now called PositionalMotorSubsyem for clarity). --- .idea/discord.xml | 14 +++++++++ .../com/team2813/lib2813/control/Motor.java | 5 ++++ .../control/motors/SparkMaxWrapper.java | 10 +++++++ .../control/motors/TalonFXWrapper.java | 17 +++++++++++ ...tem.java => PositionalMotorSubsystem.java} | 30 +++++++++---------- 5 files changed, 61 insertions(+), 15 deletions(-) create mode 100644 .idea/discord.xml rename lib/src/main/java/com/team2813/lib2813/subsystems/{MotorSubsystem.java => PositionalMotorSubsystem.java} (90%) diff --git a/.idea/discord.xml b/.idea/discord.xml new file mode 100644 index 00000000..912db825 --- /dev/null +++ b/.idea/discord.xml @@ -0,0 +1,14 @@ + + + + + \ No newline at end of file diff --git a/lib/src/main/java/com/team2813/lib2813/control/Motor.java b/lib/src/main/java/com/team2813/lib2813/control/Motor.java index 6c92ed0b..c73bca6f 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/Motor.java +++ b/lib/src/main/java/com/team2813/lib2813/control/Motor.java @@ -29,4 +29,9 @@ public interface Motor { * @return The current applied current */ Current getAppliedCurrent(); + + /** + * Stops the motor. + */ + void disable(); } diff --git a/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java b/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java index 4ddc5b00..073594e8 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java +++ b/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java @@ -20,6 +20,7 @@ import java.util.ArrayList; import java.util.List; +@Deprecated(forRemoval = true) // We likely wont use sparkmax's ever again. public class SparkMaxWrapper implements PIDMotor { private final List followers = new ArrayList<>(); private final SparkBase motor; @@ -81,6 +82,15 @@ public Current getAppliedCurrent() { return Units.Amps.of(motor.getOutputCurrent()); } + /** + * WARNING: due to the end of support of SparkMaxWrapper, there is no evidence that this method will work. + * Proceed with caution! + */ + @Override + public void disable() { + motor.disable(); + } + @Override public void setPosition(double position) { encoder.setPosition(position); diff --git a/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java b/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java index 49f05a12..08c10542 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java +++ b/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java @@ -162,10 +162,27 @@ public TalonFX motor() { return motor; } + /** + * Sets the behavior the motor should exhibit upon receiving a request to stop: "disable()". + * + * @param mode + */ public void setNeutralMode(NeutralModeValue mode) { motor.setNeutralMode(mode); } + /** + * Sends a disable command to the motor, placing it in its neutral value. + * @see TalonFXWrapper#setNeutralMode(NeutralModeValue) + */ + @Override + public void disable() { + motor.disable(); + } + @Override public void configPIDF(int slot, double p, double i, double d, double f) { SlotConfigs conf = new SlotConfigs(); diff --git a/lib/src/main/java/com/team2813/lib2813/subsystems/MotorSubsystem.java b/lib/src/main/java/com/team2813/lib2813/subsystems/PositionalMotorSubsystem.java similarity index 90% rename from lib/src/main/java/com/team2813/lib2813/subsystems/MotorSubsystem.java rename to lib/src/main/java/com/team2813/lib2813/subsystems/PositionalMotorSubsystem.java index c8052804..8e050eb1 100644 --- a/lib/src/main/java/com/team2813/lib2813/subsystems/MotorSubsystem.java +++ b/lib/src/main/java/com/team2813/lib2813/subsystems/PositionalMotorSubsystem.java @@ -28,7 +28,7 @@ * * @param the type of the {@link Supplier} used to specify setpoints. */ -public abstract class MotorSubsystem> extends SubsystemBase +public abstract class PositionalMotorSubsystem> extends SubsystemBase implements Motor, Encoder { protected final Motor motor; @@ -44,7 +44,7 @@ public abstract class MotorSubsystem> extends Subsyste private boolean isEnabled; - protected MotorSubsystem(MotorSubsystemConfiguration builder) { + protected PositionalMotorSubsystem(PositionalMotorSubsystemConfiguration builder) { this.controller = builder.controller; this.controller.setTolerance(builder.acceptableError); acceptableError = builder.acceptableError; @@ -136,7 +136,7 @@ public final void enable() { */ public final void disable() { isEnabled = false; - motor.set(controlMode, 0); + motor.disable(); } /** @@ -248,8 +248,8 @@ public void periodic() { } } - /** A configuration for a MotorSubsystem */ - public static class MotorSubsystemConfiguration { + /** A configuration for a PositionalMotorSubsystem */ + public static class PositionalMotorSubsystemConfiguration { /** The default acceptable position error. */ public static final double DEFAULT_ERROR = 5.0; @@ -273,7 +273,7 @@ public static class MotorSubsystemConfiguration { * @param motor the motor to control * @param encoder the encoder providing feedback */ - public MotorSubsystemConfiguration(Motor motor, Encoder encoder) { + public PositionalMotorSubsystemConfiguration(Motor motor, Encoder encoder) { this.motor = Objects.requireNonNull(motor, "motor should not be null"); this.encoder = Objects.requireNonNull(encoder, "encoder should not be null"); controller = new PIDController(0, 0, 0); @@ -290,7 +290,7 @@ public MotorSubsystemConfiguration(Motor motor, Encoder encoder) { * * @param motor the integrated motor controller */ - public MotorSubsystemConfiguration(PIDMotor motor) { + public PositionalMotorSubsystemConfiguration(PIDMotor motor) { this(motor, motor); } @@ -300,7 +300,7 @@ public MotorSubsystemConfiguration(PIDMotor motor) { * @param controller The PID controller * @return {@code this} for chaining */ - public MotorSubsystemConfiguration controller(PIDController controller) { + public PositionalMotorSubsystemConfiguration controller(PIDController controller) { this.controller = controller; return this; } @@ -312,7 +312,7 @@ public MotorSubsystemConfiguration controller(PIDController controller) { * @param controlMode The mode to use when controlling the motor * @return {@code this} for chaining */ - public MotorSubsystemConfiguration controlMode(ControlMode controlMode) { + public PositionalMotorSubsystemConfiguration controlMode(ControlMode controlMode) { this.controlMode = controlMode; return this; } @@ -325,7 +325,7 @@ public MotorSubsystemConfiguration controlMode(ControlMode controlMode) { * @param d the derivative * @return {@code this} for chaining */ - public MotorSubsystemConfiguration PID(double p, double i, double d) { + public PositionalMotorSubsystemConfiguration PID(double p, double i, double d) { controller.setPID(p, i, d); return this; } @@ -336,7 +336,7 @@ public MotorSubsystemConfiguration PID(double p, double i, double d) { * @param startingPosition the initial setpoint * @return {@code this} for chaining */ - public MotorSubsystemConfiguration startingPosition(Angle startingPosition) { + public PositionalMotorSubsystemConfiguration startingPosition(Angle startingPosition) { this.startingPosition = startingPosition.in(this.rotationUnit); return this; } @@ -350,12 +350,12 @@ public MotorSubsystemConfiguration startingPosition(Angle startingPosition) { * @param startingPositionSupplier supplier to use to get the initial setpoint * @return {@code this} for chaining */ - public MotorSubsystemConfiguration startingPosition(Supplier startingPositionSupplier) { + public PositionalMotorSubsystemConfiguration startingPosition(Supplier startingPositionSupplier) { return startingPosition(startingPositionSupplier.get()); } /** Sets the acceptable position error. */ - public MotorSubsystemConfiguration acceptableError(double error) { + public PositionalMotorSubsystemConfiguration acceptableError(double error) { this.acceptableError = error; return this; } @@ -365,13 +365,13 @@ public MotorSubsystemConfiguration acceptableError(double error) { * * @param rotationUnit The angle unit to use for calculations */ - public MotorSubsystemConfiguration rotationUnit(AngleUnit rotationUnit) { + public PositionalMotorSubsystemConfiguration rotationUnit(AngleUnit rotationUnit) { startingPosition = rotationUnit.convertFrom(startingPosition, this.rotationUnit); this.rotationUnit = rotationUnit; return this; } - public MotorSubsystemConfiguration publishTo(NetworkTableInstance ntInstance) { + public PositionalMotorSubsystemConfiguration publishTo(NetworkTableInstance ntInstance) { this.ntInstance = ntInstance; return this; } From 6fd0fa2d91824c6df87d54e10606c7acb33e5d39 Mon Sep 17 00:00:00 2001 From: spderman3333 Date: Mon, 13 Oct 2025 14:27:17 -0700 Subject: [PATCH 2/7] Cherrypicked c646ea4 and rerenamed a class, to prevent need for major refactor. --- ...otorSubsystem.java => MotorSubsystem.java} | 28 +++++++++---------- 1 file changed, 14 insertions(+), 14 deletions(-) rename lib/src/main/java/com/team2813/lib2813/subsystems/{PositionalMotorSubsystem.java => MotorSubsystem.java} (90%) diff --git a/lib/src/main/java/com/team2813/lib2813/subsystems/PositionalMotorSubsystem.java b/lib/src/main/java/com/team2813/lib2813/subsystems/MotorSubsystem.java similarity index 90% rename from lib/src/main/java/com/team2813/lib2813/subsystems/PositionalMotorSubsystem.java rename to lib/src/main/java/com/team2813/lib2813/subsystems/MotorSubsystem.java index 8e050eb1..d2e76276 100644 --- a/lib/src/main/java/com/team2813/lib2813/subsystems/PositionalMotorSubsystem.java +++ b/lib/src/main/java/com/team2813/lib2813/subsystems/MotorSubsystem.java @@ -28,7 +28,7 @@ * * @param the type of the {@link Supplier} used to specify setpoints. */ -public abstract class PositionalMotorSubsystem> extends SubsystemBase +public abstract class MotorSubsystem> extends SubsystemBase implements Motor, Encoder { protected final Motor motor; @@ -44,7 +44,7 @@ public abstract class PositionalMotorSubsystem> extend private boolean isEnabled; - protected PositionalMotorSubsystem(PositionalMotorSubsystemConfiguration builder) { + protected MotorSubsystem(MotorSubsystemConfiguration builder) { this.controller = builder.controller; this.controller.setTolerance(builder.acceptableError); acceptableError = builder.acceptableError; @@ -248,8 +248,8 @@ public void periodic() { } } - /** A configuration for a PositionalMotorSubsystem */ - public static class PositionalMotorSubsystemConfiguration { + /** A configuration for a MotorSubsystem */ + public static class MotorSubsystemConfiguration { /** The default acceptable position error. */ public static final double DEFAULT_ERROR = 5.0; @@ -273,7 +273,7 @@ public static class PositionalMotorSubsystemConfiguration { * @param motor the motor to control * @param encoder the encoder providing feedback */ - public PositionalMotorSubsystemConfiguration(Motor motor, Encoder encoder) { + public MotorSubsystemConfiguration(Motor motor, Encoder encoder) { this.motor = Objects.requireNonNull(motor, "motor should not be null"); this.encoder = Objects.requireNonNull(encoder, "encoder should not be null"); controller = new PIDController(0, 0, 0); @@ -290,7 +290,7 @@ public PositionalMotorSubsystemConfiguration(Motor motor, Encoder encoder) { * * @param motor the integrated motor controller */ - public PositionalMotorSubsystemConfiguration(PIDMotor motor) { + public MotorSubsystemConfiguration(PIDMotor motor) { this(motor, motor); } @@ -300,7 +300,7 @@ public PositionalMotorSubsystemConfiguration(PIDMotor motor) { * @param controller The PID controller * @return {@code this} for chaining */ - public PositionalMotorSubsystemConfiguration controller(PIDController controller) { + public MotorSubsystemConfiguration controller(PIDController controller) { this.controller = controller; return this; } @@ -312,7 +312,7 @@ public PositionalMotorSubsystemConfiguration controller(PIDController controller * @param controlMode The mode to use when controlling the motor * @return {@code this} for chaining */ - public PositionalMotorSubsystemConfiguration controlMode(ControlMode controlMode) { + public MotorSubsystemConfiguration controlMode(ControlMode controlMode) { this.controlMode = controlMode; return this; } @@ -325,7 +325,7 @@ public PositionalMotorSubsystemConfiguration controlMode(ControlMode controlMode * @param d the derivative * @return {@code this} for chaining */ - public PositionalMotorSubsystemConfiguration PID(double p, double i, double d) { + public MotorSubsystemConfiguration PID(double p, double i, double d) { controller.setPID(p, i, d); return this; } @@ -336,7 +336,7 @@ public PositionalMotorSubsystemConfiguration PID(double p, double i, double d) { * @param startingPosition the initial setpoint * @return {@code this} for chaining */ - public PositionalMotorSubsystemConfiguration startingPosition(Angle startingPosition) { + public MotorSubsystemConfiguration startingPosition(Angle startingPosition) { this.startingPosition = startingPosition.in(this.rotationUnit); return this; } @@ -350,12 +350,12 @@ public PositionalMotorSubsystemConfiguration startingPosition(Angle startingPosi * @param startingPositionSupplier supplier to use to get the initial setpoint * @return {@code this} for chaining */ - public PositionalMotorSubsystemConfiguration startingPosition(Supplier startingPositionSupplier) { + public MotorSubsystemConfiguration startingPosition(Supplier startingPositionSupplier) { return startingPosition(startingPositionSupplier.get()); } /** Sets the acceptable position error. */ - public PositionalMotorSubsystemConfiguration acceptableError(double error) { + public MotorSubsystemConfiguration acceptableError(double error) { this.acceptableError = error; return this; } @@ -365,13 +365,13 @@ public PositionalMotorSubsystemConfiguration acceptableError(double error) { * * @param rotationUnit The angle unit to use for calculations */ - public PositionalMotorSubsystemConfiguration rotationUnit(AngleUnit rotationUnit) { + public MotorSubsystemConfiguration rotationUnit(AngleUnit rotationUnit) { startingPosition = rotationUnit.convertFrom(startingPosition, this.rotationUnit); this.rotationUnit = rotationUnit; return this; } - public PositionalMotorSubsystemConfiguration publishTo(NetworkTableInstance ntInstance) { + public MotorSubsystemConfiguration publishTo(NetworkTableInstance ntInstance) { this.ntInstance = ntInstance; return this; } From 4a94d3dac316b1d497f7128a5f0d5cf7be50efdd Mon Sep 17 00:00:00 2001 From: spderman3333 Date: Mon, 13 Oct 2025 14:30:21 -0700 Subject: [PATCH 3/7] I wish spotless was automatic --- .../main/java/com/team2813/lib2813/control/Motor.java | 4 +--- .../lib2813/control/motors/SparkMaxWrapper.java | 4 ++-- .../lib2813/control/motors/TalonFXWrapper.java | 10 +++++++--- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/lib/src/main/java/com/team2813/lib2813/control/Motor.java b/lib/src/main/java/com/team2813/lib2813/control/Motor.java index c73bca6f..80bad2c5 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/Motor.java +++ b/lib/src/main/java/com/team2813/lib2813/control/Motor.java @@ -30,8 +30,6 @@ public interface Motor { */ Current getAppliedCurrent(); - /** - * Stops the motor. - */ + /** Stops the motor. */ void disable(); } diff --git a/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java b/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java index 073594e8..b1ccc032 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java +++ b/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java @@ -83,8 +83,8 @@ public Current getAppliedCurrent() { } /** - * WARNING: due to the end of support of SparkMaxWrapper, there is no evidence that this method will work. - * Proceed with caution! + * WARNING: due to the end of support of SparkMaxWrapper, there is no evidence that this method + * will work. Proceed with caution! */ @Override public void disable() { diff --git a/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java b/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java index 08c10542..ec6cc48b 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java +++ b/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java @@ -163,11 +163,14 @@ public TalonFX motor() { } /** - * Sets the behavior the motor should exhibit upon receiving a request to stop: "disable()". + * Sets the behavior the motor should exhibit upon receiving a request to stop: + * "disable()". + * *
    - *
  • Coast: The motor stops applying an input, but continues to move with its inertia.
  • - *
  • Brake: The motor stops applying an input, and actively opposes its inertia.
  • + *
  • Coast: The motor stops applying an input, but continues to move with its inertia. + *
  • Brake: The motor stops applying an input, and actively opposes its inertia. *
+ * * @param mode */ public void setNeutralMode(NeutralModeValue mode) { @@ -176,6 +179,7 @@ public void setNeutralMode(NeutralModeValue mode) { /** * Sends a disable command to the motor, placing it in its neutral value. + * * @see TalonFXWrapper#setNeutralMode(NeutralModeValue) */ @Override From f3e542af184cd129cf783f7fe9968f3dc52f78b4 Mon Sep 17 00:00:00 2001 From: spderman3333 Date: Mon, 13 Oct 2025 14:35:16 -0700 Subject: [PATCH 4/7] Removed unnessesary deprecation. --- .../com/team2813/lib2813/control/motors/SparkMaxWrapper.java | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java b/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java index b1ccc032..0a9b1e81 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java +++ b/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java @@ -20,7 +20,6 @@ import java.util.ArrayList; import java.util.List; -@Deprecated(forRemoval = true) // We likely wont use sparkmax's ever again. public class SparkMaxWrapper implements PIDMotor { private final List followers = new ArrayList<>(); private final SparkBase motor; @@ -88,7 +87,7 @@ public Current getAppliedCurrent() { */ @Override public void disable() { - motor.disable(); + motor.stopMotor(); } @Override From 3305d278dec09b74555889aa63917bbb8f80815d Mon Sep 17 00:00:00 2001 From: spderman3333 Date: Mon, 13 Oct 2025 15:22:59 -0700 Subject: [PATCH 5/7] Removed discord.xml, an unnesessary file, and added it to gitignore in .idea --- .idea/.gitignore | 1 + .idea/discord.xml | 14 -------------- 2 files changed, 1 insertion(+), 14 deletions(-) delete mode 100644 .idea/discord.xml diff --git a/.idea/.gitignore b/.idea/.gitignore index 26d33521..38e29aac 100644 --- a/.idea/.gitignore +++ b/.idea/.gitignore @@ -1,3 +1,4 @@ # Default ignored files /shelf/ /workspace.xml +discord.xml \ No newline at end of file diff --git a/.idea/discord.xml b/.idea/discord.xml deleted file mode 100644 index 912db825..00000000 --- a/.idea/discord.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - - - \ No newline at end of file From 8086eded1947be75752a1ee7cb97bdb9b9ecdab1 Mon Sep 17 00:00:00 2001 From: spderman3333 Date: Mon, 13 Oct 2025 15:27:14 -0700 Subject: [PATCH 6/7] Refactored some javadocs. --- .../com/team2813/lib2813/control/motors/SparkMaxWrapper.java | 4 ---- .../com/team2813/lib2813/control/motors/TalonFXWrapper.java | 3 ++- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java b/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java index 0a9b1e81..8ac34981 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java +++ b/lib/src/main/java/com/team2813/lib2813/control/motors/SparkMaxWrapper.java @@ -81,10 +81,6 @@ public Current getAppliedCurrent() { return Units.Amps.of(motor.getOutputCurrent()); } - /** - * WARNING: due to the end of support of SparkMaxWrapper, there is no evidence that this method - * will work. Proceed with caution! - */ @Override public void disable() { motor.stopMotor(); diff --git a/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java b/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java index ec6cc48b..33a585d9 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java +++ b/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java @@ -13,6 +13,7 @@ import com.team2813.lib2813.control.DeviceInformation; import com.team2813.lib2813.control.InvertType; import com.team2813.lib2813.control.PIDMotor; +import com.team2813.lib2813.subsystems.MotorSubsystem; import com.team2813.lib2813.util.InvalidCanIdException; import edu.wpi.first.units.Units; import edu.wpi.first.units.measure.Angle; @@ -164,7 +165,7 @@ public TalonFX motor() { /** * Sets the behavior the motor should exhibit upon receiving a request to stop: - * "disable()". + * {@link MotorSubsystem#disable()} * *
    *
  • Coast: The motor stops applying an input, but continues to move with its inertia. From 63e173b407c89a75c0e2f184f38e7200f863b0ce Mon Sep 17 00:00:00 2001 From: spderman3333 Date: Mon, 13 Oct 2025 15:31:36 -0700 Subject: [PATCH 7/7] Spotless --- .idea/compiler.xml | 22 +++++++++++++++++++ .../control/motors/TalonFXWrapper.java | 4 ++-- 2 files changed, 24 insertions(+), 2 deletions(-) diff --git a/.idea/compiler.xml b/.idea/compiler.xml index b589d56e..cdd14b22 100644 --- a/.idea/compiler.xml +++ b/.idea/compiler.xml @@ -1,6 +1,28 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java b/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java index 33a585d9..69437281 100644 --- a/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java +++ b/lib/src/main/java/com/team2813/lib2813/control/motors/TalonFXWrapper.java @@ -164,8 +164,8 @@ public TalonFX motor() { } /** - * Sets the behavior the motor should exhibit upon receiving a request to stop: - * {@link MotorSubsystem#disable()} + * Sets the behavior the motor should exhibit upon receiving a request to stop: {@link + * MotorSubsystem#disable()} * *
      *
    • Coast: The motor stops applying an input, but continues to move with its inertia.