core / com.acmerobotics.roadrunner.trajectory / BaseTrajectoryBuilder

BaseTrajectoryBuilder

abstract class BaseTrajectoryBuilder<T : BaseTrajectoryBuilder<T>> (source)

Easy-to-use builder for creating Trajectory instances.

Parameters

startPose - start pose

trajectory - initial trajectory (for splicing)

t - time index in previous trajectory to begin new trajectory

Constructors

<init>

Easy-to-use builder for creating Trajectory instances.

BaseTrajectoryBuilder(startPose: Pose2d?, startTangent: Double?, trajectory: Trajectory?, t: Double?)

Properties

pathBuilder

var pathBuilder: PathBuilder

Functions

addDisplacementMarker

Adds a marker at the current position of the trajectory.

fun addDisplacementMarker(callback: MarkerCallback): T

Adds a marker to the trajectory at displacement.

fun addDisplacementMarker(displacement: Double, callback: MarkerCallback): T

Adds a marker to the trajectory at scale * path length + offset.

fun addDisplacementMarker(scale: Double, offset: Double, callback: MarkerCallback): T

Adds a marker to the trajectory at displacement evaluated with path length.

fun addDisplacementMarker(displacement: (Double) -> Double, callback: MarkerCallback): T

addSpatialMarker

Adds a marker that will be triggered at the closest trajectory point to point.

fun addSpatialMarker(point: Vector2d, callback: MarkerCallback): T

addTemporalMarker

Adds a marker to the trajectory at time.

fun addTemporalMarker(time: Double, callback: MarkerCallback): T

Adds a marker to the trajectory at scale * trajectory duration + offset.

fun addTemporalMarker(scale: Double, offset: Double, callback: MarkerCallback): T

Adds a marker to the trajectory at time evaluated with the trajectory duration.

fun addTemporalMarker(time: (Double) -> Double, callback: MarkerCallback): T

back

Adds a line straight backward.

fun back(distance: Double): T

build

Constructs the Trajectory instance.

fun build(): Trajectory

buildTrajectory

Build a trajectory from path.

abstract fun buildTrajectory(path: Path, temporalMarkers: List<TemporalMarker>, displacementMarkers: List<DisplacementMarker>, spatialMarkers: List<SpatialMarker>): Trajectory

forward

Adds a line straight forward.

fun forward(distance: Double): T

lineTo

Adds a line segment with tangent heading interpolation.

fun lineTo(endPosition: Vector2d): T

lineToConstantHeading

Adds a line segment with constant heading interpolation.

fun lineToConstantHeading(endPosition: Vector2d): T

lineToLinearHeading

Adds a line segment with linear heading interpolation.

fun lineToLinearHeading(endPose: Pose2d): T

lineToSplineHeading

Adds a line segment with spline heading interpolation.

fun lineToSplineHeading(endPose: Pose2d): T

splineTo

Adds a spline segment with tangent heading interpolation.

fun splineTo(endPosition: Vector2d, endTangent: Double): T

splineToConstantHeading

Adds a spline segment with constant heading interpolation.

fun splineToConstantHeading(endPosition: Vector2d, endTangent: Double): T

splineToLinearHeading

Adds a spline segment with linear heading interpolation.

fun splineToLinearHeading(endPose: Pose2d, endTangent: Double): T

splineToSplineHeading

Adds a spline segment with spline heading interpolation.

fun splineToSplineHeading(endPose: Pose2d, endTangent: Double): T

strafeLeft

Adds a segment that strafes left in the robot reference frame.

fun strafeLeft(distance: Double): T

strafeRight

Adds a segment that strafes right in the robot reference frame.

fun strafeRight(distance: Double): T

strafeTo

Adds a strafe path segment.

fun strafeTo(endPosition: Vector2d): T

Inheritors

SimpleTrajectoryBuilder

Builder for trajectories with static constraints.

class SimpleTrajectoryBuilder : BaseTrajectoryBuilder<SimpleTrajectoryBuilder>

TrajectoryBuilder

Builder for trajectories with dynamic constraints.

class TrajectoryBuilder : BaseTrajectoryBuilder<TrajectoryBuilder>