Class MARSShooter

java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
frc.robot.subsystems.MARSShooter
All Implemented Interfaces:
SystemTestable, edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj2.command.Subsystem

public class MARSShooter extends edu.wpi.first.wpilibj2.command.SubsystemBase implements SystemTestable
Generic flywheel subsystem used for the main shooter, floor intake, and feeder.

Despite its name, this class is a general-purpose velocity-controlled flywheel wrapper. In RobotContainer, three separate instances are created:

  • shooter — the main scoring flywheel (4-motor, high-velocity)
  • floorIntake — ground pickup rollers
  • feeder — internal transfer mechanism

Each instance accepts a FlywheelIO implementation via dependency injection, allowing seamless switching between real hardware (FlywheelIOTalonFX) and physics simulation (FlywheelIOSim).

  • Constructor Summary

    Constructors
    Constructor
    Description
    MARSShooter(String name, FlywheelIO io, MARSPowerManager powerManager)
    Constructs the shooter subsystem.
  • Method Summary

    Modifier and Type
    Method
    Description
    edu.wpi.first.wpilibj2.command.Command
    Generates an autonomous, state-machine style verification routine for this subsystem.
    double
    Gets the current velocity of the shooter flywheel.
    boolean
    Returns whether the flywheel velocity is within 20 rad/s of the target.
    void
     
    void
    setClosedLoopVelocity(double speed)
    Runs the flywheel at a target velocity using the motor's internal closed-loop controller and dynamically injects the calculated feedforward voltage.
    void
    setVoltage(double volts)
    Directly sets the shooter motor voltage.
    edu.wpi.first.wpilibj2.command.Command
    Returns a command that continuously spins the flywheel at the default scoring velocity.
    edu.wpi.first.wpilibj2.command.Command
    sysIdDynamic(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
    Generates a SysId Dynamic characterization command.
    edu.wpi.first.wpilibj2.command.Command
    sysIdQuasistatic(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
    Generates a SysId Quasistatic characterization command.

    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
  • Constructor Details

    • MARSShooter

      public MARSShooter(String name, FlywheelIO io, MARSPowerManager powerManager)
      Constructs the shooter subsystem.
      Parameters:
      name - The unique identifier for this flywheel instance (e.g., Shooter, FloorIntake, Feeder)
      io - The hardware abstraction layer for the shooter flywheel motor.
      powerManager - The active power manager for load-shedding voltage queries.
  • Method Details

    • periodic

      public void periodic()
      Specified by:
      periodic in interface edu.wpi.first.wpilibj2.command.Subsystem
    • spinUpCommand

      public edu.wpi.first.wpilibj2.command.Command spinUpCommand()
      Returns a command that continuously spins the flywheel at the default scoring velocity.
      Returns:
      A Command that runs the flywheel at ~400 rad/s using closed-loop control.
    • setVoltage

      public void setVoltage(double volts)
      Directly sets the shooter motor voltage. Used for open-loop manual control.
      Parameters:
      volts - The voltage to apply.
    • setClosedLoopVelocity

      public void setClosedLoopVelocity(double speed)
      Runs the flywheel at a target velocity using the motor's internal closed-loop controller and dynamically injects the calculated feedforward voltage.
      Parameters:
      speed - Target velocity in radians per second.
    • isAtTolerance

      public boolean isAtTolerance()
      Returns whether the flywheel velocity is within 20 rad/s of the target.
      Returns:
      true if the flywheel is at the commanded velocity within tolerance.
    • sysIdQuasistatic

      public edu.wpi.first.wpilibj2.command.Command sysIdQuasistatic(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
      Generates a SysId Quasistatic characterization command.
      Parameters:
      direction - The direction of the quasistatic routine (Forward/Reverse).
      Returns:
      The SysId Command to execute.
    • sysIdDynamic

      public edu.wpi.first.wpilibj2.command.Command sysIdDynamic(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction direction)
      Generates a SysId Dynamic characterization command.
      Parameters:
      direction - The direction of the dynamic routine (Forward/Reverse).
      Returns:
      The SysId Command to execute.
    • getVelocityRadPerSec

      public double getVelocityRadPerSec()
      Gets the current velocity of the shooter flywheel.
      Returns:
      Velocity in radians per second.
    • getSystemCheckCommand

      public edu.wpi.first.wpilibj2.command.Command getSystemCheckCommand()
      Description copied from interface: SystemTestable
      Generates an autonomous, state-machine style verification routine for this subsystem.
      Specified by:
      getSystemCheckCommand in interface SystemTestable
      Returns:
      A command that runs through diagnostic checks and logs results.