Skip to content

Greenland-Robotics/GCSFTCFramework

Greenland Robotics Framework: Documentation

Notes

  • When writing your opmodes, always include the line ///@author <your-name> just above the @TeleOp or @Autonomous annotation. This provides clean documentation about who wrote the opmode, which is useful for collaborative purposes and knowing who to blame when something goes wrong. Jokes aside, it is very important when collaborating on code to sign your work.

    • Example:
      ///@author Josh Kelley
      @TeleOp(name = "My TeleOp")
      public class MyTeleOp extends TeleOpBase {...}
  • If you are using the PlayStation controllers, use the button map below:

    PlayStation Gamepad (in code)
    X A
    O B
    Y
    X

    For example: gamepad1.a will be automatically mapped to the X button on the PlayStation controller.

  • In TeleOp, the following inputs are consumed by the built-in drive logic inside TeleOpBase (gamepad1 only):

    • left_stick_x
    • left_stick_y
    • right_stick_x

    These are forwarded to Pedro Pathing's setTeleOpDrive(). Using these inputs elsewhere in your teleop code means that one action will control both driving and whatever else you mapped it to. If you need to change or override the drive logic, see TeleOpBase.loopInternal().


Where is my code?

All code is under TeamCode/src/main/java/gcsrobotics/. Here you will find the following packages:

  • examples: Example opmodes (as .java.md files) that show how to use the framework for Autos and TeleOps
  • control: The base classes for all opmodes — OpModeBase, AutoBase, and TeleOpBase. You will only go here to change the hardware configuration in OpModeBase.java
  • opmode: This is where your opmodes will reside. It contains boilerplate files to get you started. This is where you spend most of your time.
  • pedroPathing: Pedro Pathing integration — Constants.java (tune this for your robot) and the Tuning opmode suite
  • vertices: The command system. These are the building blocks you combine to create autonomous routines and teleop actions
  • commands: Pre-built commands like FollowPath and the example command template. Add your own custom commands here

Installation / Setup

Setting up a new project is very easy — just follow these steps and you are ready to go!

  1. Fork the repo — Go to the main GitHub page for this repo and look for the Fork button. Click it and give your fork a name.
  2. Once forked, you will be taken to a page that looks like this one, but with your name on it.
  3. Clone the repo — Click the green Code button on the main page of your repository (not this one). Copy the URL shown there.
  4. Open Android Studio and go to the top-left three-line menu → FileNewProject from Version Control. Paste in the URL from step 3 and continue.
  5. It may take a few minutes to sync and build, but you'll know you're ready when you see three folders in the left-hand panel: FtcRobotController, TeamCode, and Gradle Scripts.
  6. You're done! Your code goes under TeamCode.

WARNING: Do NOT write while loops

Code that is written inside functions with loop in their name(runLoop(), loop(), etc.) are automatically run inside the main loop. You do NOT have to write a while (opModeIsActive) {...} inside of them. Doing so will break the functionality of the entire framework. It is exceedingly rare that you would ever have to write one, if at all

Method Documentation

This documentation covers all classes and methods relevant to writing opmodes with this framework.


Table of Contents


OpModeBase

Purpose: Abstract base for all OpModes (autonomous or teleop). Handles hardware initialization and provides access to the Pedro Pathing follower and a shared INSTANCE reference used by commands.

Key Properties

  • follower — The Pedro Pathing Follower instance, used for all path following and pose tracking
  • INSTANCE — A static, volatile reference to the currently running opmode. Used by commands to access robot hardware via OpModeBase.INSTANCE

Main Methods

public double getX(), public double getY(), public double getHeading()

Returns the robot's current X position, Y position, or heading, respectively, as reported by the Pedro Pathing localizer. Available in any Auto or TeleOp that extends this class.

private void initHardware()

Initializes all hardware. You will need to modify this method for your specific robot — declare and configure motors, servos, and any other devices here.

The following are internal methods. You won't need to interact with them directly.

protected abstract void initInternal()

Implemented by AutoBase and TeleOpBase. Runs during the init phase before waitForStart().

protected abstract void loopInternal()

Implemented by AutoBase and TeleOpBase. Runs every iteration of the main loop after start.

public void runOpMode()

The main entrypoint for the opmode. Calls initHardware(), creates the follower, sets INSTANCE, calls initInternal(), waits for start, then runs the main loop.


AutoBase

Purpose: AutoBase is an abstract class for autonomous opmodes. It extends OpModeBase and integrates the command system, so your entire autonomous routine is expressed as a tree of commands that run automatically.

Common Usage

  • Extend AutoBase in your autonomous opmode class.
  • Override buildCommands() to construct your command objects.
  • Override initialize() to set the robot's starting pose, build paths, and assemble the CommandRunner.
  • Override runLoop() for anything you want to run continuously alongside the commands (e.g., telemetry).

What does "Override" mean?

Overriding means providing your own implementation of a method that is declared in a parent class:

@Override // Not strictly required but recommended for readability
protected void initialize() {
    follower.setStartingPose(new Pose(0, 0, Math.toRadians(0)));
}

These methods are declared in AutoBase but you define what they actually do.

Key Methods

protected abstract void buildCommands()

Override to instantiate your Command objects.

@Override
protected void buildCommands() {
    driveToGoal = new SeriesCommand(
        new FollowPath(paths.toGoal),
        new Shoot()
    );
}

protected abstract void initialize()

Override to set the starting pose, build your Paths, and create the CommandRunner with the full sequence.

@Override
protected void initialize() {
    follower.setStartingPose(new Pose(26, 128, Math.toRadians(-38)));
    paths = new Paths(follower);
    commandRunner = new CommandRunner(new SeriesCommand(
        driveToGoal,
        intakeAndScore
    ));
}

protected abstract void runLoop()

Override to add logic that runs every loop tick during the autonomous (alongside command execution). Great for telemetry:

@Override
protected void runLoop() {
    telemetry.addData("x", getX());
    telemetry.addData("y", getY());
}

The Paths inner class

By convention, a static class Paths inside your Auto holds all PathChain objects. Generate path code from Pedro Pathing Visualizer and paste it in here.


TeleOpBase

Purpose: Base class for teleop opmodes. Integrates Pedro Pathing's teleop drive and the command system for button-triggered actions.

Key Properties

  • commandRunner — A CommandRunner instance, available for use with ButtonAction
  • driveMode — Set to false to temporarily disable the driver-controlled drive (e.g., when a path command takes over)

Key Methods

protected abstract void initialize()

Override to set up your ButtonAction objects and any other init logic.

protected abstract void runLoop()

Override to define your main teleop loop. Call buttonAction.update(gamepad.button) here for each action.

Built-in Drive Logic

Each loop tick, TeleOpBase automatically calls:

follower.setTeleOpDrive(
    -gamepad1.left_stick_y,
    -gamepad1.left_stick_x,
    -gamepad1.right_stick_x,
    false
);

This gives you full mecanum drive out of the box. Set driveMode = false to pause it (useful when a FollowPath command is running in teleop).


Constants

Purpose: Central location for all tunable robot constants — motor names, directions, odometry pod offsets, and path constraints. This is the first file you configure when setting up for a new robot.

Key Fields

Drive Constants (MecanumConstants driveConstants)

  • Motor names: must match your hardware configuration file in the Driver Station app
    • rightFrontMotorName, rightRearMotorName, leftFrontMotorName, leftRearMotorName
  • Motor directions: FORWARD or REVERSE per motor
  • maxPower: Maximum drive power (0–1)

Localizer Constants (PinpointConstants localizerConstants)

  • hardwareMapName: The name of the Pinpoint device in your hardware config (default: "pinpoint")
  • forwardPodY, strafePodX: Pod offsets in the configured distanceUnit
  • encoderResolution: Pod type, e.g. goBILDA_4_BAR_POD
  • forwardEncoderDirection, strafeEncoderDirection: FORWARD or REVERSED

Path Constraints (PathConstraints pathConstraints)

Limits for velocity and acceleration during path following. Tune these to prevent wheel slip.

public static Follower createFollower(HardwareMap hardwareMap)

Used internally by OpModeBase — builds and returns the configured Follower. You don't call this directly.

Adding your own constants

Add static fields for servo positions, motor targets, PID coefficients, etc.:

// eg.
public static double CLAW_CLOSED = 0.2;
public static double CLAW_OPEN = 0.8;
public static int ARM_UP = 1200;

Command Interface

Purpose: The core interface of the Vertices command system. All commands implement this:

public interface Command {
    void init();          // Called once when the command starts
    void loop();          // Called every loop tick while the command is running
    boolean isFinished(); // Return true to end the command
}

To write a custom command, implement this interface. Access robot hardware via OpModeBase.INSTANCE:

public class MyCommand implements Command {
    private OpModeBase robot = OpModeBase.INSTANCE;

    public void init() { /* startup logic */ }
    public void loop() { /* per-tick logic */ }
    public boolean isFinished() { return /* done condition */; }
}

See commands/ExampleCommand.java as a starting template.


CommandRunner

Purpose: Manages and executes a list of active commands. It runs all added commands concurrently, removing each one as it finishes.

Key Methods

public CommandRunner(Command... commands)

Constructs a runner pre-loaded with commands (used in AutoBase.initialize()).

public void run(Command command)

Adds and immediately starts a command. Used by ButtonAction in teleop.

public void update()

Called every loop tick — runs loop() on all active commands and removes finished ones.

public boolean isFinished()

Returns true when all commands have completed.


SeriesCommand

Purpose: Runs a list of commands one at a time, in order. The next command starts only after the previous one finishes.

new SeriesCommand(
    new FollowPath(paths.toGoal),
    new Shoot(),
    new FollowPath(paths.toIntake)
)

addCommands(Command... commands)

Dynamically appends more commands before the series starts.


ParallelCommand

Purpose: Runs multiple commands simultaneously. Finishes when all commands have finished.

new ParallelCommand(
    new FollowPath(paths.toIntake),
    new StartIntake()
)

addCommands(Command... commands)

Appends more commands before execution starts.


InstantCommand

Purpose: Executes a single Runnable action on the first loop tick, then immediately finishes. Great for one-liners like setting a servo position.

new InstantCommand(() -> claw.setPosition(0.5))

SleepCommand

Purpose: Pauses the command chain for a specified number of milliseconds without blocking the rest of the program.

new SleepCommand(1000) // wait 1 second

Unlike Thread.sleep(), this keeps the opmode loop running while waiting.


AwaitCommand

Purpose: Blocks the command chain until a Condition becomes true. Optionally times out after a set duration.

// Wait indefinitely
new AwaitCommand(() -> sensor.getDistance() < 5)

// Wait with a 3-second timeout
new AwaitCommand(() -> sensor.getDistance() < 5, 3000)

Condition is a functional interface: boolean getValue().


TimeoutCommand

Purpose: Wraps another command and forcefully finishes it if it takes longer than the specified timeout.

new TimeoutCommand(new FollowPath(paths.toGoal), 3000) // give up after 3 seconds

CancelCommand

Purpose: Wraps one or more commands and gives you external control to cancel or pause them mid-execution.

Key Methods

  • cancel() — Permanently stops all wrapped commands and marks as finished
  • disable() — Temporarily pauses the wrapped commands
  • enable() — Resumes paused commands
  • isDisabled() — Returns the current disabled state
CancelCommand movingArm = new CancelCommand(new SeriesCommand(armUp, deliver));
// later:
movingArm.cancel(); // abort if something goes wrong

SwitchCommand

Purpose: Evaluates a Condition at the moment it starts, and runs either the action command (if true) or a fallback command (if false). Think of it as an if/else for commands.

// With fallback
new SwitchCommand(
    () -> isRed,       // condition
    new DriveLeft(),   // run if true
    new DriveRight()   // run if false
)

// Without fallback (no-op if false)
new SwitchCommand(() -> hasSample, new Shoot())

How to Use This Framework

  1. Configure Constants.java — set motor names, directions, and pod offsets to match your hardware config
  2. Add your hardware to initHardware() in OpModeBase.java
  3. Create an OpMode in the opmode/ package:
    • Autonomous: extend AutoBase — use BoilerplateAuto.java as your starting point
    • TeleOp: extend TeleOpBase — use BoilerplateTeleOp.java as your starting point
  4. Override the required abstract methods (buildCommands, initialize, runLoop, etc.)
  5. Build your command trees using SeriesCommand, ParallelCommand, FollowPath, and your own custom Command classes
  6. Wire buttons to actions in teleop using ButtonAction
  7. Tune using the Tuning opmode suite (in pedroPathing/Tuning.java)

Questions?

  • Each class and method is documented with purpose, usage, and examples in this file.
  • For detailed code reference, browse the .java files under TeamCode/src/main/java/gcsrobotics/.
  • For path generation, use the Pedro Pathing Visualizer.
  • For FTC SDK reference, see FTC documentation.
  • For advanced help, use an AI such as Claude or ChatGPT with your code attached
  • If nothing else works, ask Josh.

About

No description, website, or topics provided.

Resources

License

Contributing

Stars

Watchers

Forks

Releases

No releases published

Packages

 
 
 

Contributors

Languages