AutoOpMode
Overview
AutoOpMode
is a base class for autonomous programs that integrates many powerful features. It uses a clean, state-based structure so you can focus on building a smart, reliable autonomous program without the extra hassle.
Key Features
🎯 Finite State Machine (FSM)
Manages autonomous routines using states in a state machine structure.
🧠 Real-time Adaptive Routines
Supports real-time autonomous decision-making based on remaining time.
📋 Pre-match Choice Menu
Offers an interactive menu system for configuring autonomous options before the match starts.
Usage
Setup
To use AutoOpMode
, simply extend your OpMode with the AutoOpMode
class.
@Autonomous
public class MyAuto extends AutoOpMode {
// Implement required methods here
}
That's it! You now have access to all the features AutoOpMode
provides.
Lifecycle Methods
AutoOpMode
exposes the regular OpMode
lifecycle methods, prefixed with "on"
(e.g., onInit()
, onStart()
, onLoop()
), allowing you to insert custom logic at each stage of the autonomous flow.
See Example Auto for example usage.
Defining States
Each state in the FSM is essentially a method annotated with @State
. Each state method contains the logic to execute during that state.
@State
public void state1() {
runBlocking(new SomeAction());
transition("state2");
}
Managing State Transitions
Use transition(string)
to move to another state. This method gets a state's name and transitions to that state.
transition("nextState");
State Timing and Timeout Configuration
When defining your autonomous states with the @State
annotation, you can specify timing-related properties to control state behavior under time constraints:
timeoutState
The fallback state to transition to if there is not enough time to complete the state.
requiredTime
The estimated minimum duration (in seconds) needed to finish the state.
forceExitTime
Force exit this state immediately when this many seconds remain in autonomous period.
This example shows how AutoOpMode
handles time-aware transitions.
If less than 5 seconds remain, the robot skips scoring and goes straight to parking.
If there’s enough time, it begins scoring—but if time drops below 2 seconds mid-state, it forcefully exits and parks.
@State
public void grabGameElement() {
// Grab game element logic
transition("score");
}
@State(requiredTime = 5, timeoutState = "park", forceExitTime = 2)
public void score() {
// Score game element logic
}
@State
public void park() {
// Park logic
}
Running RoadRunner Actions
AutoOpMode
provides a robust system to run RR actions:
Use
runBlocking(action)
to run an action synchronously until completion.Use
runAsync(action)
to run actions concurrently in the background.
See Example Auto for example usage.
Pre-match User Prompts
AutoOpMode
integrates ChoiceMenu
to allow for easy pre-auto menu configurations. This allows you to configure the autonomous before each match.
public void onInit() {
// Initialize subsystems...
choiceMenu.enqueuePrompt("alliance", new OptionPrompt<>("SELECT AN ALLIANCE:", Alliance.RED, Alliance.BLUE));
choiceMenu.enqueuePrompt("delay", new ValuePrompt("SELECT A START DELAY:", 0.0, 30.0, 0.0, 1.0));
choiceMenu.run(); // Blocks until done
Alliance alliance = choiceMenu.get("alliance");
int delay = choiceMenu.get("delay");
telemetry.addData("Selected Alliance", alliance);
telemetry.addData("Selected Start Delay", delay);
}
Handling Fallback Conditions
The FSM supports fallback logic for handling unexpected situations or manual overrides. The FSM will repeatedly re-evaluate the supplied condition and will transition to the provided state if true.
This is especially helpful during auto tuning, where you may want the robot to return to the start position at the press of a button.
setFallbackState(() -> gamepad1.back, "abort");
Please note that controlling the autonomous with gamepad input is FORBIDDEN in competition matches and is considered cheating.
Example Auto
This example uses RoadRunner and demonstrates how all the different systems work together.
enum Alliance {
RED,
BLUE
}
@Autonomous
public class MyAuto extends AutoOpMode {
MecanumDrive drive;
Alliance alliance;
double delay;
public void onInit() {
// ---- Initialize Subsystems ----
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
// ---- Configure Prompts ----
choiceMenu.enqueuePrompt("alliance", new OptionPrompt<>("SELECT AN ALLIANCE:", Alliance.RED, Alliance.BLUE));
choiceMenu.enqueuePrompt("delay", new ValuePrompt("SELECT A START DELAY:", 0.0, 30.0, 0.0, 1.0));
choiceMenu.run(); // Blocks until done
alliance = choiceMenu.get("alliance");
delay = choiceMenu.get("delay");
telemetry.addData("Selected Alliance", alliance);
telemetry.addData("Selected Start Delay", delay);
}
public void onStart() {
// ---- Set Starting State and Fallback State ----
// Make the robot go back to the starting position on button press
// (THIS IS FORBIDDEN IN COMPETITION. MAKE SURE TO DISABLE IT BEFOREHAND.)
setFallbackState(() -> gamepad1.guide.isJustPressed() || gamepad2.guide.isJustPressed(), "reset");
runBlocking(new SleepAction(delay)); // Wait the chosen delay before starting auto
transition("grab");
}
// ---- STATES ----
// This example alternates between "grab" and "score" states,
// and will transition to "park" when there isn't enough time left.
@State(requiredTime = 2, timeoutState = "park", forceExitTime = 1)
public void grab() {
runBlocking(
drive.actionBuilder(drive.pose)
.splineToConstantHeading(new Vector2d(20, 0), 0)
.build()
);
transition("score");
}
@State(requiredTime = 3, timeoutState = "park")
public void score() {
runBlocking(
drive.actionBuilder(drive.pose)
.splineToConstantHeading(new Vector2d(30, 0), Math.PI)
.build()
);
transition("grab");
}
@State
public void park() {
runBlocking(
drive.actionBuilder(drive.pose)
.splineToConstantHeading(new Vector2d(10, 10), Math.PI / 2)
.build()
);
requestOpModeStop();
}
@State
public void reset() {
runBlocking(
drive.actionBuilder(drive.pose)
.splineToConstantHeading(new Vector2d(0, 0), Math.PI / 2)
.build()
);
requestOpModeStop();
}
}
Last updated