Lesson 2.2: Commands
π― What Youβll Learn
By the end of this lesson you will be able to:
- Explain what a command is and how it relates to subsystems
- Describe the four lifecycle methods every command has
- Read through
AutoShootCommandand explain what each section does - Identify inline commands in
RobotContainerand explain how they work - Understand command groups and how they combine simple commands into complex behaviors
The Mental Model: Command = Instruction
In Lesson 2.1 you learned that subsystems are capabilities β they answer βwhat can the robot do?β Now itβs time for the other half:
A command is an instruction that tells one or more subsystems what to do and when to do it.
Think of it like a restaurant kitchen:
- Subsystems are the kitchen stations β the grill, the fryer, the prep counter. Each station has equipment and knows how to use it.
- Commands are the orders β βmake a burger,β βfry the onion rings,β βplate the meal.β An order tells the stations what to do, in what sequence, and when to stop.
Without commands, subsystems just sit there doing nothing. Without subsystems, commands have nothing to control. They work together.
The Command Lifecycle
Every command in WPILib follows the same four-method lifecycle. When the command scheduler runs a command, it calls these methods in order:
| Method | When It Runs | What It Does |
|---|---|---|
initialize() | Once, when the command first starts | Set up initial state β reset timers, zero out variables |
execute() | Every ~20ms while the command is running | Do the actual work β move motors, check sensors, make decisions |
isFinished() | After every execute() call | Return true to end the command, false to keep going |
end(interrupted) | Once, when the command stops | Clean up β stop motors, reset state. The interrupted parameter tells you if the command was cancelled early |
Hereβs the flow as a timeline:
Command starts β βΌinitialize() β runs once β βΌβββΊ execute() β runs every 20msβ ββ βΌβ isFinished()?β ββ βββ false βββββββββ (loop back to execute)β ββ βββ trueβ ββ βΌβ end(false) β normal finishββ OR if cancelled:β end(true) β interruptedisFinished()would check if 2 seconds have passed and returntruewhen the time is up.end(interrupted)would stop the motor. This is the right place for cleanup becauseend()runs whether the command finishes normally OR gets cancelled early. If you stopped the motor inisFinished(), it wouldnβt stop if the command was interrupted!
A common pattern: initialize() starts a timer, execute() runs the motor, isFinished() checks the timer, and end() stops the motor.
Walking Through AutoShootCommand
Now letβs read a real command from your robot project.
What does AutoShootCommand do?
Coordinates turret aiming, flywheel spin-up, and note feeding. It runs continuously (never finishes on its own) and handles everything:
- Aims the turret at the target, compensating for robot movement
- Calculates distance to the target
- Sets hood angle and flywheel speed based on that distance
- Feeds the note once the turret is aimed AND flywheels are at speed
The constructor β declaring dependencies
Look at the constructor first:
public AutoShootCommand(TurretSubsystem turret, ShooterSubsystem shooter, CommandSwerveDrivetrain drivetrain, Supplier<Pose2d> targetSupplier, Supplier<Boolean> trajectoryPassingSupplier, boolean allianceZoneOnly) { this.turret = turret; this.shooter = shooter; this.drivetrain = drivetrain; this.targetSupplier = targetSupplier; this.trajectoryPassingSupplier = trajectoryPassingSupplier; this.allianceZoneOnly = allianceZoneOnly; addRequirements(turret, shooter);}Two important things to notice:
-
The subsystems are passed in as parameters β the command doesnβt create them. This is called dependency injection. RobotContainer creates the subsystems and hands them to the command.
-
addRequirements(turret, shooter)β this tells the command scheduler βI need exclusive access to the turret and shooter.β If another command tries to use the turret while AutoShootCommand is running, the scheduler will cancel one of them. This prevents two commands from fighting over the same motor.
initialize() β resetting state
@Overridepublic void initialize() { feeding = false; readyTimestamp = 0.0; targetPose = targetSupplier.get();}Simple and clean. Reset the feeding flag, clear the timer, and grab the current target position. This runs once when the driver presses the Y button.
execute() β the main loop
The execute() method is where all the action happens. It runs every 20ms and follows a clear step-by-step sequence:
@Overridepublic void execute() { // Step 1: Update target (changes as robot crosses field zones) targetPose = targetSupplier.get();
// Step 2: Aim the turret with velocity compensation turret.aimAtPose(robotPose, targetPose, fieldSpeeds);
// Step 3: Calculate distance to target double distance = robotPose.getTranslation().getDistance(compensatedTarget);
// Step 4: Set hood angle and flywheel speed based on distance shooter.autoAim(distance);
// Step 5: When aimed AND flywheels ready, feed the note if (aimed && flywheelsReady && /* other safety checks */) { shooter.runFeeder(0.85); }}Notice how the command coordinates multiple subsystems. It calls methods on both turret (aiming) and shooter (flywheels, feeder, hood) every single loop. Thatβs the power of commands β they orchestrate complex behaviors across subsystems.
The feed delay β a clever safety pattern
AutoShootCommand doesnβt feed the note the instant everything looks ready. It waits 0.3 seconds first:
private static final double FEED_DELAY = 0.3;
// In execute():if (aimed && flywheelsReady && !turretResetting && !inTrench && allowedToShoot) { if (readyTimestamp == 0.0) { readyTimestamp = Timer.getFPGATimestamp(); } if (Timer.getFPGATimestamp() - readyTimestamp >= FEED_DELAY) { shooter.runFeeder(0.85); // Fire! feeding = true; }} else { readyTimestamp = 0.0; // Reset timer if conditions change}Why? Because the βreadyβ check might briefly flicker true before the flywheels are truly stable. The delay ensures we only feed when everything has been consistently ready for 0.3 seconds. This is a common pattern in FRC β debouncing a condition before acting on it.
isFinished() β runs forever
@Overridepublic boolean isFinished() { return false;}This command never finishes on its own. It runs until the driver presses Y again (toggle off) or until autonomous ends. The toggleOnTrue binding in RobotContainer handles the toggle behavior.
end() β cleanup
@Overridepublic void end(boolean interrupted) { turret.stop(); shooter.stopAll(); shooter.setHoodPosition(0.0); // Flatten hood when not shooting}When the command ends (for any reason), it stops everything and flattens the hood. This is critical β without end(), the flywheels would keep spinning after you stop shooting!
Why does AutoShootCommand call addRequirements(turret, shooter) but NOT addRequirements(drivetrain)?
Inline Commands in RobotContainer
Not every command needs its own file. For simpler behaviors, WPILib provides inline command factories that let you create commands right inside
The Intake Toggle (X Button)
This is the most complex inline command in the project. When the driver presses X, it deploys the intake, runs the rollers, and handles retraction when toggled off:
controller.x() .toggleOnTrue( // Phase 1: Deploy out, wait, stop deploy, then run rollers new SequentialCommandGroup( new InstantCommand(() -> intakeSubsystem.deployOut(), intakeSubsystem), new WaitCommand(0.3), new InstantCommand(() -> intakeSubsystem.stopDeploy()), new RunCommand(() -> intakeSubsystem.runIntake(0.5), intakeSubsystem) ).finallyDo(() -> { // When cancelled: stop rollers and start retracting intakeSubsystem.stopIntake(); intakeSubsystem.deployIn(); }) // Phase 2: After cancel, give deploy motor 0.3s to retract, then stop .andThen(new WaitCommand(0.3)) .andThen(new InstantCommand(() -> intakeSubsystem.stopDeploy())) );Letβs break down the command types used here:
| Command Type | What It Does |
|---|---|
InstantCommand | Runs a single action once and immediately finishes β like flipping a switch |
WaitCommand | Does nothing for a specified number of seconds, then finishes |
RunCommand | Runs an action every 20ms and never finishes β keeps going until cancelled |
SequentialCommandGroup | Runs commands one after another, in order |
The toggleOnTrue binding means: press X once to start the command, press X again to cancel it. When cancelled, the finallyDo() block runs the cleanup (stop rollers, retract intake).
In the intake toggle, why is RunCommand used for the rollers instead of InstantCommand?
The Shoot Toggle (Y Button)
The Y button uses the AutoShootCommand class we just studied:
controller.y() .toggleOnTrue(new AutoShootCommand( turretSubsystem, shooterSubsystem, drivetrain, this::getSmartTarget, this::isTrajectoryPassingEnabled, false));Notice how RobotContainer passes the subsystems and configuration to the command. The this::getSmartTarget syntax is a method reference β it passes the getSmartTarget() method itself so AutoShootCommand can call it every loop to get the latest target.
Named Commands for Autonomous
RobotContainer also registers named commands that PathPlanner autonomous routines can trigger:
NamedCommands.registerCommand("AutoShoot", new AutoShootCommand(turretSubsystem, shooterSubsystem, drivetrain, this::getAllianceHub, () -> false, true));
NamedCommands.registerCommand("Intake", Commands.run(() -> { intakeSubsystem.deployOut(); intakeSubsystem.runIntake(0.35);}, intakeSubsystem));
NamedCommands.registerCommand("StopShooter", Commands.runOnce(() -> { shooterSubsystem.stopAll(); shooterSubsystem.setHoodPosition(0.0);}, shooterSubsystem));These are the same subsystem methods you learned about in Lesson 2.1, just wrapped in commands and given names that PathPlanner can reference. Commands.run() creates a RunCommand (runs every 20ms), and Commands.runOnce() creates an InstantCommand (runs once).
When the driver presses X, this sequence runs:
deployOut()β the deploy motors swing the intake outward (InstantCommand, runs once)- Wait 0.3 seconds β gives the deploy mechanism time to fully extend (WaitCommand)
stopDeploy()β stops the deploy motors since the intake is now out (InstantCommand)runIntake(0.5)β rollers start spinning at 50% to grab notes (RunCommand, runs continuously)
When the driver presses X again (toggle off), the cleanup runs:
stopIntake()β rollers stop spinningdeployIn()β deploy motors retract the intake- Wait 0.3 seconds β gives the mechanism time to retract
stopDeploy()β stops the deploy motors
The SequentialCommandGroup ensures steps 1β4 happen in order, and finallyDo() ensures the cleanup always runs when the command ends.
Command Groups: Combining Commands
Youβve already seen SequentialCommandGroup in the intake toggle. WPILib provides several ways to combine commands into more complex behaviors:
SequentialCommandGroup β One After Another
Commands run in order. The next command starts only after the previous one finishes.
ββββββββββββ ββββββββββββ βββββββββββββ Deploy βββββΊβ Wait 0.3sβββββΊβ Run ββ Out β β β β Rollers βββββββββββββ ββββββββββββ ββββββββββββThis is what the intake toggle uses β deploy first, wait, then run rollers.
ParallelCommandGroup β All At Once
All commands start at the same time. The group finishes when all commands have finished.
βββββββββββββββββββββ Aim Turret ββββββββββββββββββββββββ β ββββΊ Group finishes when ALL are doneββββββββββββββββββββ ββ Spin Flywheels ββββββββββββββββββββββββUse this when you want multiple things happening simultaneously β like aiming the turret while spinning up the flywheels.
ParallelRaceGroup β First One Wins
All commands start at the same time. The group finishes when any one command finishes, and the rest are cancelled.
βββββββββββββββββββββ Run Intake ββββββββββββββββββββββββ β ββββΊ Group finishes when FIRST one endsββββββββββββββββββββ ββ Wait 3 seconds ββββββββββββββββββββββββThis is useful for timeouts β βrun the intake, but stop after 3 seconds no matter what.β
Chaining with .andThen() and .alongWith()
Instead of creating group objects, you can chain commands with methods:
// Sequential: do A, then BcommandA.andThen(commandB)
// Parallel: do A and B at the same timecommandA.alongWith(commandB)The intake toggle uses .andThen() to chain the retraction sequence after the main command ends.
You want the robot to deploy the intake AND spin up the flywheels at the same time, then feed the note after both are ready. Which combination would you use?
Default Commands β What Happens When Nothing Else Is Running
Every subsystem can have a default command β a command that runs whenever no other command is using that subsystem. RobotContainer sets these up:
// Turret default: always auto-aim at the smart targetturretSubsystem.setDefaultCommand(new RunCommand( () -> turretSubsystem.aimAtPose(drivetrain.getState().Pose, getSmartTarget(), drivetrain.getState().Speeds), turretSubsystem));
// Drivetrain default: drive using joystick inputdrivetrain.setDefaultCommand( drivetrain.applyRequest(() -> drive .withVelocityX(/* joystick input */) .withVelocityY(/* joystick input */) .withRotationalRate(/* joystick input */)));The turretβs default command keeps it constantly aimed at the target β even when the driver isnβt shooting. The drivetrainβs default command reads the joystick and drives. These run in the background, all the time, unless a higher-priority command takes over.
How Commands and Subsystems Work Together β The Big Picture
Letβs zoom out and see how everything connects:
- Subsystems declare hardware and expose methods (
runIntake(),aimAtPose(), etc.) - Commands call those methods in a structured lifecycle (
initializeβexecuteβisFinishedβend) - RobotContainer creates both subsystems and commands, then wires buttons to commands
- The Command Scheduler runs the whole show β it calls
execute()on active commands every 20ms and manages which command gets each subsystem
Driver presses Y button β βΌRobotContainer: controller.y().toggleOnTrue(AutoShootCommand) β βΌCommand Scheduler starts AutoShootCommand β βΌAutoShootCommand.initialize() β reset state β βΌEvery 20ms: AutoShootCommand.execute() βββ turret.aimAtPose() β calls TurretSubsystem method βββ shooter.autoAim() β calls ShooterSubsystem method βββ shooter.runFeeder() β calls ShooterSubsystem method β βΌDriver presses Y again β command cancelled β βΌAutoShootCommand.end(true) β stop turret, stop shooter, flatten hoodπ οΈ Try It: Modify a Named Command
This is the first lesson where you get to write code! Hereβs a small, safe modification to try.
Look at the βStopShooterβ named command in RobotContainer:
NamedCommands.registerCommand("StopShooter", Commands.runOnce(() -> { shooterSubsystem.stopAll(); shooterSubsystem.setHoodPosition(0.0);}, shooterSubsystem));Your task: Add a System.out.println() statement so you can see in the console when this command runs during autonomous. Add it right before stopAll():
System.out.println(">>> AUTO: Stopping shooter <<<");This is a safe change β it only adds a log message and doesnβt affect any motor behavior. After making the change, build the project to make sure it compiles. Youβll learn more about safe edits like this in Lesson 3.1.
Quick Reference: Command Types
| Type | Behavior | Example Use |
|---|---|---|
InstantCommand | Runs once, finishes immediately | Toggle a flag, set a motor speed |
RunCommand | Runs every 20ms, never finishes | Joystick driving, continuous intake |
WaitCommand | Waits N seconds, then finishes | Delays between actions |
SequentialCommandGroup | Runs commands in order | Deploy β wait β run rollers |
ParallelCommandGroup | Runs commands simultaneously, finishes when all done | Aim + spin up flywheels |
ParallelRaceGroup | Runs commands simultaneously, finishes when first one done | Run intake with a timeout |
| Custom command class | Full lifecycle control | AutoShootCommand |
Whatβs Next?
You now understand both halves of the robotβs architecture: subsystems (capabilities) and commands (instructions). In Lesson 2.3: RobotContainer and Bindings, youβll see how RobotContainer ties everything together β creating subsystems, wiring buttons to commands, and setting up autonomous routines. Youβll also trace the complete path from a button press to a motor output.