RoadRunner

Autonomous mode is easier and more effective with the RoadRunner toolkit. It's not easy to understand all at once, but it makes a lot of sense if we look a little bit at a time.

How it Works

Where does RR come from?

I believe RoadRunner was developed by Team #8367, Acme Robotics, around 2018 to address the need for more precise and efficient motion planning in FTC competitions. Before RoadRunner, many teams relied on less advanced methods for robot trajectory control, limiting the precision of their autonomous routines. By 2019 and 2020, RoadRunner gained widespread adoption. It has since become a go-to tool for FTC teams seeking smooth, accurate robot movement during autonomous periods.

What does RR do?

RoadRunner is a motion planning library designed for FTC robots, allowing teams to create precise, smooth trajectories for autonomous movement. It uses kinematic models, such as mecanum and tank drive, to account for a robot’s unique drivetrain and behavior. RoadRunner operates by defining Pose2d (position and orientation) coordinates and allows teams to create paths with splines (curved paths) and waypoints (specific positions the robot should pass through). The library incorporates feedforward control and supports tuning for optimal motion via parameters like kV, kA, and track width, providing fine-tuned trajectory generation for complex autonomous tasks.

VOCABULARY

  • Pose2d: Defines the robot’s position (x, y) and orientation (heading) on the field.

  • Spline: A smooth, curved path that the robot follows during its trajectory.

  • Waypoint: Specific points that the robot must pass through on its path.

  • Feedforward Control: A method of controlling robot movement based on predicted motion, helping smooth trajectories.

  • kV: A constant used to model the robot’s velocity.

  • kA: A constant used to model the robot’s acceleration.

  • Track Width: The distance between the left and right wheels of a robot, important for accurately modeling turns.

  • Mecanum Drive: A type of drivetrain that allows for omnidirectional movement using angled wheels.

  • Tank Drive: A drivetrain setup where each side of the robot operates independently, allowing for tight turns.

  • Odometry: Use of data from motion sensors to estimate change in position over time. It is used in robotics by some legged or wheeled robots to estimate their position relative to a starting location. This method is sensitive to errors due to the integration of velocity measurements over time to give position estimates

Two Drive Subsystems

To integrate FTCLib with RoadRunner, we start by modifying the provided Mecanum Drive class. First, we remove its status as final, allowing us to extend it. We then make this class extend FTCLib’s Subsystem class, renaming it to RoadRunner for clarity. We inject our parameters using the Params object but keep the rest of the logic minimal in this class. Instead, we place our custom functionality in the Mecanum Drive class, where we define any additional logic or custom functions tailored to our specific robot. This separation allows RoadRunner to handle trajectory generation while our custom drive logic remains organized in Mecanum Drive.

Tuning RoadRunner

For the most up-to-date information Tuning RoadRunner will be your lifeline.

Tuning RoadRunner involves a step-by-step process to calibrate various components of a robot's drivetrain and localization system for optimal performance. The process begins with defining DriveConstants, which includes key parameters such as wheel radius, gear ratio, and track width. If the robot uses dead wheels (odometry pods), a preliminary Dead Wheels calibration and a LocalizationTest ensure accurate positional tracking. Depending on whether the robot uses drive encoders, the next step involves either tuning velocity control with the DriveVelocityPIDTuner or feedforward coefficients with the DriveFeedforwardTuner. Afterward, a StraightTest verifies the robot's ability to move linearly, followed by the TrackWidthTuner to fine-tune turning accuracy by calibrating the effective track width. The TurnTest assesses angular movement precision. A secondary LocalizationTest validates improvements in positional tracking accuracy post-tuning. To refine trajectory following, the FollowerPIDTuner optimizes control parameters for path adherence. Finally, the SplineTest confirms the robot's capability to execute complex motion paths smoothly. When completed, the robot is finely tuned, and ready for reliable and precise autonomous operation.

Using RoadRunner

Difference between Strafe and Spline

"Strafe to Pose" involves moving directly to a target position and orientation in a straight line, useful for simple, precise adjustments. In contrast, "Splines" generate smooth, curved trajectories, ideal for navigating complex paths while optimizing motion stability and efficiency. Strafe is straightforward, while splines handle dynamic and intricate maneuvers.

We as a team often build our

Example Command (StrafeToPose)

package org.firstinspires.ftc.teamcode.commands;

import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.acmerobotics.roadrunner.Action;
import com.acmerobotics.roadrunner.Pose2d;

import org.firstinspires.ftc.teamcode.Callisto;
import org.firstinspires.ftc.teamcode.subsystems.Mecanum;
import org.firstinspires.ftc.teamcode.util.Constants;

import com.acmerobotics.roadrunner.Vector2d;
import com.arcrobotics.ftclib.command.CommandBase;
import com.arcrobotics.ftclib.util.Timing;

public class StrafeToPose extends CommandBase {

    // REFERENCES
    private Callisto robot;
    private Mecanum mecanum;

    // ASSETS
    private final Pose2d targetPose; // The target position and heading
    protected Action action;
    protected boolean finished = false;

    // TIMER
    protected Timing.Timer timer;

    // FTC DASHBOARD
    private FtcDashboard dashboard;

    // Constructor to initialize the command
    public StrafeToPose(Callisto robot, Pose2d targetPose) {
        this.robot = robot;
        this.mecanum = robot.mecanum;
        this.targetPose = targetPose;

        // default timeout
        timer = new Timing.Timer((long)Constants.DEFAULT_TIMEOUT);

        addRequirements(mecanum);
    }

    public StrafeToPose(Callisto robot, Pose2d targetPose, double timeout) {
        this.robot = robot;
        this.mecanum = robot.mecanum;
        this.targetPose = targetPose;
        this.dashboard = FtcDashboard.getInstance();

        timer = new Timing.Timer((long)timeout);

        // this will allow us to interrupt the other command that may be running
        addRequirements(mecanum);

    }

    // Initialize method to build the trajectory
    @Override
    public void initialize() {
        // only start the timer once the command is run and not built
        timer.start();

        // Build the trajectory from the current pose to the target pose
        action = mecanum.actionBuilder(mecanum.pose).strafeTo(targetPose.position).build();
    }

    // The execute method keeps updating the trajectory following
    @Override
    public void execute() {
        robot.telemetry.addData("is running?", true);
        // Create Packet for dashboard
        TelemetryPacket packet = new TelemetryPacket();

        packet.put("x", mecanum.pose.position.x);
        packet.put("y", mecanum.pose.position.y);
        packet.put("heading", mecanum.pose.heading.toDouble());

        packet.fieldOverlay()
                .setStrokeWidth(1).setStroke("Blue")
                .fillCircle(mecanum.pose.position.x, mecanum.pose.position.y,3);

        robot.telemetry.addData("leftFront:", robot.mecanum.leftFront.getVelocity());
        robot.telemetry.addData("rightFront:", robot.mecanum.rightFront.getVelocity());
        robot.telemetry.addData("leftBack:", robot.mecanum.leftBack.getVelocity());
        robot.telemetry.addData("rightBack:", robot.mecanum.rightBack.getVelocity());

        robot.telemetry.addData("Running Strafe To Pose: ", true);


        // Use the telemetryPacket with the action's run method:
        finished = !action.run(packet);
        FtcDashboard.getInstance().sendTelemetryPacket(packet);


    }

    // Check if the command has finished
    @Override
    public boolean isFinished() {
        return finished || timer.done();
    }

    // Stop the robot once the command ends
    @Override
    public void end(boolean interrupted) {
        // Stop the drive if interrupted or completed
        mecanum.stop();
    }
}

FeedForward vs. Feedback Parameters

Once you have gotten kS, kV, and kA your feedforward params YOU ARE NOT DONE.

Forward Control

  • Definition: In a forward control system, the control action is based on predefined conditions or inputs, without considering the actual output.

  • Example: Cruise control system in a car, where speed is set and maintained without continuous adjustments based on external factors.

Feedback Control

  • Definition: This system continuously monitors output results and adjusts inputs based on deviations from desired performance targets.

  • Example: A thermostat in a heating system that adjusts temperature based on current room temperature.

Key Differences

  • Responses: Forward control is proactive, relying on preset conditions, while feedback control is reactive, adjusting inputs based on actual output.

  • Accuracy: Feedback systems tend to be more accurate due to real-time adjustments.

  • Complexity: Feedback systems are usually more complex because they require continuous monitoring and adjustments.

    // feedforward parameters (in tick units)
    //public double kS = 0.6891724468066125;
    public double kS = 1.4895249721776433;
    // temporary testing values
    public double kV = 0.0004895060750799223;
    public double kA = 0.0001;

    // path profile parameters (in inches)
    public double maxWheelVel = 17.5; // over-estimating leads to instability
    public double minProfileAccel = -30;
    public double maxProfileAccel = 30;

    // turn profile parameters (in radians)
    public double maxAngVel = Math.PI; // shared with path
    public double maxAngAccel = Math.PI;

    // path controller gains
    public double axialGain = 0.5;
    public double lateralGain = 0.1;
    public double headingGain = 0.4;

    public double axialVelGain = 0.25;
    public double lateralVelGain = 0.6;
    public double headingVelGain = 0.3;

Last updated