Class AbstractVelocityCommandFactory<TSubsystem extends AbstractVelocitySubsystem<?>>

java.lang.Object
frc.robot.shared.commands.AbstractSubsystemCommandFactory<TSubsystem>
frc.robot.shared.commands.AbstractVelocityCommandFactory<TSubsystem>
Type Parameters:
TSubsystem - concrete velocity subsystem type
Direct Known Subclasses:
FeederSubsystemCommandFactory, IndexerSubsystemCommandFactory, IntakeSubsystemCommandFactory, ShooterSubsystemCommandFactory

public abstract class AbstractVelocityCommandFactory<TSubsystem extends AbstractVelocitySubsystem<?>> extends AbstractSubsystemCommandFactory<TSubsystem>
Command factory for velocity-controlled subsystems that exposes common SysId characterization commands while keeping subsystems free of command creation.
  • Field Summary

    Fields inherited from class frc.robot.shared.commands.AbstractSubsystemCommandFactory

    subsystem
  • Constructor Summary

    Constructors
    Modifier
    Constructor
    Description
    protected
    Builds a command factory bound to a velocity subsystem.
  • Method Summary

    Modifier and Type
    Method
    Description
    edu.wpi.first.wpilibj2.command.Command
    Builds a command that continuously reads a target RPM from a supplier and seeks that velocity every cycle.
    protected abstract edu.wpi.first.wpilibj2.command.Command
    Builds the idle command for this velocity subsystem.
    edu.wpi.first.wpilibj2.command.Command
    Builds a command that stops the mechanism immediately by setting velocity to zero.
    edu.wpi.first.wpilibj2.command.Command
    createSysIdDynamicCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
    Creates a dynamic SysId characterization command that applies a step voltage in the requested direction.
    edu.wpi.first.wpilibj2.command.Command
    createSysIdDynamicCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction, double timeoutSeconds)
    Creates a dynamic SysId command with a timeout to prevent runaway motion.
    edu.wpi.first.wpilibj2.command.Command
    createSysIdDynamicCommandWithDefaultTimeout(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
    Creates a dynamic SysId command with a default timeout (3 seconds) to safeguard robot motion.
    edu.wpi.first.wpilibj2.command.Command
    Creates a full SysId sweep using timing values from the subsystem config.
    edu.wpi.first.wpilibj2.command.Command
    createSysIdFullSweepCommand(double delaySeconds, double quasistaticTimeoutSecs, double dynamicTimeoutSecs)
    Creates a full SysId sweep (quasistatic forward/reverse, dynamic forward/reverse) with optional delays between phases.
    edu.wpi.first.wpilibj2.command.Command
    createSysIdQuasistaticCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
    Creates a quasistatic SysId characterization command that ramps voltage slowly in the requested direction.
    edu.wpi.first.wpilibj2.command.Command
    createSysIdQuasistaticCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction, double timeoutSeconds)
    Creates a quasistatic SysId command with a timeout to prevent runaway motion.
    edu.wpi.first.wpilibj2.command.Command
    createSysIdQuasistaticCommandWithDefaultTimeout(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
    Creates a quasistatic SysId command with a default timeout (3 seconds) to safeguard robot motion.
    edu.wpi.first.wpilibj2.command.Command
    Sets the idle command as the default command for this velocity subsystem.

    Methods inherited from class frc.robot.shared.commands.AbstractSubsystemCommandFactory

    getSubsystem

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • AbstractVelocityCommandFactory

      protected AbstractVelocityCommandFactory(TSubsystem subsystem)
      Builds a command factory bound to a velocity subsystem.
      Parameters:
      subsystem - velocity subsystem instance shared by generated commands
  • Method Details

    • createSysIdQuasistaticCommand

      public edu.wpi.first.wpilibj2.command.Command createSysIdQuasistaticCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
      Creates a quasistatic SysId characterization command that ramps voltage slowly in the requested direction.
      Parameters:
      direction - sweep direction (forward or reverse)
      Returns:
      command that runs the quasistatic test until completion
    • createSysIdQuasistaticCommand

      public edu.wpi.first.wpilibj2.command.Command createSysIdQuasistaticCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction, double timeoutSeconds)
      Creates a quasistatic SysId command with a timeout to prevent runaway motion.
      Parameters:
      direction - sweep direction (forward or reverse)
      timeoutSeconds - maximum duration before the command ends
      Returns:
      timed quasistatic SysId command
    • createSysIdQuasistaticCommandWithDefaultTimeout

      public edu.wpi.first.wpilibj2.command.Command createSysIdQuasistaticCommandWithDefaultTimeout(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
      Creates a quasistatic SysId command with a default timeout (3 seconds) to safeguard robot motion.
      Parameters:
      direction - sweep direction (forward or reverse)
      Returns:
      timed quasistatic SysId command
    • createSysIdDynamicCommand

      public edu.wpi.first.wpilibj2.command.Command createSysIdDynamicCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
      Creates a dynamic SysId characterization command that applies a step voltage in the requested direction.
      Parameters:
      direction - sweep direction (forward or reverse)
      Returns:
      command that runs the dynamic test until completion
    • createSysIdDynamicCommand

      public edu.wpi.first.wpilibj2.command.Command createSysIdDynamicCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction, double timeoutSeconds)
      Creates a dynamic SysId command with a timeout to prevent runaway motion.
      Parameters:
      direction - sweep direction (forward or reverse)
      timeoutSeconds - maximum duration before the command ends
      Returns:
      timed dynamic SysId command
    • createSysIdDynamicCommandWithDefaultTimeout

      public edu.wpi.first.wpilibj2.command.Command createSysIdDynamicCommandWithDefaultTimeout(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
      Creates a dynamic SysId command with a default timeout (3 seconds) to safeguard robot motion.
      Parameters:
      direction - sweep direction (forward or reverse)
      Returns:
      timed dynamic SysId command
    • createSysIdFullSweepCommand

      public edu.wpi.first.wpilibj2.command.Command createSysIdFullSweepCommand()
      Creates a full SysId sweep using timing values from the subsystem config.

      Reads sysIdDelaySeconds, sysIdQuasistaticTimeoutSeconds, and sysIdDynamicTimeoutSeconds from the subsystem's configuration so each mechanism can define its own timing without changing bindings code.

      Returns:
      command that executes the four standard SysId tests in sequence
    • createSysIdFullSweepCommand

      public edu.wpi.first.wpilibj2.command.Command createSysIdFullSweepCommand(double delaySeconds, double quasistaticTimeoutSecs, double dynamicTimeoutSecs)
      Creates a full SysId sweep (quasistatic forward/reverse, dynamic forward/reverse) with optional delays between phases.
      Parameters:
      delaySeconds - pause inserted between each phase to let the mechanism settle
      quasistaticTimeoutSecs - timeout for each quasistatic sweep to prevent runaway motion
      dynamicTimeoutSecs - timeout for each dynamic sweep to prevent runaway motion
      Returns:
      command that executes the four standard SysId tests in sequence
    • createStopCommand

      public edu.wpi.first.wpilibj2.command.Command createStopCommand()
      Builds a command that stops the mechanism immediately by setting velocity to zero.
      Returns:
      command that stops the motor in a single cycle
    • setDefaultIdleCommand

      public edu.wpi.first.wpilibj2.command.Command setDefaultIdleCommand()
      Sets the idle command as the default command for this velocity subsystem.

      Call this once during RobotContainer construction so the subsystem returns to its idle behavior whenever no other command is scheduled.

      Returns:
      the idle command that was set as default
    • createContinuousVelocityCommand

      public edu.wpi.first.wpilibj2.command.Command createContinuousVelocityCommand(Supplier<Double> targetRpmSupplier)
      Builds a command that continuously reads a target RPM from a supplier and seeks that velocity every cycle.

      Unlike commands that lock the target at initialization, this command re-evaluates the supplier each cycle. Use this when the target is backed by a tunable value that operators may adjust while the command is running.

      When the command ends (button released or interrupted), the subsystem targets zero RPM and runs one final control cycle so the motor, simulation model, and telemetry all reflect the stopped state.

      Parameters:
      targetRpmSupplier - provider for the target RPM; evaluated every execute cycle
      Returns:
      command that continuously tracks the supplied RPM until interrupted, then stops cleanly
    • createIdleCommand

      protected abstract edu.wpi.first.wpilibj2.command.Command createIdleCommand()
      Builds the idle command for this velocity subsystem.

      Each concrete factory returns its own idle command type. The base factory uses this method in setDefaultIdleCommand() to wire the subsystem's default behavior.

      Returns:
      command that idles the mechanism at its configured idle RPM