Class AbstractMotorSubsystem<TConfig extends AbstractMotorSubsystemConfig>

java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
frc.robot.shared.subsystems.AbstractSubsystem<TConfig>
frc.robot.shared.subsystems.AbstractMotorSubsystem<TConfig>
Type Parameters:
TConfig - configuration type that supplies PID and feedforward gains
All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj2.command.Subsystem
Direct Known Subclasses:
AbstractSetAndSeekSubsystem, AbstractVelocitySubsystem

public abstract class AbstractMotorSubsystem<TConfig extends AbstractMotorSubsystemConfig> extends AbstractSubsystem<TConfig>
Base subsystem for any mechanism driven by a single motor with feedforward estimation and SysId support.

Position-based (set-and-seek) and velocity-based subsystems both extend this class to share motor lifecycle management, voltage clamping, feedforward configuration, SysId routine creation, and AdvantageKit motor input logging. Concrete subclasses add their own controller (profiled PID for position, standard PID for velocity) and expose an appropriate public API.

  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    protected edu.wpi.first.math.controller.SimpleMotorFeedforward
    Feedforward model used to estimate the voltage needed to maintain a desired velocity.
    protected final Motor
    Motor used to drive the mechanism.
    protected final frc.robot.devices.motor.MotorIOInputsAutoLogged
    Logged motor inputs snapshot used for telemetry and replay.

    Fields inherited from class frc.robot.shared.subsystems.AbstractSubsystem

    className, config, enabled, kDt, log, verbose
  • Constructor Summary

    Constructors
    Modifier
    Constructor
    Description
    protected
    Creates a motor-driven subsystem with feedforward estimation and SysId support.
  • Method Summary

    Modifier and Type
    Method
    Description
    protected void
    applyVoltage(double voltageCommand)
    Clamps a voltage command to the safe range (±12V) and sends it to the motor.
    double
    Returns the current measured position of the mechanism in radians.
    double
    Returns the current measured velocity of the mechanism in radians per second.
    edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine
    Exposes the underlying SysId routine so command factories can build characterization commands without subsystems manufacturing commands.
    void
    Logs the successful completion of a SysId routine.
    void
    Logs when a SysId routine is interrupted before completion.
    void
    Logs the start of a SysId routine for operator awareness.
    void
    Refreshes feedforward configuration when not attached to the FMS, and logs motor inputs every cycle.
    protected void
    Re-reads feedforward gains from config so live tuning updates affect voltage estimates immediately.
    void
    Stops the motor and resets subsystem state to a safe idle condition.
    protected void
    Refreshes motor sensor data and logs it via AdvantageKit for telemetry and replay.

    Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase

    addChild, getName, getSubsystem, initSendable, setName, setSubsystem

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait

    Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem

    defer, getCurrentCommand, getDefaultCommand, idle, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, simulationPeriodic, startEnd, startRun
  • Field Details

    • motor

      protected final Motor motor
      Motor used to drive the mechanism.
    • motorInputs

      protected final frc.robot.devices.motor.MotorIOInputsAutoLogged motorInputs
      Logged motor inputs snapshot used for telemetry and replay.
    • feedforward

      protected edu.wpi.first.math.controller.SimpleMotorFeedforward feedforward
      Feedforward model used to estimate the voltage needed to maintain a desired velocity.
  • Constructor Details

    • AbstractMotorSubsystem

      protected AbstractMotorSubsystem(TConfig config, Motor motor)
      Creates a motor-driven subsystem with feedforward estimation and SysId support.
      Parameters:
      config - configuration bundle supplying PID and feedforward gains
      motor - motor controller that reports position/velocity and accepts voltage commands, or null to use a disabled no-op motor
  • Method Details

    • periodic

      public void periodic()
      Refreshes feedforward configuration when not attached to the FMS, and logs motor inputs every cycle.

      Motor inputs (encoder position, velocity, current, temperature, etc.) are captured each cycle so telemetry is always available, even when no command is actively driving the mechanism. Override this if you need additional periodic behavior, but call super.periodic() to keep live tuning updates and motor input logging active.

    • getSysIdRoutine

      public edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine getSysIdRoutine()
      Exposes the underlying SysId routine so command factories can build characterization commands without subsystems manufacturing commands.
      Returns:
      configured SysId routine for the primary motor
    • logSysIdStart

      public void logSysIdStart()
      Logs the start of a SysId routine for operator awareness.

      Call this once before running a SysId command sequence so the console reflects the upcoming characterization sweep.

    • logSysIdEnd

      public void logSysIdEnd()
      Logs the successful completion of a SysId routine.

      Call this after a SysId command finishes to confirm the characterization sweep completed.

    • logSysIdInterrupted

      public void logSysIdInterrupted()
      Logs when a SysId routine is interrupted before completion.

      Call this when a SysId command is cancelled or interrupted so operators know the sweep did not finish.

    • getMeasuredPositionRadians

      public double getMeasuredPositionRadians()
      Returns the current measured position of the mechanism in radians.
      Returns:
      measured position in radians
    • getMeasuredVelocityRadiansPerSecond

      public double getMeasuredVelocityRadiansPerSecond()
      Returns the current measured velocity of the mechanism in radians per second.
      Returns:
      measured velocity in radians per second
    • stop

      public void stop()
      Stops the motor and resets subsystem state to a safe idle condition.

      Subclasses override this method to zero out controller state (velocity targets, profile goals, etc.) and then call super.stop() so the motor is always halted at the end of the chain.

    • updateAndLogMotorInputs

      protected void updateAndLogMotorInputs()
      Refreshes motor sensor data and logs it via AdvantageKit for telemetry and replay.

      Call this from the concrete subsystem's control loop before computing PID/feedforward so the controller reads fresh sensor values.

    • applyVoltage

      protected void applyVoltage(double voltageCommand)
      Clamps a voltage command to the safe range (±12V) and sends it to the motor.
      Parameters:
      voltageCommand - requested motor voltage in volts before clamping
    • refreshFeedforward

      protected void refreshFeedforward()
      Re-reads feedforward gains from config so live tuning updates affect voltage estimates immediately.