TrajectoryBuilder

Constructors

Link copied to clipboard
constructor(params: TrajectoryBuilderParams, beginPose: Pose2d, beginEndVel: Double, baseVelConstraint: VelConstraint, baseAccelConstraint: AccelConstraint, poseMap: PoseMap = IdentityPoseMap)

Functions

Link copied to clipboard

Builds the specified trajectories, creating a new CancelableTrajectory object for each discontinuity. Equivalent to buildToList.

Link copied to clipboard

Builds the trajectory, creating a new CancelableTrajectory object for each discontinuity, and then composes them into a single CompositeTrajectory object. There may be complete stops in this composite based on where its components start and end.

Link copied to clipboard

Builds the specified trajectories, creating a new CancelableTrajectory object for each discontinuity.

Link copied to clipboard
fun forward(ds: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes forward ds.

Link copied to clipboard
fun forwardConstantHeading(ds: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes forward ds while maintaining current heading. Equivalent to forward.

Link copied to clipboard
fun forwardLinearHeading(ds: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun forwardLinearHeading(ds: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes forward ds, changing heading from current to heading using linear interpolation.

Link copied to clipboard
fun forwardSplineHeading(ds: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun forwardSplineHeading(ds: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes forward ds, changing heading from current to heading using spline interpolation.

Link copied to clipboard
fun lineToX(posX: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to \(x\)-coordinate posX. The robot will continue traveling in the direction it is currently in; if the robot is perpendicular to the x-axis, this throws an error.

Link copied to clipboard
fun lineToXConstantHeading(posX: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to \(x\)-coordinate posX. The robot will continue traveling in the direction it is currently in; if the robot is perpendicular to the x-axis, this throws an error. Equivalent to lineToX.

Link copied to clipboard
fun lineToXLinearHeading(posX: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun lineToXLinearHeading(posX: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to \(x\)-coordinate posX, while changing heading from current to heading using linear interpolation. The robot will continue traveling in the direction it is currently in; if the robot is perpendicular to the x-axis, this throws an error.

Link copied to clipboard
fun lineToXSplineHeading(posX: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun lineToXSplineHeading(posX: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to \(x\)-coordinate posX, while changing heading from current to heading using spline interpolation. The robot will continue traveling in the direction it is currently in; if the robot is perpendicular to the x-axis, this throws an error.

Link copied to clipboard
fun lineToY(posY: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to \(y\)-coordinate posY. The robot will continue traveling in the direction it is currently in; if the robot is perpendicular to the y-axis, this throws an error.

Link copied to clipboard
fun lineToYConstantHeading(posY: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to \(y\)-coordinate posY.

Link copied to clipboard
fun lineToYLinearHeading(posY: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun lineToYLinearHeading(posY: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to \(y\)-coordinate posY, while changing heading from current to heading using linear interpolation. The robot will continue traveling in the direction it is currently in; if the robot is perpendicular to the y-axis, this throws an error.

Link copied to clipboard
fun lineToYSplineHeading(posY: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun lineToYSplineHeading(posY: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to \(y\)-coordinate posY, while changing heading from current to heading using spline interpolation. The robot will continue traveling in the direction it is currently in; if the robot is perpendicular to the y-axis, this throws an error.

Link copied to clipboard

Reverses the next path segment; actually a call to setTangent(Math.PI)!

Link copied to clipboard

Sets the starting tangent of the next path segment. See RoadRunner docs.

Link copied to clipboard
fun splineTo(pos: Vector2d, tangent: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun splineTo(pos: Vector2d, tangent: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a curved path segment using quintic Hermite splines that goes to pos with an end tangent of tangent. The shape of the curve is based off of the starting position and tangent as well as the ending pos and tangent.

Link copied to clipboard
fun splineToConstantHeading(pos: Vector2d, tangent: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun splineToConstantHeading(pos: Vector2d, tangent: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a curved path segment using quintic Hermite splines that goes to pos with an end tangent of tangent. The shape of the curve is based off of the starting position and tangent as well as the ending pos and tangent. The robot's heading remains constant as opposed to matching the tangent.

Link copied to clipboard
fun splineToLinearHeading(pose: Pose2d, tangent: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun splineToLinearHeading(pose: Pose2d, tangent: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a curved path segment using quintic Hermite splines that goes to pose.position with an end tangent of tangent. The shape of the curve is based off of the starting position and tangent as well as the ending position and tangent. The robot's heading linearly interpolates from its current heading to pose.heading.

Link copied to clipboard
fun splineToSplineHeading(pose: Pose2d, tangent: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun splineToSplineHeading(pose: Pose2d, tangent: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a curved path segment using quintic Hermite splines that goes to pose.position with an end tangent of tangent. The shape of the curve is based off of the starting position and tangent as well as the ending position and tangent. The robot's heading interpolates from its current heading to pose.heading using spline interpolation.

Link copied to clipboard
fun strafeTo(pos: Vector2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to pos.

Link copied to clipboard
fun strafeToConstantHeading(pos: Vector2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to pos. Equivalent to strafeTo.

Link copied to clipboard
fun strafeToLinearHeading(pos: Vector2d, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun strafeToLinearHeading(pos: Vector2d, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to pos, changing heading from current to heading using linear interpolation.

Link copied to clipboard
fun strafeToSplineHeading(pos: Vector2d, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder
fun strafeToSplineHeading(pos: Vector2d, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryBuilder

Adds a line segment that goes to pos, changing heading from current to heading using spline interpolation.