Skip to content

RoadRunner

Lucas Bubner edited this page Dec 23, 2024 · 84 revisions

RoadRunner (Road Runner) is a motion planning library, written for the FTC robotics competition. Designed primarily for autonomous robotic movement, it allows for complex path following and generation while maintaining control of velocity and acceleration. This enables bots to have more accurate and advanced path following capabilities.

Note

RoadRunner is a significant portion of BunyipsLib, offering geometry utilities and forming the backbone for the trajectory builder. Several modifications have been made to the library to provide modular configuration steps, a type-safe unit system, an all-in-one tuning OpMode, and complete integrations with the core BunyipsLib Paradigms. This article is the largest, as it is the most significant, so take some time to read up about the processes to familiarise yourself.

Terminology

"Odometry" vs "Dead wheels"

Although in the FTC community, dead wheels and odometry are often used synonymously, they are very different things. Odometry refers to the use of sensors to determine a robot's position. Dead wheels (sometimes called odometry wheels or odometry pods) are unpowered omni wheels not connected to any motor. These wheels have rotary encoders to track the distance travelled. This data is fed through a kinematic equation and integrated to calculate the robot's relative position on the field. The advantage of using dead wheels over drive wheel odometry is that dead wheels experience very little slip compared to mecanum wheels. This improves the accuracy signifcantly when using a mecanum drive, especially in instances of high acceleration.

Localization

You'll see the term localization thrown around throughout higher level FTC teams. Localization essentially just means the ability for your bot to know where you are at any point in time. Trying to get somewhere without knowing where you are is a difficult task (this is essentially the difference between closed and open loop control). Localization is generally done through odometry but can also take form in more exotic methods such as VSLAM (see the Intel Realsense T265 which can be found on some FTC bots). Using some form of odometry (drive encoders or external dead wheels) and feeding it into their respective kinematic equations then integrating allows one to determine the relative pose (x, y, heading) of the bot.

Motion Profile

A motion profile is essentially just a graph of the behavior that something must follow to reach a certain state. In Road Runner's primary case, motion profiles are generated describing the velocity of the bot to reach a defined pose (although motion profiles can be generated for different components, like an elevator). But what we're concerned with is the bot's velocity graph. Motion profiling essentially maps out the entire movement that you need to take to get to a certain point. You can modify/control this graph by defining max velocity, max acceleration, etc.

Open vs Closed Loop Control

The difference between open and closed-loop control is a matter of whether you have feedback or not. Open-loop control can be transformed into closed-loop control if there is feedback in a system. The below process demonstrates open vs. closed control.

Let's take the FTC example of wanting to control the velocity of your motor. Let's start with open-loop control. Open-loop essentially means you're "guestimating" the value you need. You have an existing mathematical model of some components. And then you shove your value through that equation and hope that value works. So going back to our velocity control. Let's say you have a goBILDA 13.7:1 435 RPM motor. You want the motor to spin at 217.5 RPM. That's 50% speed. What you do is send 50% of the voltage to the motor right? So do a motor.setPower(0.5) which sends 6v (technically, not really. The motor speed is controlled with PWM but let's just pretend here) to the motor. However, this is the real world. That motor isn't going to go exactly 217.5 RPM. Due to physical tolerances, electrical noise, magic dust, etc, that motor will have a ±10% tolerance (according to goBILDA's own specs. Source: @ethand on the discord). Meaning, we send 6v to the motor but in reality that motor can be spinning anywhere from 174 to 261 RPM. Quite a big range! But this is the best open-loop control can give us. We just send a value and hope it works. We never actually know if it's running at the speed we desire.

What if we want to be more accurate? Say if you want a consistent velocity for your 2020-21 Ultimate Goal disc shooter. Or accurate motion profiling. Well, most FTC motors will have encoders built-in. This allows you to measure the position of the shaft. But, velocity can also be derived. We can use this velocity data to actively correct our voltage output. This is what is meant by "closing the loop." Having feedback from the encoder allows us to slightly tweak the voltage we output and lower it if the motor is going too fast or raise it if the motor is going too slow. This is often done through a PID controller, although fancier methods such as LQR do exist.

Spline Paths

Spline paths are trajectories generated using spline curves. Spline curves are piecewise polynomials that connect multiple points continuously (smoothly). These benefit autonomous trajectories because they allow an object to follow a path while changing the heading without making a point turn. Spline curves are ideal for non-holonomic drive trains. For Road Runner, spline paths will be utilised frequently as they allow continuous paths.

Geometry

Ensure to review the Geometry section of the Paradigms page to learn about the Robot Coordinate System and units for poses.

Components

Tip

Review this section from the Subsystems page for a quick overview of how RoadRunner drive and BunyipsLib components interact with each other.

Localizers

The four main localizers used in RoadRunner are listed here. Picking a localizer depends on what hardware you have access to. Additional Localizers exist with alternative/partial localization capabilities and can be read on the official accompanying Javadoc. Partial localizers cannot be tuned for as they do not function like these four standard localizers below.

MecanumLocalizer (default for MecanumDrive)

Uses the IMU and four Mecanum wheel encoders to localize the robot. Does not require localizer-specific parameters.

TankLocalizer (default for TankDrive)

Uses the left and right sets of wheel encoders to localize the robot. Does not require localizer-specific parameters.

ThreeWheelLocalizer

Uses three dead wheels (two parallel, one perpendicular) to localize the robot. Offers faster loop times compared to the TwoWheelLocalizer. Uses an instance of ThreeWheelLocalizer.Params to define the par0Ticks, par1Ticks, and perpXTicks fields (found during Tuning).

TwoWheelLocalizer

Uses two dead wheels (one parallel, one perpendicular) plus the IMU to localize the robot. Uses an instance of TwoWheelLocalizer.Params to define the parYTicks and perpXTicks fields (found during Tuning).

Accumulators

Accumulator (default)

Accumulates pose based on updates by the Localizer and performs no other changes.

AprilTagRelocalizingAccumulator

Uses a configured AprilTag processor to relocalize the robot pose, internally uses Kalman filters to smoothen out and fuse readings. Read more about this accumulator configuration in the Vision section.

BoundedAccumulator

A standard accumulator with restrictions/clamps on where the robot pose is able to be positioned, such as restricting the pose to the field to allow for relocalization by running into a wall.

PeriodicIMUAccumulator

Periodically polls the IMU every time period you define to set the current pose of the robot to the IMU heading. Useful for relocalizing three-wheel odometry.

Setting Localizers and Accumulators

To set a desired localizer and accumulator, pass them as arguments to the withLocalizer() and withAccumulator() methods. You do not have to call withAccumulator if you want to use a standard Accumulator, and you do not have to call withLocalizer if you want to use a standard TankLocalizer or MecanumLocalizer (depending on your drive instance) An example for a MecanumDrive using a ThreeWheelLocalizer and PeriodicIMUAccumulator is shown using a generic RobotConfig:

// definitions for driveModel, motionProfile, mecanumGains, and localiserParams are defined during tuning
drive = new MecanumDrive(driveModel, motionProfile, mecanumGains, hw.fl, hw.bl, hw.br, hw.fr, hw.imu, hardwareMap.voltageSensor)
        .withLocalizer(new ThreeWheelLocalizer(driveModel, localiserParams, hw.dwleft, hw.dwright, hw.dwx))
        .withAccumulator(new PeriodicIMUAccumulator(hw.imu.get(), Seconds.of(5))) // imu resets every 5 seconds

Defining LazyImu

RoadRunner is the only place in BunyipsLib where the LazyImu instance has to be used for defining the IMU. Instead of defining an IMU in your config as an IMU instance, you will need to define it as a LazyImu. A LazyImu wraps an IMU instance and delays initialisation until the .get() method is called on it.

Note

The LazyImu does not support construction via passing in an instance of an already instantiated IMU instance, so the LazyImu must be defined at the config level. The underlying instance can still be accessed via the .get() call.

To define a LazyImu in a RobotConfig, you can use the getLazyImu() method. See the official IMU configuration guide for specific IMU initialisation orientations.

hw.imu = getLazyImu(
        "imu",
        new RevHubOrientationOnRobot(
                RevHubOrientationOnRobot.LogoFacingDirection.UP, // Use the correct orientation depending on your robot!
                RevHubOrientationOnRobot.UsbFacingDirection.RIGHT
        )
);

Defining Dead Wheels

Odometry wheels are modelled from a limited DcMotor instance, where in RoadRunner, this is represented by the RawEncoder. In RobotConfig, to define dead wheels, you can simply use the getHardware() method.

// Deadwheels can be connected to ports with other motors on them! This is perfectly fine to do as directionality is unaffected on the actual motor.
hw.dwleft = getHardware("br", RawEncoder.class, (d) -> d.setDirection(DcMotorSimple.Direction.FORWARD));
hw.dwright = getHardware("fl", RawEncoder.class, (d) -> d.setDirection(DcMotorSimple.Direction.FORWARD));
hw.dwx = getHardware("bl", RawEncoder.class, (d) -> d.setDirection(DcMotorSimple.Direction.REVERSE));

Tuning

Tuning is the most significant step when using RoadRunner. Tuning allows the correct coefficients to be selected for feedforward, feedback, and localization controls. As of RoadRunner v1.0.0, the tuning process has been simplified down to several regressions, eliminating the need for the overly complex tuning process of older versions. The official docs for tuning is located at https://rr.brott.dev/docs/v1-0/tuning/.

Tip

Many of the tuning procedures requires the use of FtcDashboard. Various OpModes throughout the tuning process will expose static properties that will appear under the Configuration tab. If you change some of these values for derived tuning OpModes, you may need to reinitialise the respective OpMode. Review FtcDashboard in the IO section.

To begin tuning, create a new class that extends RoadRunnerTuningOpMode. You will be given access to one method override, which should return the RoadRunnerDrive instance you wish to tune.

Important

If you are using a custom Accumulator, consider switching back to the default by temporarily commenting it out! Accumulators other than the default are not useful in the tuning process and can cause your tuning to be inaccurate or wrong. Ensure to set the Localizer you wish to use.

import androidx.annotation.NonNull;

import com.qualcomm.robotcore.eventloop.opmode.TeleOp;

import au.edu.sa.mbhs.studentrobotics.bunyipslib.roadrunner.RoadRunnerDrive;
import au.edu.sa.mbhs.studentrobotics.bunyipslib.roadrunner.tuning.RoadRunnerTuningOpMode;

@TeleOp(name = "RoadRunner Tuning")
public class RoadRunnerTuning extends RoadRunnerTuningOpMode {
    @NonNull
    @Override
    protected RoadRunnerDrive getDrive() {
        Robot robot = new robot();
        robot.init(this);
        return robot.drive; // robot.drive is using a standard Accumulator, with Localizer configured
    }
}

Caution

If you're using a RobotConfig (like the example above), you must pass this as a parameter to init(), as the config is not being run from the context of a BunyipsOpMode. A helpful exception will be thrown if you forget this parameter.

When you run the OpMode, you will be greeted by a TelemetryMenu to select a Tuning OpMode. Use Gamepad 1 to select an OpMode using d-pad up, d-pad down, and A to select. This choice is remembered by a static variable and auto-selected when play is pressed, so if you hover over an OpMode, it will execute when the play button is pressed.

RoadRunner tuning can now begin. If applicable to your robot (denoted by brackets after the step), run the OpMode in the title and follow the instructions under each section sequentially until you reach the bottom. The goal is to fill in all the coefficients for the DriveModel, MotionProfile, Mecanum or TankGains, and any other Localizer coefficients. These coefficients should be built into one cumulative object per constants class, and defined locally wherever your drive is defined to pass them in as arguments (such as in RobotConfig).

HardwareTester (optional)

Goal: Hardware sanity check

Use the BunyipsLib-integrated Hardware Tester OpMode to ensure motors and dead-wheels are configured and counting correctly. If you would like to reverse an encoder, it can be done on the internal encoder object (if using RawEncoder), or on the Encoder object by Motor. You can also reverse the entire motor with setDirection().

Note

The direction of each Encoder is independent of the DcMotorEx it’s created with. Changing the direction of an Encoder has no effect on the direction of its associated DcMotorEx (and vice versa).

MecanumDirectionDebugger (mecanum only)

Goal: Ensure Mecanum wheels are configured correctly

This test is the RoadRunner-equivalent of performing a HardwareTester test. This will ensure your wheel directions are correct. The OpMode uses the following button mappings:

/**
 * Xbox/PS4 Button - Motor
 *   X / ▢         - Front Left
 *   Y / Δ         - Front Right
 *   B / O         - Rear  Right
 *   A / X         - Rear  Left
 *                                    The buttons are mapped to match the wheels spatially if you
 *                                    were to rotate the gamepad 45deg°. x/square is the front left
 *                    ________        and each button corresponds to the wheel as you go clockwise
 *                   / ______ \
 *     ------------.-'   _  '-..+              Front of Bot
 *              /   _  ( Y )  _  \                  ^
 *             |  ( X )  _  ( B ) |     Front Left   \    Front Right
 *        ___  '.      ( A )     /|       Wheel       \      Wheel
 *      .'    '.    '-._____.-'  .'       (x/▢)        \     (Y/Δ)
 *     |       |                 |                      \
 *      '.___.' '.               |          Rear Left    \   Rear Right
 *               '.             /             Wheel       \    Wheel
 *                \.          .'              (A/X)        \   (B/O)
 *                  \________/
 */

Reverse any motors running in the wrong direction with setDirection(...), and do the same for corresponding drive encoders as well.

DeadWheelDirectionDebugger (dead wheels only)

Run DeadWheelDirectionDebugger and manually spin the dead-wheels on your robot, either by hand or by pushing the robot. As the robot moves left, parallel deadwheel tick readings should remain relatively stationary, and the perpendicular readings should increase. As the robot moves forward, parallel deadwheel tick readings should increase, while the perpendicular readings should remain relatively stationary.

ForwardPushTest (all)

Goal: determine DriveModel field inPerTick empirically

Place the robot on the tiles with plenty of room in front. Square the robot up with the grid and make note of its starting position. Run ForwardPushTest and then slowly push or pull the robot straight until the end of the tiles. Record the “ticks traveled” from telemetry before stopping the op mode. Without moving the robot, record also the forward distance traveled on the tiles in inches. Set the inPerTick variable in your drive class to the real distance in inches traveled divided by the ticks traveled.

Make sure the wheels don’t slip! The motors should spin freely.

A DriveModel builder is used to set the inPerTick field.

DriveModel driveModel = new DriveModel.Builder()
        // ...
        .setInPerTick(distIn / ticksTravelled)
        // Alternative methods of setting inPerTick (not recommended, as a raw decimal inPerTick value is required for later tuning):
        // .setDistPerTick(Inches.of(distIn), ticksTravelled)
        // .setComputedInPerTick(tpr, gearRatio, wheelDiameter)
        .build();

Note

If your robot is too light to do a ForwardPushTest (encoder slip), you can use a temporary computed value for inPerTick using the setComputedInPerTick method attached to the DriveModel builder.

LateralPushTest (mecanum with drive encoders only)

Goal: determine DriveModel field lateralInPerTick empirically

This routine is simply a version of ForwardPushTest that measures leftward motion instead of forward motion. Set the robot up as before, slowly push it left, and set lateralInPerTick to the distance divided by ticks. The value you get should be positive.

DriveModel driveModel = new DriveModel.Builder()
        // ...
        .setLateralInPerTick(distIn / ticksTravelled)
        .build();

You can use the same utility methods from previously for setting custom unit per ticks, but do note a raw decimal lateralInPerTick value for these parameters is required for tuning later.

The measured value includes the inevitable strafing slip (previous versions compensated for this explicitly with lateralMultiplier), so you should expect it to be smaller than laterInPerTick by a modest amount.

Tip

FtcDashboard is now going to be used hereon in the tuning process. Reviewing the IO section for FtcDashboard is strongly recommended if not done already.

ForwardRampLogger (dead wheels only)

Goal: determine MotionProfile fields kS and kV empirically

This routine slowly increases the forward power given to the robot and measures the forward velocity over time to calculate the static and velocity feedforward parameters (kS and kV, respectively). By default, the power will increase by 0.1 each second until it reaches 0.9.

Place your robot on the tiles with as much distance in front of it as possible. Start the OpMode and press stop immediately when the robot nears the edge of the tile. Don’t expect anything to be displayed in telemetry. All data collected is saved to a file for further analysis.

Warning

This OpMode does not terminate on its own, so be sure to press STOP when there is no more room! The longer the logger runs for, the more accurate the regression will be.

Once you finish, connect your computer to the RC wireless network using these instructions.

Control Hub URLs will be used in further links for brevity.

You should see a page that looks like this:


Click the “Latest” button, and you should see a graph appear:


The gray points are the measurements made by the tuner, and the red line is the line of best fit. Its from this line that the feedforward parameters will be extracted. In fact, you can see preliminary values for kS and kV already displayed above. But those estimates are limited by the presence of outliers. You can see that the red line doesn’t quite fit the trend. Let’s help the algorithm out by manually filtering out outlier points.

First, click and drag to select a rectangular region of the plot:


Then to remove those points, press the “e” key or the “exclude” button above. The selection box will disappear, and the points will turn a lighter gray. After repeating this process as many times as necessary, you should end up with a plot like this:


If you mess up and accidentally exclude non-outlier points, select them and press “i” or click the include button to bring them back into the calculation.

Set these kS and kV values as copied from the webpage into your MotionProfile:

MotionProfile motionProfile = new MotionProfile.Builder()
        .setKv(...)
        .setKs(...)
        .build();

LateralRampLogger (mecanum with dead wheels only)

Goal: determine DriveModel field lateralInPerTick empirically

If all is configured correctly, the logger OpMode will move the robot to the left, increasing in speed as it goes (similar to ForwardRampLogger). Stop it at any point, keeping in mind that longer runs will collect more data.

When you’re done, go to http://192.168.43.1:8080/tuning/lateral-ramp.html and click the “Latest” button. The slope reported is lateralInPerTick.

DriveModel driveModel = new DriveModel.Builder()
        // ...
        .setLateralInPerTick(lateralInPerTick)
        .build();

Important

A multiplicative factor alone unfortunately doesn’t adequately capture the strafing behavior of most robots. It’s common to see a plot with a plateau in the beginning:

There’s nothing much to be done about the poor fit during tuning. Future versions of Road Runner may change the strafing model to get a better fit (progress will be tracked on this issue).

AngularRampLogger (all)

This routine is very similar to the last except that it rotates in place instead of moving forward. Run it in the same fashion you would run a ForwardRampLogger or LateralRampLogger, with the added benefit the robot should not crash since it will rotate instead.

The longer the logger is run, the more accurate data will be collected. After running the logger, follow the below specific instructions based on your localization method:

Drive Encoders

Goal: determine DriveModel field trackWidthTicks and MotionProfile fields kS and kV empirically

Go to http://192.168.43.1:8080/tuning/drive-encoder-angular-ramp.html and click the “Latest” button. Use the instructions from the ForwardRampLogger analysis to get kS, kV from the the “Ramp Regression” plot. Then use the same outlier-exclusion technique on the “Track Width Regression” and set trackWidthTicks to the “track width” value when you’re finished.

DriveModel driveModel = new DriveModel.Builder()
        // ...
        .setTrackWidthTicks(trackWidthTicks)
        .build();

Dead Wheels

Goal: determine DriveModel field trackWidthTicks and odometry Params fields (perpXTicks, etc.) empirically

Go to http://192.168.43.1:8080/tuning/dead-wheel-angular-ramp.html and click the “Latest” button. Copy the kS and kV values from ForwardRampLogger into the appropriate boxes and click the “update” button. Use the instructions from the ForwardRampLogger analysis to fill in trackWidthTicks in DriveModel and the wheel position in your localizer Params object.

There should be multiple plots. Scroll down to make sure you don’t miss any.

DriveModel driveModel = new DriveModel.Builder()
        // ...
        .setTrackWidthTicks(trackWidthTicks)
        .build();

// For three-wheel
ThreeWheelLocalizer.Params localiserParams = new ThreeWheelLocalizer.Params.Builder()
        .setPar0YTicks(par0Ticks)
        .setPar1YTicks(par1Ticks)
        .setPerpXTicks(perpXTicks)
        .build();

// For two-wheel
TwoWheelLocalizer.Params localiserParams = new TwoWheelLocalizer.Params.Builder()
        .setParYTicks(parYTicks)
        .setPerpXTicks(perpXTicks)
        .build()

Important

To get an accurate trackWidthTicks value, you need accurate values for kS and kV.

LocalizationTest (all)

Goal: verify robot localization

Running the LocalizationTest, you should be able to control the robot using Gamepad 1. Use FtcDashboard to ensure the robot is tracking relatively accurately, the red line that extends from the robot on the field represents the measured velocity.

Warning

If your localization on the dashboard is very inaccurate, restart the tuning steps and verify your hardware is configured properly! Note that the lateral movement of the robot is non-linear depending on speed, so this value may never actually converge to a perfect strafing model. This issue may be corrected in a later version of RoadRunner.

ManualFeedforwardTuner (all)

Goal: fine-tune MotionProfile fields kS, kV, and adding in kA

This routine repeatedly drives forward and back DISTANCE units, giving you an opportunity to finalize the feedforward parameters.

To adjust the feedforward components on the dashboard, under the Configuration tab adjust the "[RR] Tuning Parameters" subsection fields tuningMotionProfile_kS, tuningMotionProfile_kV, and tuningMotionProfile_kA entries. A refresh of the page while the OpMode is active may be required if these fields are null or not visible.

Open FTC Dashboard by navigating to http://192.168.43.1:8080/dash. Run the OpMode, and graph vref against v0. Set kA to a small value like 0.0000001 and slowly increase it by a factor of ten until it starts affecting the plot. Try to make the two lines in chart as close together as possible.

Warning

Your tuning graph should plateau (flatten) at the top and bottom of the vref lines. An example of an improper vref graph is shown:


In this case, increase DISTANCE of ManualFeedforwardTuner in FtcDashboard or decrease your robot maxWheelVel, to ensure a trapezoidal plateau is followed.

Tip

At this point, the robot still has no feedback and may drift over many cycles. Pressing Y/Δ (Xbox/PS4) will pause the tuning process and enter driver override, allowing you to reset the position of the bot. Pressing B/O (Xbox/PS4) will return to the tuning process.

Important

If you see bumps on your graph when the robot is decelerating, as shown below, this is normal.


This issue is caused by a fundamental hardware issue in the robot hubs that cannot be resolved. There is not much you can do about these bumps, so you can ignore them and tune the rest of the graph as best as you can.

ManualFeedbackTuner (all)

Goal: tune the MecanumGains/TankGains coefficients

This routine also goes back and forth DISTANCE units but using combined feedforward and feedback.

Use this opportunity to tune the feedforward parameters of your trajectory following controller.

Tip

If the robot goes off course, you can take over control by holding down the right bumper. Releasing will start following a straight line trajectory from the current robot pose forward.

MecanumDrive

There are two gains for each travel direction (forward, lateral, heading). The first (“position gain”) is like the proportional term of a position PID, and the second (“velocity gain”) is like the derivative term of a position PID. Here are some tips:

  • Focus on tuning one parameter at a time.
  • Start by setting a small value like 1 and adjust from there.
  • Nudge the robot to introduce disturbances and watch them be corrected.
  • Skip the velocity gains unless you know what you’re doing.

These fields can be tuned on the dashboard under "[RR] Tuning Parameters" > tuningMecanumGains_XXX.

Note

A browser page refresh may be required if you only see null fields for the Mecanum gains. The TankGains fields should remain null.

TankDrive

The two Ramsete gains shouldn’t need much tuning. According to the FRC Docs, “Larger values of bBar make convergence more aggressive like a proportional term whereas larger values of zeta provide more damping in the response.”

These fields can be tuned on the dashboard under "[RR] Tuning Parameters" > tuningTankGains_XXX.

Note

A browser page refresh may be required if you only see null fields for the tank gains. The MecanumGains fields should remain null.

SplineTest (all)

Goal: verify complete tuning process

This routine follows a basic spline from the centre of the field to the tile on the far left wall. This step verifies all steps of tuning.

Important

The Spline Test is simply a normal trajectory! You can test your own trajectories and get straight into Autonomous if you'd like if this path is implausible.

You're all done! Ensure the values for tuning are saved to the robot configuration. If you make any major hardware changes to the robot, including weight changes, tuning may have to be done again. Tuning is a process that gets faster the more you do it, so get used to it.

Adjusting Robot Constraints

After configuring and tuning your robot, you should set up the suitable constraints. These are exposed as fields on MotionProfile, and include setting your maximum default velocity and acceleration constraints. An object below shows the setting of new defaults.

MotionProfile motionProfile = new MotionProfile.Builder()
        // .setKv(...)
        // .setKs(...)
        // .setKa(...)
        .setMaxWheelVel(FieldTilesPerSecond.of(2))
        .setMinProfileAccel(FieldTilesPerSecondPerSecond.of(-4))
        .setMaxProfileAccel(FieldTilesPerSecondPerSecond.of(8))
        .setMaxAngVel(DegreesPerSecond.of(180))
        .setMaxAngAccel(DegreesPerSecondPerSecond.of(270))
        .build();

Tip

Using the LocalizationTest can assist in determining the maximum constraints of your robot, by looking at the PoseVelocity2d field that shows up in telemetry. All reported geometry units are in inches.

The base defaults for RoadRunner are a max velocity of 40 in/s, symmetric accel limit of 30 in/s, max angular velocity of 170 deg/s, and max angular acceleration of 180 deg/s.

Extra Mecanum Options

For the MecanumDrive, some additional options exist due to holonomic properties and since the Mecanum drive is the most commonly used drive. Further configurations may exist for future drives, but is up to the Release cycle.

Path follower mode

To switch the paradigm from a time-based follower to a displacement trajectory follower, which will set the target to the closest point on the path (similar to Pure Pursuit), you can add an additional parameter to the MecanumGains object.

MecanumGains mecanumGains = new MecanumGains.Builder()
        // ...
        .setPathFollowing(true)
        .build();

All built trajectories will now follow the displacement follower, which may provide faster pushing towards the goal rather than performing a full motion profile per standard RoadRunner. You can review more about this mode on the official docs linked above.

Error thresholds

Road Runner uses feedback control while following trajectories to correct for disturbances and end up in the desired final pose. However, the correction timing may be insufficient, as the feedback controllers may not have enough time to correct. Holonomic drivebases have the option of running the feedback controllers for some additional time after a trajectory has ended, to ensure the end pose is met.

By default, BunyipsLib will allocate 0.5 seconds of extra stabilisation time, allowing a maximum error of 2 inches and 1 degree for stabilisation. There is an extra velocity cutoff where stabilisation will only propagate for velocities under 0.5 in/s and 5 deg/s.

You can set your own error thresholding by passing an instance of ErrorThresholds into the MecanumDrive withErrorThresholds, as shown:

drive = new MecanumDrive(/* ... */)
       .withLocalizer(/* ... */)
       .withAccumulator(/* ... */)
       .withErrorThresholds(new ErrorThresholds(
               Seconds.of(1), // stabilisation timeout buffer
               Inches.of(1), // max translational error
               InchesPerSecond.of(0.1), // min translational vel consideration threshold
               Degrees.of(0.5), // max angular error
               DegreesPerSecond.of(2) // min angular vel consideration threshold
       ));

Tip

To disable extra error thresholding, you can use .withErrorThresholds(ErrorThresholds.NONE)

You can review more about this correction on the official docs linked above.

Task Builder

Now that your robot is fully configured and ready to go, creating trajectories and making them into Task instances is the next step.

Construction

In order to construct a trajectory, a TaskBuilder instance is used. This instance can be accessed through any RoadRunner drive using the makeTrajectory method.

The following commands use a builder pattern to construct a RoadRunner path. The methods elaborated here can be combined to form full trajectories. References found throughout this section come from the Cookbook, with additions to include the unit system of BunyipsLib.

Tip

See the accompanying API documentation for this builder here.

Unit system

All builder methods support BunyipsLib units, to allow for units other than the inch and radian to be used. These are optional parameters - passing in regular parameters as per the standard RoadRunner TrajectoryBuilder will work for most of the old methods (most examples shown in the Complete Reference Guide work as-is). Kotlin users using the builder may need to pass in hints to the parameters if using implicit arguments (e.g. Vector2d(0, 0), heading = PI / 2)

Important

The major changes made to the BunyipsLib task builder vs. the standard RoadRunner one is that the BunyipsLib one provides unit overloads and delegates constraints to builder settings (explained below), and some methods that take in instances of Pose2d now have extra overloads for Vector2d and Double, as Pose2d instances cannot be unit converted and must be in inches + radians.

All references here will use the unit system - implicit construction without units assumes inches and radians as per standard RoadRunner.

Constraints changes

Since there are now many overloads required for a unit system, the parameters to pass in new velocity and acceleration constraints has been moved back into two builder methods, setVelConstraints and setAccelConstraints (also reset methods to revert to default).

These work the same as they did in RoadRunner 0.5.6. By setting constraints, all future builder calls will now respect those constraints, as shown:

drive.makeTrajectory()
        .setVelConstraints(Vel.ofMax(5, InchesPerSecond))
        // builder instructions here will respect 5 inches per second max velocity, default ang vel
        .setAccelConstraints(Accel.ofMax(2, InchesPerSecondPerSecond).andMin(-2, InchesPerSecondPerSecond))
        // builder instructions here will respect 5 in/s PLUS plus-minus 2 in/s/s accel constraints, default ang vel+accel
        .resetVelConstraints()
        .resetAccelConstraints()
        // back to default constraints

Tip

The Vel and Accel utility classes can assist with making constraints. Custom constraints can also be made as per this section of the official docs (in units of inches).

Builder methods

waitFor(Double, Time) and waitSeconds(Double)

Suspends the trajectory and waits for the inputted amount of time before continuing.

Caution

Ensure that you are using waitFor/waitSeconds and not wait(). All Java objects have a wait() function which causes the current thread to wait until another thread invokes a notify() or notifyAll() method. See further details in the Oracle JavaDoc. We don't care for this function, but it does show up as a suggestion.

turn(Double, Angle)

Turns the robot +angle counter-clockwise by the specified angle. This is a delta operation, so calling turn(90, Degrees) twice will turn the robot a full 180 degrees at the end of its trajectory.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 30, Degrees) // starts at 0,0 facing 30 degrees CCW
        .turn(-30, Degrees) // 30 degrees CW
        .waitFor(5, Seconds) // Robot will wait 5 seconds before continuing
        .turn(30, Degrees) // 30 degrees CCW
        .addTask(); // result below
waitAndTurn.mp4

turnTo(Double, Angle)

Turns the robot to the specified angle. This is a global operation, so calling turnTo(90, Degrees) twice will turn the robot to 90 degrees and then by 0 degrees as it is already at 90 degrees.

Important

By default, the robot will turn in the shortest direction to the specified heading. For 180-degree turns, this is ambiguous, so you can add or subtract a very small value (+ 1.0e-6) to flip the direction. This seems cursed, but it is the best method.

// implicit unit demonstration
drive.makeTrajectory(new Pose2d(0, 0, Math.PI / 6)) // both can be omitted as they are already inches and radians, so we can use Pose2d
        .turnTo(Math.PI / 2) // radians is the default unit so the type can be omitted
        .turnTo(Math.PI / 6) // 30 degrees in radians
        .addTask(); // result below
turnTo.mp4

setTangent(Double, Angle)

Sets the path tangent to use for the next builder instructions. This allows the next called methods on the builder to be run at arbitrary tangents.

A path tangent is the heading at which the path runs. The robot heading is instead the heading of the robot at the time, which can be discontinuous with the path tangent. For example, if a robot ran a spline while facing backwards, the path tangent would be 180 degrees desynchronised from the robot heading.

Important

Path tangents are essential in ensuring continuity and smooth paths. Without tangent modification, your robot will stop and start along the full trajectory, as the mathematical model of Hermite splines cannot have discontinuities.

setReversed(Boolean)

Flips the trajectory path direction to traverse it backwards instead of forwards. Useful for splines that should be run with the robot running in reverse. Without running in reverse, spline trajectories will attempt to keep tangent and can cause inefficient hooks to form on your trajectory, as shown below:

drive.makeTrajectory(new Vector2d(0, 0), Inches, 30, Degrees)
        .splineTo(new Vector2d(-48, -24), Inches, -90, Degrees)
        .splineTo(new Vector2d(-48, 0), Inches, 180, Degrees)
        .addTask(); // result below
notReversed.mp4

These can be corrected for by using setReversed, as shown:

drive.makeTrajectory(new Vector2d(0, 0), Inches, 30, Degrees)
        .setReversed(true)
        .splineTo(new Vector2d(-48, -24), Inches, -90, Degrees) // this spline will run backwards
        .setReversed(false)
        .splineTo(new Vector2d(-48, 0), Inches, 180, Degrees) // continue forward
        .addTask(); // result below
reversed.mp4

strafeTo(Vector2d, Distance) and strafeToConstantHeading(Vector2d, Distance)

Moves to the specified coordinates while maintaining heading. strafeTo and strafeToConstantHeading are equivalent methods.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 30, Degrees)
        .strafeTo(new Vector2d(2, -2), FieldTiles) // 1 field tile is 24 inches
        .addTask(); // result below
strafeTo.mp4

strafeToLinearHeading(Vector2d, Distance, Double, Angle)

Moves to the specified coordinates while linearly interpolating heading between the current heading and specified target heading. Linear interpolation refers to constantly incrementing towards the target angle.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 30, Degrees)
        .strafeToLinearHeading(new Vector2d(36, -36), Inches, 180, Degrees)
        .addTask(); // result below
strafeToLinearHeading.mp4

strafeToSplineHeading(Vector2d, Distance, Double, Angle)

Moves to the specified coordinates while spline interpolating heading between the current heading and specified target heading. Spline interpolation refers to incrementing towards the angle in a curved fashion.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 30, Degrees)
        .strafeToSplineHeading(new Vector2d(36, -36), Inches, 180, Degrees)
        .addTask(); // result below
strafeToSplineHeading.mp4

lineToX(Double, Distance) and lineToXConstantHeading(Double, Distance)

Moves to the specified X coordinate in the direction of the robot's heading (straight line). lineToX and lineToXConstantHeading are equivalent methods.

Warning

It is highly recommended to use a strafeTo with an X component rather than a lineToX! This is because if the heading is perpendicular to the robot is travelling, lineToX will throw an exception will be thrown as it is no longer orthogonal.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 30, Degrees)
        .lineToX(48, Inches)
        .addTask(); // result below
lineToX.mp4

lineToY(Double, Distance) and lineToYConstantHeading(Double, Distance)

Moves to the specified Y coordinate in the direction of the robot's heading (straight line). lineToY and lineToYConstantHeading are equivalent methods.

Warning

It is highly recommended to use a strafeTo with a Y component rather than a lineToY! This is because if the heading is perpendicular to the robot is travelling, lineToY will throw an exception will be thrown as it is no longer orthogonal.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 30, Degrees)
        .lineToY(36, Inches)
        .addTask(); // result below
lineToY.mp4

splineTo(Vector2d, Distance, Double, Angle)

Moves to the specified coordinates in a spline path while following a tangential heading interpolator.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 90, Degrees)
        .splineTo(new Vector2d(48, 48), Inches, 90, Degrees)
        .addTask(); // result below
splineTo.mp4

splineTo(Vector2d, Distance, Double, Angle) with tangent

Follows the spline while maintaining the tangent heading.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 90, Degrees)
        .setTangent(0, Degrees) // spline heading is at 0 degrees
        .splineTo(new Vector2d(48, 48), Inches, 90, Degrees)
        .addTask(); // result below
splineToWithTangent.mp4

splineToConstantHeading(Vector2d, Distance, Double, Angle)

Moves to the specified coordinates in a spline path while keeping the robot heading constant. Changing the shape of the spline can be done by adjusting the last angle parameter (tangent).

drive.makeTrajectory(new Vector2d(0, 0), Inches, 90, Degrees)
        .setTangent(0, Degrees)
        .splineToConstantHeading(new Vector2d(48, 48), Inches, 90, Degrees)
        .addTask(); // result below
splineToConstantHeading.mp4

splineToLinearHeading(Vector2d, Distance, Double, Angle)

Moves to the specified coordinates in a spline path while linearly interpolating robot heading separately. Changing the shape of the spline can be done by adjusting the last angle parameter (tangent). The second angle adjusts the linear interpolation target of the robot heading.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 90, Degrees)
        .setTangent(0, Degrees)
        .splineToLinearHeading(new Vector2d(48, 48), Inches, 0, Degrees, 90, Degrees)
        .addTask(); // result below
splineToLinearHeading.mp4

splineToSplineHeading(Vector2d, Distance, Double, Angle)

Moves to the specified coordinates in a spline path while spline interpolating robot heading separately. Changing the shape of the spline can be done by adjusting the last angle parameter (tangent). The second angle adjusts the spline interpolation target of the robot heading.

drive.makeTrajectory(new Vector2d(0, 0), Inches, 90, Degrees)
        .setTangent(0, Degrees)
        .splineToSplineHeading(new Vector2d(48, 48), Inches, 0, Degrees, 90, Degrees)
        .addTask(); // result below
splineToSplineHeading.mp4

Note: asymmetric deacceleration is not displayed in this specific visualisation; splineToSplineHeading does not impact this

Integrating with tasks

Once your trajectory has been built using the builder methods above, there are a few more builder and finalising methods you can use to transform this into a Task to use. The Action system of RoadRunner has been transformed into the Task system of BunyipsLib.

1. withTimeout(Measure<Time>)

This method manually sets the timeout of the constructed task group. By default, this timeout is set to the trajectory time (if using timed trajectories), or is infinite if you're using the path follower.

2. withName(String)

This method sets the name of the trajectory to show up in telemetry and other places. By default, this will be a description of the trajectory segments, which could get long and messy! Making names for your trajectories can help provide more concise telemetry.

3. build()

This method returns the built trajectory as an ActionTask. This Task functions as any other task. The built task is attached to the BunyipsSubsystem it was built on.

4. withPriority(AutonomousBunyipsOpMode.TaskPriority)

For AutonomousBunyipsOpMode, you can mention where the addTask() call will add the trajectory in the queue. This functions equivaneltly to the addFirst, and addLast methods of AutonomousBunyipsOpMode.

5. addTask()

This method is a utility that will auto-build the trajectory and attempt to add it to the AutonomousBunyipsOpMode task queue statically. This reduces the need to call add(drive.makeTrajectory().build()), although if used in composition with other tasks, build() will still need to be used (see below). This method throws an exception if not used in the context of an AutonomousBunyipsOpMode.

Chaining trajectories

In AutonomousBunyipsOpMode, trajectories often have to be chained among other tasks. For example, running two tasks at the same time with a drive instance can be accomplished with:

add(
    new ParallelTaskGroup(
        drive.makeTrajectory(/* ... */)
            // ...
            .build(),
        new OtherTask()
    )
)

or more concisely with the Task utility:

add(drive.makeTrajectory(/* ... */)
        // ...
        .build()
        .with(new OtherTask()));

functioning as any other task would in the BunyipsLib Task system.

Trajectories can also be composed with other Action or Task instances to run at specific events, similar to composing them into a Parallel/Sequential TaskGroup as shown above. The methods are built into the TaskBuilder and include:

stopAndAdd(Action) and stopAndAdd(InstantFunction)

Stops the current trajectory and queues an Action or Task to run next after the previous trajectory instruction.

afterDisp(Double, Distance, Action) and afterDisp(Double, Distance, InstantFunction)

Schedules an Action/Task or function to execute in parallel starting at a displacement after the previous trajectory instruction. The action start is clamped to the span of the current trajectory.

afterTime(Double, Time, Action) and afterTime(Double, Time, InstantFunction)

Schedules an Action/Task or function to execute in parallel starting at an interval after the previous trajectory instruction.

Tip

Either the builder pattern or manual composition into tasks are valid ways of performing this sort of parallelization, but do note the RoadRunner approach may cause issues with parallel hardware writes as the concurrency protections are not available.

Sometimes, capturing the end pose of each spliced trajectory may be desired. This pose may be needed in two separate tasks between other robot actions, and there are two main ways of doing this.

Built-in fresh() method

The fresh() method can be called on a TaskBuilder to return a new instance of a builder that is situated at the endpoint of the current builder, as shown:

TaskBuilder one = drive.makeTrajectory(new Pose2d(0, 0, 0))
        // ...
        .lineToX(10);

add(one.build()); // runs from (0,0,0) to (10,0,0)

one.fresh() // starts at (10, 0, 0)
        .lineToY(10)
        .addTask(); // runs from (10,0,0) to (10,10,0)

Splicing using a Reference<Pose2d>

Sometimes, calling fresh and manually managing builders is not ideal, especially if there are many nested/grouped tasks involved and you don't want to rearrange your code structure. You can optionally use a Reference from BunyipsLib which will store the end spliced pose inside of it when the trajectory is built.

You must define your own Reference, then pass it into build() or addTask() for it to be filled. Chaining trajectories can be done with the same Reference.

Reference<Pose2d> last = Reference.of(new Pose2d(0, 0, 0)); // initial pose

drive.makeTrajectory(last.get())
        .lineToX(10)
        .addTask(last); // saves last spliced pose (10,0,0) to last

drive.makeTrajectory(last.get()) // last.get() returns Pose2d(10,0,0)
        .lineToY(10)
        .addTask(last); // runs from (10,0,0) to (10,10,0)

// last.get() now returns Pose2d(10,10,0)

Pose Mapping

In many seasons of FTC, the field is often a reflection or other transformation depending on what alliance the robot is located. This leads to two trajectories - often with the same coordinates but some inverted - to be developed.

A pose map can alleviate the trouble of adjusting coordinates for mirrored or otherwise mappable trajectories. To use one, simply pass an extra argument into the makeTrajectory method on your RoadRunner drive.

The PoseMap is especially useful in combination with the AutonomousBunyipsOpMode selectedOpMode used on a StartingConfiguration, as shown:

// in the context of AutonomousBunyipsOpMode onReady
StartingConfiguration.Position startingPosition = (StartingConfiguration.Position) selectedOpMode.require();

PoseMap poseMap = startingPosition.isBlue() ? new SymmetricPoseMap() : new IdentityPoseMap();
drive.makeTrajectory(initialPose, poseMap)
    // trajectory here will be flipped depending on the selected alliance
    .addTask();

Tip

There are three built-in PoseMaps, being the IdentityPoseMap (default), the SymmetricPoseMap, and MirroredPoseMap. The IdentityPoseMap performs no mapping, and is the default implicit option. The SymmetricPoseMap flips the alliance side rotationally, for fields such as the INTO THE DEEP field, while the MirroredPoseMap reflects over the alliance axis, such as the CENTERSTAGE field.

Implicit pose maps

If using an implicit makeTrajectory() call (no pose argument) and you provide a PoseMap (makeTrajectory(poseMap)), an additional operation will be performed to doubly transform the pose to maintain global coordinates. This will pass the current pose of the robot into the pose mapping, then again when it is actually mapped to return to the original pose.

Note

If your PoseMap is not idempotent, such that mapping the mapped pose does not return the original pose, this operation will fail. The default three provided PoseMaps are idempotent.

If you wish to map the pose anyways, explicitly pass the pose parameter (the used parameter in an implicit calling is Storage.memory().lastKnownPosition).

Important

Why does this happen? When an implicit call to makeTrajectory() is made, it is assumed that the current pose of the robot at the time of calling will be used. As such, performing a PoseMap on this current pose will discard the fact that the current pose does not need to be mapped, and will cause unexpected behaviour.

You can review more about how the pose map impacts the coordinates on the official docs linked above.

Tips and Troubleshooting

1. When I run a trajectory, the robot races off into a random direction!

This can be due to a few problems, the most common offender is failing to set the initial pose of the robot. By default, the robot pose is situated at (x=0,y=0,r=0), the center of the field.

// ❌ Initial pose not set, the robot will use feedback controllers to aggressively correct forward-left then return back to the origin
drive.makeTrajectory(new Pose2d(30, 30, 0))
    .strafeTo(new Vector2d(0, 0))
    .addTask();

Instead, use the setPose method to update the Accumulator first. If you're using a StartingConfiguration, this is as simple as setting the pose to the result of .toFieldPose(), then using an implicit makeTrajectory() call.

// ✅ Initial pose is set, the robot will travel backwards and right in a continuous motion
Pose2d initial = new Pose2d(30, 30, 0);
drive.setPose(initial);
drive.makeTrajectory(initial) // initial parameter can actually be omitted here as it is known implicitly
    .strafeTo(new Vector2d(0, 0))
    .addTask();

Tip

Always use FtcDashboard and the Field view to see what the robot is attempting. The blue circle when a trajectory is active indicates where the robot thinks it is, and the green circle is what the robot is trying to do.

2. The implicit constructor makes a trajectory from where the robot was initially, not where it is now!

The implicit makeTrajectory() call will capture the current pose of the robot at the time the trajectory is created. This means if you call it expecting to be progressed along the path at the new robot pose, the entire trajectory will try to correct back to wherever the initial pose was.

This is not ideal, and there are two ways this problem can be solved:

Solution 1. Pass a pose to the builder

This is the proper way to resolve this problem, as the implicit pose is far too stale to use if you experience this problem.

You can review splicing poses between builders in the above section, or you can simply supply the start yourself. Solution 2 offers a solution if knowing the current pose is not possible.

Solution 2. Use a task deferral

It is much more recommended to use Solution 1 when dealing with pose splicing, however, you can use a DynamicTask (or the defer method of AutonomousBunyipsOpMode or Task) if desired to start the trajectory from the robot's current position.

Warning

Task deferrals are tasks that are built at runtime, so the trajectory is not evaluated until the task is run. However, this approach may induce noticeable lag in your trajectories, as they need to build at runtime which can take some milliseconds.

A deferral makes the value for lastKnownPosition correct to be the position of the robot, as the trajectory is evaluated with the last pose being set. An example is provided below for an AutonomousBunyipsOpMode.

defer(() -> robot.drive.makeTrajectory() // initial pose will now be the current position of the robot when the task is run
               // ...
               .build()); // this DynamicTask is added to the queue and will build the task when it is run

Deferrals are also useful for other applications, such as making trajectories that are dependent on runtime information, such as the TEAM PROP from CENTERSTAGE.

Credit for materials on this page goes to the creators of RoadRunner at ACME Robotics (https://rr.brott.dev/), and the resources at https://learnroadrunner.com/!
Clone this wiki locally