Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/spectrum3847/2026-Spectrum/llms.txt

Use this file to discover all available pages before exploring further.

WPILib’s command-based framework is the standard architecture for FRC robot code. Rather than writing one giant loop that manually checks every sensor and actuates every motor, you decompose robot behavior into small, composable units called Commands, attach them to hardware abstractions called Subsystems, and let the CommandScheduler coordinate their execution. The Spectrum 3847 2026 robot is built entirely on this framework, with an additional pattern layered on top: Triggers that represent named robot states.

Subsystems

A subsystem represents a physical mechanism — intake, launcher, hood, swerve drivetrain. It owns the hardware objects (motors, sensors, encoders) and exposes methods that Commands can call. Every subsystem has a periodic() method called automatically by the scheduler every 20 ms (50 times per second), regardless of which commands are running. Use it for telemetry, sensor updates, and state logging:
@Override
public void periodic() {
    // Called 50 times per second by the CommandScheduler
    Telemetry.log("FuelIntake/Position", getPosition());
    Telemetry.log("FuelIntake/Velocity", getVelocity());
}
The Robot.java constructor instantiates every subsystem once and stores it as a static field, so any class can retrieve it with a getter:
// Robot.java
fuelIntake      = new FuelIntake(config.fuelIntake);
intakeExtension = new IntakeExtension(config.intakeExtension);
launcher        = new Launcher(config.launcher);
hood            = new Hood(config.hood);
indexerTower    = new IndexerTower(config.indexerTower);
indexerBed      = new IndexerBed(config.indexerBed);
swerve          = new Swerve(config.swerve);
// Anywhere else in the codebase
private static final Launcher launcher = Robot.getLauncher();

Commands

A Command is a unit of robot action. It has a defined lifecycle — initialize(), execute() (called every loop), end(), and isFinished(). WPILib provides factory methods for the most common patterns so you rarely implement these methods directly:
Runs a single action and immediately finishes. Use for state changes, one-shot actuations, and resetting values:
// Apply a robot state in one shot
Commands.runOnce(() -> {
    appliedState = state;
    coordinator.applyRobotState(state);
}).withName("APPLYING STATE: " + state);

The CommandScheduler

The CommandScheduler is the heartbeat of the command-based framework. It runs inside robotPeriodic(), which executes every 20 ms:
// Robot.java — called every loop iteration
@Override
public void robotPeriodic() {
    CommandScheduler.getInstance().run();
    // ...
}
On each call, the scheduler:
1

Polls all registered Triggers

Checks every button and Trigger to see if their state changed since the last loop.
2

Schedules new commands

Any Trigger whose condition became true schedules its associated command.
3

Runs active commands

Calls execute() on every currently-running command and checks isFinished().
4

Calls subsystem periodic()

Invokes periodic() on every registered subsystem, whether or not it has an active command.
5

Handles interrupts and conflicts

If two commands require the same subsystem, the scheduler cancels the older one unless it is non-interruptible.
When modes switch (teleop → disabled → auton), resetCommandsAndButtons() cancels all running commands and re-registers all Triggers:
public void resetCommandsAndButtons() {
    CommandScheduler.getInstance().cancelAll();
    CommandScheduler.getInstance().getActiveButtonLoop().clear();

    pilot.resetConfig();
    operator.resetConfig();

    setupStates();           // subsystem-level bindings
    RobotStates.setupStates(); // robot-level state bindings
}

Triggers

A Trigger is a boolean condition that the scheduler polls every loop. When the condition changes, the Trigger fires its associated command. Triggers can be composed with boolean logic just like conditions in an if statement:
// Compose triggers with .and(), .or(), .not()
public static final Trigger robotInNeutralZone = swerve.inNeutralZone();
public static final Trigger robotInEnemyZone   = swerve.inEnemyAllianceZone();
public static final Trigger robotInFeedZone    = robotInEnemyZone.or(robotInNeutralZone);
public static final Trigger robotInScoreZone   = robotInFeedZone.not();
The three most common binding methods are:
MethodWhen it firesTypical use
onTrue(cmd)Once, when condition becomes trueApply a state, start a sequence
onFalse(cmd)Once, when condition becomes falseReturn to IDLE, clean up
whileTrue(cmd)Every loop while condition is true, cancels on falseContinuous tracking, holding a position

How Spectrum uses Triggers as states

The key design pattern in the Spectrum 2026 codebase is treating robot states as Triggers. The RobotStates.setupStates() method binds every gamepad button and autonomous event to a named State enum value through applyState():
// RobotStates.java
public static void setupStates() {

    // Pilot RT alone → intake fuel
    pilot.RT.onTrue(
        Commands.either(applyState(State.INTAKE_FUEL), Commands.none(), pilot.LT.negate()));

    // Pilot LT alone → launch with squeeze
    pilot.LT.onTrue(
        Commands.either(
            applyState(State.LAUNCH_WITH_SQUEEZE), Commands.none(), pilot.RT.negate()));

    // Both LT + RT → launch without squeeze
    pilot.LT.and(pilot.RT).onTrue(applyState(State.LAUNCH_WITHOUT_SQUEEZE));

    // X button held → track target continuously
    pilot.XButton.whileTrue(applyState(State.TRACK_TARGET));
    pilot.XButton.onFalse(applyState(State.IDLE));

    // A button held → unjam
    pilot.AButton.whileTrue(applyState(State.UNJAM));
    pilot.AButton.onFalse(applyState(State.IDLE));

    // Auton triggers
    Auton.autonIntake.onTrue(applyState(State.INTAKE_FUEL));
    Auton.autonShoot.onTrue(applyState(State.LAUNCH_WITH_SQUEEZE));
    Auton.autonUnjam.onTrue(
        Commands.sequence(
            applyState(State.UNJAM),
            Commands.waitSeconds(1),
            applyState(State.LAUNCH_WITH_SQUEEZE)));
}
applyState() is a command factory that stores the active state and delegates to the Coordinator, which fans the state out to every affected subsystem:
public static Command applyState(State state) {
    return Commands.runOnce(() -> {
        appliedState = state;
        coordinator.applyRobotState(state);
    }).withName("APPLYING STATE: " + state);
}
The State enum lists every valid robot state. This makes it impossible to pass an invalid state — the compiler rejects anything not in the enum:
public enum State {
    IDLE,
    INTAKE_FUEL,
    TRACK_TARGET,
    LAUNCH_WITH_SQUEEZE,
    LAUNCH_WITH_SQUEEZE_WITH_NO_DELAY,
    LAUNCH_WITHOUT_SQUEEZE,
    CUSTOM_SPEED_TURRET_LAUNCH,
    UNJAM,
    FORCE_HOME,
    COAST,
    BRAKE,
    TEST_INFINITE_LAUNCH,
    TEST_IDLE;
}
Zone-based triggers derived from swerve odometry show how Triggers can react to robot position rather than buttons:
public static final Trigger launcherOnTarget = LauncherStates.aimingAtTarget();

// Automatically logs trigger state without any manual if/else
bindTriggerTelemetry("LauncherPrep/LauncherOnTarget", launcherOnTarget);
The bindTriggerTelemetry helper wires onTrue and onFalse to log true/false to the telemetry system, keeping dashboards in sync with trigger state automatically rather than polling in periodic().

Java fundamentals

Review the Java building blocks that underpin commands and subsystems.

Applying Java to FRC

See which Java constructs are commonly used and how commands replace traditional loops.

Build docs developers (and LLMs) love