Skip to main content

TrajectoryBuilder Reference

This page lists common Roadrunner TrajectoryBuilder functions along with a description and demonstration of them. All of the functions listed below should be put inside a trajectoryBuilder which could then be created into an action and run. The following code shows a demonstration of how the following trajectories could be run.

Notice

This page only covers functions for the TrajectoryBuilder. TrajectoryActionBuilder includes these functions along with other ones for turning and other actions. TODO: Should we make a separate page for this? Also build() technically not TrajectoryBuilder function.

Pose2d beginPose = new Pose2d(-16.0, -55.0, Math.toRadians(90.0));
MecanumDrive drive = new MecanumDrive(hardwareMap, beginPose);

TrajectoryActionBuilder traj;
Action trajAction;

traj = drive.actionBuilder(drive.pose)
// Put your functions here
.strafeTo(new Vector2d(30.0, 10.0))
.strafeTo(new Vector2d(-30.0, -10.0));

trajAction = traj.build()

// Run trajectory
Actions.runBlocking(trajAction);
Be careful

The video demonstrations of the commands shown below are shown from the point of view of the audience which means the x-axis is vertical.

setTangent()

Parameters
setTangent(Rotation2d r)
setTangent(Double r)
// Sets the tangent to 90°
// This is used to specify the start tangent of the next movement command
.setTangent(Math.toRadians(90.0))

setReversed()

Parameters
setReversed(Boolean reversed)

This internally calls setTangent(Math.toRadians(180.0)).

// Run trajectory with robot facing opposite direction (backwards)
.setReversed(true)


Be Careful of Starting Heading

lineToX() and lineToY() do not allow strafing. Therefore, these functions should be avoided in favor of strafeTo(). See this section on the Common Issues page for more details.

Notice

The behavior of all of the below lineTo functions are the same when the heading does not change.

lineTo commands

lineToX(), lineToXConstantHeading(), lineToXLinearHeading(), lineToXSplineHeading()
lineToY(), lineToYConstantHeading(), lineToYLinearHeading(), lineToYSplineHeading()

lineToX()

Parameters
lineToX(Double posX, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToX(Double posX, VelConstraint velConstraintOverride)
lineToX(Double posX)
// Drive to an x-value of 25.0
.lineToX(25.0)

lineToXConstantHeading()

Parameters
lineToXConstantHeading(Double posX, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToXConstantHeading(Double posX, VelConstraint velConstraintOverride)
lineToXConstantHeading(Double posX)
// Drive to an x-value of 25.0, keeping the heading constant
.lineToXConstantHeading(25.0)

lineToXLinearHeading()

Parameters
lineToXLinearHeading(Double posX, Rotation2d heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToXLinearHeading(Double posX, Rotation2d heading, VelConstraint velConstraintOverride)
lineToXLinearHeading(Double posX, Rotation2d heading)
lineToXLinearHeading(Double posX, Double heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToXLinearHeading(Double posX, Double heading, VelConstraint velConstraintOverride)
lineToXLinearHeading(Double posX, Double heading)
// Drive to an x-value of 25.0, changing the heading linearly
.lineToXLinearHeading(25.0, Math.toRadians(90.0))

lineToXSplineHeading()

Parameters
lineToXSplineHeading(Double posX, Rotation2d heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToXSplineHeading(Double posX, Rotation2d heading, VelConstraint velConstraintOverride)
lineToXSplineHeading(Double posX, Rotation2d heading)
lineToXSplineHeading(Double posX, Double heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToXSplineHeading(Double posX, Double heading, VelConstraint velConstraintOverride)
lineToXSplineHeading(Double posX, Double heading)
// Drive to an y-value of 25.0, changing the heading according to a spline
.lineToXSplineHeading(25.0, Math.toRadians(90.0))

lineToY()

Parameters
lineToY(Double posY, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToY(Double posY, VelConstraint velConstraintOverride)
lineToY(Double posY)
// Drive to an y-value of 25.0
.lineToY(25.0)

lineToYConstantHeading()

Parameters
lineToYConstantHeading(Double posY, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToYConstantHeading(Double posY, VelConstraint velConstraintOverride)
lineToYConstantHeading(Double posY)
// Drive to an y-value of 25.0, keeping the heading constant
.lineToYConstantHeading(25.0)

lineToYLinearHeading()

Parameters
lineToYLinearHeading(Double posY, Rotation2d heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToYLinearHeading(Double posY, Rotation2d heading, VelConstraint velConstraintOverride)
lineToYLinearHeading(Double posY, Rotation2d heading)
lineToYLinearHeading(Double posY, Double heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToYLinearHeading(Double posY, Double heading, VelConstraint velConstraintOverride)
lineToYLinearHeading(Double posY, Double heading)
// Drive to an y-value of 25.0, linearly changing the heading
.lineToYLinearHeading(25.0, Math.toRadians(90.0))

lineToYSplineHeading()

Parameters
lineToYSplineHeading(Double posY, Rotation2d heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToYSplineHeading(Double posY, Rotation2d heading, VelConstraint velConstraintOverride)
lineToYSplineHeading(Double posY, Rotation2d heading)
lineToYSplineHeading(Double posY, Double heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
lineToYSplineHeading(Double posY, Double heading, VelConstraint velConstraintOverride)
lineToYSplineHeading(Double posY, Double heading)
// Drive to an y-value of 25.0, changing the heading according to a spline
.lineToYSplineHeading(25.0, Math.toRadians(90.0))

strafeTo commands

strafeTo(), strafeToConstantHeading(), strafeToLinearHeading(), strafeToSplineHeading()

strafeTo()

Parameters
strafeTo(Vector2d pos, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
strafeTo(Vector2d pos, VelConstraint velConstraintOverride)
strafeTo(Vector2d pos)
// Strafe to (24.0, 24.0), keeping the heading the same
.strafeToConstantHeading(new Vector2d(24.0, 24.0))

strafeToConstantHeading()

Parameters
strafeToConstantHeading(Vector2d pos, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
strafeToConstantHeading(Vector2d pos, VelConstraint velConstraintOverride)
strafeToConstantHeading(Vector2d pos)

idk what is difference between strafeToConstantHeading() and strafeTo()?

// Strafe to (24.0, 24.0), keeping the heading constant
.strafeToConstantHeading(new Vector2d(24.0, 24.0))

strafeToLinearHeading()

Parameters
strafeToLinearHeading(Vector2d pos, Rotation2d heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
strafeToLinearHeading(Vector2d pos, Rotation2d heading, VelConstraint velConstraintOverride)
strafeToLinearHeading(Vector2d pos, Rotation2d heading)
strafeToLinearHeading(Vector2d pos, Double heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
strafeToLinearHeading(Vector2d pos, Double heading, VelConstraint velConstraintOverride)
strafeToLinearHeading(Vector2d pos, Double heading)
// Strafe to (24.0, 24.0), changing the heading linearly
.strafeToLinearHeading(new Vector2d(24.0, 24.0), Math.toRadians(0.0))

strafeToSplineHeading()

Parameters
strafeToSplineHeading(Vector2d pos, Rotation2d heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
strafeToSplineHeading(Vector2d pos, Rotation2d heading, VelConstraint velConstraintOverride)
strafeToSplineHeading(Vector2d pos, Rotation2d heading)
strafeToSplineHeading(Vector2d pos, Double heading, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
strafeToSplineHeading(Vector2d pos, Double heading, VelConstraint velConstraintOverride)
strafeToSplineHeading(Vector2d pos, Double heading)
// Strafe to (24.0, 24.0), changing the heading according to a spline
.strafeToSplineHeading(new Vector2d(24.0, 24.0), Math.toRadians(0.0))

splineTo commands

splineTo(), splineToConstantHeading(), splineToLinearHeading(), splineToSplineHeading()

splineTo()

Parameters
splineTo(Vector2d pos, Rotation2d tangent, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
splineTo(Vector2d pos, Rotation2d tangent, VelConstraint velConstraintOverride)
splineTo(Vector2d pos, Rotation2d tangent)
splineTo(Vector2d pos, Double tangent, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
splineTo(Vector2d pos, Double tangent, VelConstraint velConstraintOverride)
splineTo(Vector2d pos, Double tangent)
// Spline to (24, 24) with an ending tangent of 0.0, changing the heading with the spline
.splineTo(new Vector2d(24.0, 24.0), Math.toRadians(0.0))

splineToConstantHeading()

Parameters
splineToConstantHeading(Vector2d pos, Rotation2d tangent, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
splineToConstantHeading(Vector2d pos, Rotation2d tangent, VelConstraint velConstraintOverride)
splineToConstantHeading(Vector2d pos, Rotation2d tangent)
splineToConstantHeading(Vector2d pos, Double tangent, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
splineToConstantHeading(Vector2d pos, Double tangent, VelConstraint velConstraintOverride)
splineToConstantHeading(Vector2d pos, Double tangent)
// Spline to (24, 24) with an ending tangent of 0.0, keeping the heading constant
.splineToConstantHeading(new Vector2d(24.0, 24.0), Math.toRadians(0.0))

splineToLinearHeading()

Parameters
splineToLinearHeading(Pose2d pose, Rotation2d tangent, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
splineToLinearHeading(Pose2d pose, Rotation2d tangent, VelConstraint velConstraintOverride)
splineToLinearHeading(Pose2d pose, Rotation2d tangent)
splineToLinearHeading(Pose2d pose, Double tangent, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
splineToLinearHeading(Pose2d pose, Double tangent, VelConstraint velConstraintOverride)
splineToLinearHeading(Pose2d pose, Double tangent)
// Spline to (24, 24) with an ending tangent of 0.0, linearly changing the heading from the previous heading to 90.0 degrees
.splineToLinearHeading(new Pose2d(24.0, 24.0, Math.toRadians(90.0)), Math.toRadians(0.0))

splineToSplineHeading()

Parameters
splineToSplineHeading(Pose2d pose, Rotation2d tangent, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
splineToSplineHeading(Pose2d pose, Rotation2d tangent, VelConstraint velConstraintOverride)
splineToSplineHeading(Pose2d pose, Rotation2d tangent)
splineToSplineHeading(Pose2d pose, Double tangent, VelConstraint velConstraintOverride, AccelConstraint accelConstraintOverride)
splineToSplineHeading(Pose2d pose, Double tangent, VelConstraint velConstraintOverride)
splineToSplineHeading(Pose2d pose, Double tangent)
// Spline to (24, 24) with an ending tangent of 0.0, changing the heading from the previous heading to 90.0 degrees according to a spline
.splineToSplineHeading(new Pose2d(24.0, 24.0, Math.toRadians(90.0)), Math.toRadians(0.0))

build()

Used to assemble a trajectory into an action. This action can then be executed to run the trajectory.

// Specify a starting pose
Pose2d beginPose = new Pose2d(-16.0, -55.0, Math.toRadians(90.0));

// Create an instance of the Mecanum Drive class
MecanumDrive drive = new MecanumDrive(hardwareMap, beginPose);

// Create a Trajectory
TrajectoryActionBuilder traj = drive.actionBuilder(drive.pose)
// Put your functions here
.strafeTo(new Vector2d(30.0, 10.0))
.splineTo(new Vector2d(-30.0, -10.0));

// Create an action that follows the created trajectory
Action trajAction = traj.build()

// Run the action
Actions.runBlocking(trajAction);