Class MotorSubsystem<T extends Supplier<Angle>>

java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
com.team2813.lib2813.subsystems.MotorSubsystem<T>
Type Parameters:
T - the type of the Supplier<Angle> used to specify setpoints.
All Implemented Interfaces:
Sendable, Subsystem

public abstract class MotorSubsystem<T extends Supplier<Angle>> extends SubsystemBase
Defines a generic subsystem comprising a motor and encoder.

The MotorSybsystem supports a dual operation mode:

  • PID Mode - the user set a destination position (aka "setpoint") and the motor subsystem engages a PID Controller to drive the motor to that setpoint.
  • Direct User Input Mode - the subsystem responds to direct input from the user (i.e., voltage or duty cycle).

The PID Mode is enabled by calling setSetpoint(T). The subsystem starts moving toward the setpoint and maintains position at the setpoint under the control of the PID controller. The motor system's isEnabled() returns true.

The Direct User Input Mode is activated when the user calls the Motor.set(ControlMode,double,double) or Motor.set(ControlMode,double) method on the motor field. The PID Mode is interrupted and disengaged, and isEnabled() returns false. It can be re-engaged with the enable() method and will resume movement toward setpoint.

  • Field Details

  • Constructor Details

  • Method Details

    • setSetpoint

      public final void setSetpoint(T position)
      Sets the desired setpoint to the provided value, and enables the PID control.
      Parameters:
      position - the position to go to.
    • setSetpointCommand

      public final Command setSetpointCommand(T setpoint)
      Returns a command that sets the desired setpoint to the provided value.
      Parameters:
      setpoint - the position to go to.
      Since:
      2.0.0
    • getSetpoint

      public final Angle getSetpoint()
      Returns the current setpoint as an angle.
    • atPosition

      public final boolean atPosition()
      Determines if the motor is at the current setpoint, within the acceptable error.
    • enable

      public final void enable()
      Engages the PID controller.

      The motor voltage will be periodically updated to move the motor towards the current setpoint.

      If this method is called after the motor drive toward setpoint was interrupted by user interruption, the motor will resume its movement towards the last set setpoint.

    • isEnabled

      public final boolean isEnabled()
      Returns whether the PID controller is engaged.

      When the PID controller is engaged, the motor system is moving toward the user-specified setpoint position (set via setSetpoint(T)), or, if it has already reached the setpoint, is maintaining that position.

      Returns:
      Whether the PID controller is engaged.
    • stopMotor

      public final void stopMotor()
      Stops the motor.

      The motor voltage will be set to zero, and the motor will not adjust to move towards the current setpoint.

      Since:
      2.0.0
    • stopMotorCommand

      public final Command stopMotorCommand()
      Returns a command that stops the motor.
      Since:
      2.0.0
    • clampOutput

      protected double clampOutput(double output)
      Extension point that allows subclasses to clamp the output.

      The default implementation returns the provided value.

      Parameters:
      output - Output provided by the PID controller.
      Returns:
      Output to provide to the motor.
      Since:
      2.0.0
      See Also:
    • getMeasurement

      protected final double getMeasurement()
      Returns the current position of the motor subsystem in the units specified by rotationUnit. This position is used by the PID controller (when it is enabled) to determine if it is already at position or needs to adjust the subsystem position to reach a user-specified setpoint.
    • periodic

      public void periodic()
      Applies the PID output to the motor if this subsystem is enabled.