Getting Started
Welcome to Pedro Pathing Plus! This guide will walk you through creating your first autonomous program using the library.
Prerequisites
Section titled “Prerequisites”Before you begin, ensure you have:
- Installed Pedro Pathing Plus in your project (see Installation).
- Configured your robot’s hardware map (motors, sensors) in the Driver Station or
FtcRobotController.
The Recommended Workflow
Section titled “The Recommended Workflow”The modern Pedro Pathing Plus workflow is “Visualizer-First”:
- Design your path in the Visualizer web interface.
- Export the path as a complete Java OpMode.
- Run the generated code on your robot.
This approach eliminates the need to manually write complex geometry code and ensures your paths are visualized correctly before you even touch the robot.
Creating Your First Path
Section titled “Creating Your First Path”1. Open the Visualizer
Section titled “1. Open the Visualizer”Go to the Pedro Pathing Visualizer (or your hosted instance).
2. Draw a Path
Section titled “2. Draw a Path”- Click the + (Add Path) button or press
P. - Click on the field to place your starting point.
- Click again to place the end point.
- Drag the control handles to shape the curve if desired.
3. Export Your Code
Section titled “3. Export Your Code”When you are ready to export, you have two options: a standard Java OpMode or a Command-Based structure.
Use this option if you want a standalone OpMode that handles the path following logic directly.
- Click the Export button in the top right corner.
- Ensure “Java OpMode” is selected.
- Check “Generate Full Class”.
- Enter your team’s package name (e.g.,
org.firstinspires.ftc.teamcode). - Click Copy to Clipboard.
- Paste the code into a new Java file in your Android Studio project.
Example Output
Section titled “Example Output”Below is an example of the auto-generated OpMode. Note the use of PanelsTelemetry and Constants.
package org.firstinspires.ftc.teamcode.Commands.AutoCommands;
import com.bylazar.configurables.annotations.Configurable;import com.bylazar.telemetry.PanelsTelemetry;import com.bylazar.telemetry.TelemetryManager;import com.pedropathing.follower.Follower;import com.pedropathing.geometry.BezierCurve;import com.pedropathing.geometry.BezierLine;import com.pedropathing.geometry.Pose;import com.pedropathing.paths.PathChain;import com.qualcomm.robotcore.eventloop.opmode.Autonomous;import com.qualcomm.robotcore.eventloop.opmode.OpMode;import com.qualcomm.robotcore.util.ElapsedTime;import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
@Autonomous(name = "Pedro Pathing Autonomous", group = "Autonomous")@Configurable // Panelspublic class PedroAutonomous extends OpMode {
private TelemetryManager panelsTelemetry; // Panels Telemetry instance public Follower follower; // Pedro Pathing follower instance private int pathState; // Current autonomous path state (state machine) private ElapsedTime pathTimer; // Timer for path state machine private Paths paths; // Paths defined in the Paths class
@Override public void init() { panelsTelemetry = PanelsTelemetry.INSTANCE.getTelemetry(); // ... panelsTelemetry.debug("Status", "Initialized"); panelsTelemetry.update(telemetry);
follower = Constants.createFollower(hardwareMap); // Determine starting heading: prefer geometric heading when a path exists, otherwise fall back to explicit startPoint values follower.setStartingPose(new Pose(56.000, 8.000, Math.toRadians(90.000)));
pathTimer = new ElapsedTime(); paths = new Paths(follower); // Build paths }
@Override public void loop() { follower.update(); // Update Pedro Pathing pathState = autonomousPathUpdate(); // Update autonomous state machine
// Log values to Panels and Driver Station panelsTelemetry.debug("Path State", pathState); panelsTelemetry.debug("X", follower.getPose().getX()); panelsTelemetry.debug("Y", follower.getPose().getY()); panelsTelemetry.debug("Heading", follower.getPose().getHeading()); panelsTelemetry.update(telemetry); }
public static class Paths {
public PathChain line1;
public Paths(Follower follower) { line1 = follower .pathBuilder() .addPath( new BezierLine(new Pose(56.000, 8.000), new Pose(56.000, 36.000)) ) .setLinearHeadingInterpolation(Math.toRadians(90), Math.toRadians(180)) .build(); } }
public int autonomousPathUpdate() { switch (pathState) { case 0: follower.followPath(paths.line1, true); setPathState(1); break; case 1: if (!follower.isBusy()) { setPathState(2); } break; case 2: requestOpModeStop(); pathState = -1; break; } return pathState; }
public void setPathState(int pState) { pathState = pState; pathTimer.reset(); }}Key Components
Section titled “Key Components”pathState: A state machine variable that tracks which segment of the path is currently running.PathsClass: Contains all your generatedPathChaindefinitions.autonomousPathUpdate(): The logic that switches between paths and waits for completion.
Use this option if you are using a Command-Based framework (like SolversLib). This generates a SequentialCommandGroup rather than a full OpMode.
- Click the Export button in the top right corner.
- Select “SolversLib” (or Command-Based) as the format.
- Enter your team’s package name.
- Click Copy to Clipboard (or save the file).
- Important: This method typically requires you to save the path file (
.pp) to your robot’s storage as well, as it usesPedroPathReaderto load points dynamically.
Example Output
Section titled “Example Output”This template generates a command group that chains together path following commands.
package org.firstinspires.ftc.teamcode.Commands.AutoCommands;
import com.pedropathing.follower.Follower;import com.pedropathing.geometry.BezierCurve;import com.pedropathing.geometry.BezierLine;import com.pedropathing.geometry.Pose;import com.pedropathing.paths.PathChain;import com.pedropathingplus.PedroPathReader;import com.pedropathingplus.pathing.NamedCommands;import com.pedropathingplus.pathing.ProgressTracker;import com.qualcomm.robotcore.hardware.HardwareMap;import com.seattlesolvers.solverslib.command.InstantCommand;import com.seattlesolvers.solverslib.command.ParallelRaceGroup;import com.seattlesolvers.solverslib.command.SequentialCommandGroup;import com.seattlesolvers.solverslib.command.WaitCommand;import com.seattlesolvers.solverslib.command.WaitUntilCommand;import com.seattlesolvers.solverslib.pedroCommand.FollowPathCommand;import java.io.IOException;import org.firstinspires.ftc.robotcore.external.Telemetry;import org.firstinspires.ftc.teamcode.Subsystems.Drivetrain;
public class AutoPath extends SequentialCommandGroup {
private final Follower follower; private final ProgressTracker progressTracker;
// Poses private Pose startPoint; private Pose point1;
// Path chains private PathChain startPointTOpoint1;
public AutoPath(final Drivetrain drive, HardwareMap hw, Telemetry telemetry) throws IOException { this.follower = drive.getFollower(); this.progressTracker = new ProgressTracker(follower, telemetry);
PedroPathReader pp = new PedroPathReader("AutoPath.pp", hw.appContext);
// Load poses startPoint = pp.get("startPoint"); point1 = pp.get("point1");
follower.setStartingPose(startPoint);
buildPaths();
addCommands( new InstantCommand(() -> { progressTracker.setCurrentChain(startPointTOpoint1); progressTracker.setCurrentPathName("startPointTOpoint1"); }), new FollowPathCommand(follower, startPointTOpoint1) ); }
public void buildPaths() { startPointTOpoint1 = follower .pathBuilder() .addPath(new BezierLine(startPoint, point1)) .setLinearHeadingInterpolation( startPoint.getHeading(), point1.getHeading() ) .build(); }}Key Components
Section titled “Key Components”SequentialCommandGroup: The base class for the entire routine.PedroPathReader: Used to load named poses from the saved path file.FollowPathCommand: A command from SolversLib that wraps the path following logic.
Next Steps
Section titled “Next Steps”- Explore Command-Based Programming for integrating paths into a larger robot framework.
- Learn about Live View to see your robot’s position in real-time.