Class AbstractVelocitySubsystem<TConfig extends AbstractVelocitySubsystemConfig>

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

public abstract class AbstractVelocitySubsystem<TConfig extends AbstractVelocitySubsystemConfig> extends AbstractMotorSubsystem<TConfig>
Base subsystem for mechanisms that maintain a target velocity using feedforward and PID control.

All RPM values in the public API represent mechanism (flywheel) speed after gear reduction, not motor shaft speed. The gear ratio is applied at the motor encoder conversion layer, so subsystem code never deals with motor-side rotations. Internally, all velocity math uses radians per second to align with WPILib conventions.

When maximumAccelerationRpmPerSecond in config is greater than zero, the subsystem uses a trapezoidal profile to ramp velocity smoothly. When it is zero, the subsystem applies direct PID + feedforward control without a ramp.

  • Field Details

    • controller

      protected final edu.wpi.first.math.controller.PIDController controller
      PID controller that corrects velocity error.
  • Constructor Details

    • AbstractVelocitySubsystem

      protected AbstractVelocitySubsystem(TConfig config, Motor motor)
      Creates a velocity-controlled subsystem with PID, feedforward, and optional trapezoidal velocity ramp.
      Parameters:
      config - configuration bundle supplying velocity limits, PID gains, and feedforward gains
      motor - motor controller that reports velocity and accepts voltage commands, or null to use a disabled no-op motor
  • Method Details

    • buildVelocityMotor

      protected static <TMotorConfig extends MotorConfig> Motor buildVelocityMotor(AbstractVelocitySubsystemConfig config, TMotorConfig motorConfig, Function<TMotorConfig,Motor> realFactory, AbstractVelocitySubsystem.TriFunction<TMotorConfig,Supplier<Double>,Supplier<Double>,Motor> simFactory)
      Builds the correct motor implementation for the current environment using the shared velocity subsystem pattern.

      Returns null when the config is disabled so the parent falls back to DisabledMotor. Real and simulation motors are selected using the provided factory functions.

      Type Parameters:
      TMotorConfig - concrete motor config type
      Parameters:
      config - velocity subsystem config supplying max velocity and acceleration for sim motor suppliers
      motorConfig - motor-specific configuration bundle (CAN ID, gear ratio, inversion, etc.)
      realFactory - factory function that creates the real motor from a motor config
      simFactory - factory function that creates the sim motor from a motor config and velocity/acceleration suppliers
      Returns:
      configured motor, or null when the subsystem is disabled
    • periodic

      public void periodic()
      Refreshes motor, feedforward, and PID configuration when not attached to the FMS, and logs common velocity telemetry.

      Override this if you need additional periodic behavior, but call super.periodic() to keep live tuning updates and common telemetry active.

      Specified by:
      periodic in interface edu.wpi.first.wpilibj2.command.Subsystem
      Overrides:
      periodic in class AbstractMotorSubsystem<TConfig extends AbstractVelocitySubsystemConfig>
    • setTargetVelocityRpm

      public void setTargetVelocityRpm(double targetRpm)
      Sets a new target velocity for the mechanism. Values are clamped to the configured maximum in both directions.

      The target is in mechanism RPM (after gear reduction). Positive values spin the mechanism forward; negative values spin it in reverse. Requested and clamped values are logged for tuning visibility.

      The settle timer and tolerance flag are only reset when the measured velocity is outside tolerance of the new target. This prevents reset-flicker in distance-based commands where the interpolated target drifts slightly each cycle while the mechanism is already tracking within tolerance. Large target jumps (e.g., idle to full speed) still trigger a full reset and settle window.

      Parameters:
      targetRpm - desired mechanism velocity in RPM (0 to stop, positive for forward, negative for reverse)
    • seekVelocity

      public void seekVelocity()
      Advances the velocity controller by one cycle: updates motor inputs, steps the optional velocity ramp, computes PID + feedforward, and applies the voltage to the motor.
    • isAtTargetVelocity

      public boolean isAtTargetVelocity()
      Reports whether the measured velocity is within tolerance of the target and has been stable for the configured settle time.
      Returns:
      true when the mechanism is at the target velocity and has been stable long enough
    • isWithinTolerance

      public boolean isWithinTolerance()
      Reports whether the measured velocity is currently within tolerance of the target, without requiring the settle timer.

      Use this for continuously-updating targets (such as distance-based RPM) where the settle timer resets each time the target changes. isAtTargetVelocity() is still preferred for fixed-target scenarios where stability over time matters.

      Returns:
      true when the measured velocity is within tolerance of the current target right now
    • isReady

      public boolean isReady()
      Reports whether the subsystem is ready for downstream consumers.

      This is a stable, uniform API that all velocity subsystems expose. Composite commands and cross-subsystem suppliers should prefer this method over subsystem-specific readiness checks so wiring code stays consistent across mechanisms.

      Returns:
      true when the mechanism is at the target velocity and has been stable long enough
    • getTargetVelocityRpm

      public double getTargetVelocityRpm()
      Returns the current target velocity in RPM.
      Returns:
      target velocity in mechanism RPM
    • getMeasuredVelocityRpm

      public double getMeasuredVelocityRpm()
      Returns the current measured velocity in RPM.
      Returns:
      measured velocity in mechanism RPM
    • getIdleVelocityRpm

      public double getIdleVelocityRpm()
      Returns the configured idle velocity in RPM.

      Commands can use this to set the target to the idle speed without direct config access.

      Returns:
      idle velocity in mechanism RPM from config
    • stop

      public void stop()
      Resets velocity controller state to zero and stops the motor.

      Clears the target velocity, setpoint, tolerance flag, and trapezoidal profile state so the mechanism is fully idle.

      Overrides:
      stop in class AbstractMotorSubsystem<TConfig extends AbstractVelocitySubsystemConfig>