Shooter Example
Template Project
Start with the Command Robot template project. Shooters are implemented as subsystems, so the command-based structure is ideal. Create a new subsystem class in the
subsystems package.Overview
Shooters require Velocity Control. The goal is to spin a flywheel at a specific RPM and maintain it despite load changes (launching a note/ball). We'll build a shooter subsystem using Velocity PID and Feedforward to maintain consistent speed.
Goals
The shooter subsystem must:
- Spin to target RPM (Close, Mid, Far).
- Maintain speed (Velocity PID).
- Recover quickly after shots.
- Report "Ready" status.
Step 1: Create Subsystem Structure
Start by creating the
Shooter class that extends SubsystemBase. This class will manage the shooter motor and velocity control.Create a new subsystem class in the
subsystems package. The Command Robot template provides ExampleSubsystem as a reference. Create your Shooter class with necessary imports:package frc.robot.subsystems;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.ctre.phoenix6.controls.VelocityVoltage;
public class Shooter extends SubsystemBase {
// We'll add fields here
}Step 2: Declare Motor and Control Objects
Add fields for the motor and velocity control. The motor is on CAN ID 7. For Talon FX, we create a
VelocityVoltage control request. For SPARK MAX, we get the closed-loop controller and encoder.Add motor and controller fields:
public class Shooter extends SubsystemBase {
// Shooter motor on CAN ID 7
private final TalonFX m_motor = new TalonFX(7);
// Velocity control request
private final VelocityVoltage m_request = new VelocityVoltage(0);
}Step 3: Configure Motor - Idle Mode
Set the motor to Coast mode. This allows the flywheel to spin down naturally when stopped, preventing rapid deceleration that wastes energy and causes wear. Brake mode would make the flywheel stop abruptly, which is undesirable for shooters.
Set motor to Coast mode:
public Shooter() {
TalonFXConfiguration config = new TalonFXConfiguration();
// Coast mode allows flywheel to spin down naturally
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
m_motor.getConfigurator().apply(config);
}Step 4: Configure Velocity PID Gains
Configure PID gains for velocity control. kP (Proportional) corrects velocity errors to maintain target speed. For flywheels, kP is typically small since feedforward does most of the work. kI and kD are usually set to 0 for velocity control.
Add velocity PID gains:
public Shooter() {
TalonFXConfiguration config = new TalonFXConfiguration();
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
// Velocity PID gains (Slot 0)
config.Slot0.kP = 0.1; // Proportional gain
config.Slot0.kI = 0.0; // Integral gain
config.Slot0.kD = 0.0; // Derivative gain
m_motor.getConfigurator().apply(config);
}Step 5: Configure Velocity Feedforward
Velocity feedforward (kV) is critical for maintaining speed. It provides the base voltage needed to maintain a given velocity. This is the most important value for velocity control—tune this first so the flywheel reaches target speed without PID correction.
Add velocity feedforward:
public Shooter() {
TalonFXConfiguration config = new TalonFXConfiguration();
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
config.Slot0.kP = 0.1;
config.Slot0.kI = 0.0;
config.Slot0.kD = 0.0;
// Velocity feedforward (critical for maintaining speed)
config.Slot0.kV = 0.12;
m_motor.getConfigurator().apply(config);
}Step 6: Add Method to Set Target Speed
Create a public method that sets the target velocity. The PID controller and feedforward work together to reach and maintain this speed.
Add method to set target velocity:
/**
* Set shooter target velocity
* @param rps Target velocity in rotations per second
*/
public void setSpeed(double rps) {
m_motor.setControl(m_request.withVelocity(rps));
}Step 7: Add Ready Status Check
Add a method to check if the shooter has reached the target speed. This is useful for coordinating with other mechanisms (like an indexer) that need to wait for the shooter to be ready before feeding game pieces.
Add method to check if shooter is at target speed:
/**
* Check if shooter is at target speed
* @param target Target velocity in rotations per second
* @return True if within 2.0 RPS of target
*/
public boolean isReady(double target) {
double currentVelocity = m_motor.getVelocity().getValue();
return Math.abs(currentVelocity - target) < 2.0;
}Step 8: Create Firing Sequence Command
Shooters often work with other mechanisms. Create a command sequence that spins up the shooter, waits until it's ready, then feeds the game piece. This ensures consistent shot velocity.
// In RobotContainer class - add this method or use in configureBindings()
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
import frc.robot.subsystems.Shooter;
import frc.robot.subsystems.Indexer;
/**
* Create command sequence for shooting
* @return Sequential command: spin up, wait, feed
*/
public Command getShootSequence() {
return new SequentialCommandGroup(
// Step 1: Start spinning up shooter to 4000 RPS
new InstantCommand(() -> m_shooter.setSpeed(4000), m_shooter),
// Step 2: Wait until shooter reaches target speed
new WaitUntilCommand(() -> m_shooter.isReady(4000)),
// Step 3: Feed note into shooter
new FeedCommand(m_indexer)
);
}Understanding Velocity Control
Velocity control maintains speed rather than position. Feedforward (kV) provides most of the power needed to maintain speed. PID (kP) corrects small errors caused by load changes or friction. Together, they keep the flywheel spinning at a consistent RPM despite disturbances.
Full Code - Shooter Subsystem
Complete shooter subsystem implementation:
package frc.robot.subsystems;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.ctre.phoenix6.controls.VelocityVoltage;
public class Shooter extends SubsystemBase {
// Shooter motor on CAN ID 7
private final TalonFX m_motor = new TalonFX(7);
// Velocity control request
private final VelocityVoltage m_request = new VelocityVoltage(0);
public Shooter() {
TalonFXConfiguration config = new TalonFXConfiguration();
// Coast mode allows flywheel to spin down naturally
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
// Velocity PID gains (Slot 0)
config.Slot0.kP = 0.1; // Proportional gain
config.Slot0.kI = 0.0; // Integral gain
config.Slot0.kD = 0.0; // Derivative gain
config.Slot0.kV = 0.12; // Velocity feedforward (critical for maintaining speed)
m_motor.getConfigurator().apply(config);
}
/**
* Set shooter target velocity
* @param rps Target velocity in rotations per second
*/
public void setSpeed(double rps) {
m_motor.setControl(m_request.withVelocity(rps));
}
/**
* Check if shooter is at target speed
* @param target Target velocity in rotations per second
* @return True if within 2.0 RPS of target
*/
public boolean isReady(double target) {
double currentVelocity = m_motor.getVelocity().getValue();
return Math.abs(currentVelocity - target) < 2.0;
}
}Full Code - Firing Sequence
// In RobotContainer class - add this method
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
import frc.robot.subsystems.Shooter;
import frc.robot.subsystems.Indexer;
// The template provides RobotContainer structure
/**
* Create command sequence for shooting
* @return Sequential command: spin up, wait, feed
*/
public Command getShootSequence() {
return new SequentialCommandGroup(
// Step 1: Start spinning up shooter to 4000 RPS
new InstantCommand(() -> m_shooter.setSpeed(4000), m_shooter),
// Step 2: Wait until shooter reaches target speed
new WaitUntilCommand(() -> m_shooter.isReady(4000)),
// Step 3: Feed note into shooter
new FeedCommand(m_indexer)
);
}Tuning Tips
For Velocity Control:
- Feedforward (kV): Most important! Tune this so it reaches target speed (open loop).
- Proportional (kP): Add small P to correct errors and recover speed after shots.
- D/I: Usually not needed for flywheels (inertia provides damping).
- Coast Mode: Prevents rapid deceleration, saving energy and reducing wear.
State Management
Shooters often need a state machine: Idle → SpinUp → Ready → Fire. Use commands and the
isReady() method to manage these states and coordinate with other mechanisms.Practice with WPILib Documentation
WPILib provides tuning documentation for velocity controllers, including feedforward control strategies essential for flywheels. Use these guides to practice tuning velocity controllers and understanding feedforward principles.