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/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/Motor.java b/lib/src/main/java/com/team2813/lib2813/control/Motor.java index 6c92ed0b..80bad2c5 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,7 @@ 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..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,6 +81,11 @@ public Current getAppliedCurrent() { return Units.Amps.of(motor.getOutputCurrent()); } + @Override + public void disable() { + motor.stopMotor(); + } + @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..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 @@ -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; @@ -162,10 +163,31 @@ public TalonFX motor() { return motor; } + /** + * Sets the behavior the motor should exhibit upon receiving a request to stop: {@link + * MotorSubsystem#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/MotorSubsystem.java index c8052804..d2e76276 100644 --- a/lib/src/main/java/com/team2813/lib2813/subsystems/MotorSubsystem.java +++ b/lib/src/main/java/com/team2813/lib2813/subsystems/MotorSubsystem.java @@ -136,7 +136,7 @@ public final void enable() { */ public final void disable() { isEnabled = false; - motor.set(controlMode, 0); + motor.disable(); } /**