TrajectoryBuilder

open class TrajectoryBuilder(startPose: Pose2d, startDeriv: Pose2d, startSecondDeriv: Pose2d, val baseVelConstraint: TrajectoryVelocityConstraint, val baseAccelConstraint: TrajectoryAccelerationConstraint, val baseAngVel: Angle, val baseAngAccel: Angle, val baseAngJerk: Angle, start: MotionState, resolution: Double) : BaseTrajectoryBuilder<TrajectoryBuilder>

Builder for trajectories with dynamic constraints.

Constructors

Link copied to clipboard
constructor(startPose: Pose2d = Pose2d(), startTangent: Angle = startPose.heading, baseVelConstraint: TrajectoryVelocityConstraint, baseAccelConstraint: TrajectoryAccelerationConstraint, baseAngVel: Angle, baseAngAccel: Angle, baseAngJerk: Angle = 0.rad, resolution: Double = 0.25)

Creates a builder from a start pose and tangent. This is the recommended constructor for creating trajectories from rest.

constructor(startPose: Pose2d = Pose2d(), startTangent: Angle = startPose.heading, constraints: TrajectoryConstraints, resolution: Double = 0.25)

Creates a builder from a start pose and tangent. This is the recommended constructor for creating trajectories from rest.

constructor(startPose: Pose2d, reversed: Boolean, baseVelConstraint: TrajectoryVelocityConstraint, baseAccelConstraint: TrajectoryAccelerationConstraint, baseAngVel: Angle, baseAngAccel: Angle, baseAngJerk: Angle = 0.rad, resolution: Double = 0.25)

Create a builder from a start pose with a reversed tangent. This constructor is used to execute trajectories backwards.

constructor(startPose: Pose2d, reversed: Boolean, constraints: TrajectoryConstraints, resolution: Double = 0.25)

Create a builder from a start pose with a reversed tangent. This constructor is used to execute trajectories backwards.

constructor(trajectory: Trajectory, t: Double, baseVelConstraint: TrajectoryVelocityConstraint, baseAccelConstraint: TrajectoryAccelerationConstraint, baseAngVel: Angle, baseAngAccel: Angle, baseAngJerk: Angle = 0.rad, resolution: Double = 0.25)

Create a builder from an active trajectory. This is useful for interrupting a live trajectory and smoothly transitioning to a new one.

constructor(trajectory: Trajectory, t: Double, constraints: TrajectoryConstraints, resolution: Double = 0.25)

Create a builder from an active trajectory. This is useful for interrupting a live trajectory and smoothly transitioning to a new one.

protected constructor(startPose: Pose2d, startDeriv: Pose2d, startSecondDeriv: Pose2d, baseVelConstraint: TrajectoryVelocityConstraint, baseAccelConstraint: TrajectoryAccelerationConstraint, baseAngVel: Angle, baseAngAccel: Angle, baseAngJerk: Angle, start: MotionState, resolution: Double)

Properties

Link copied to clipboard
Link copied to clipboard
Link copied to clipboard

Functions

Link copied to clipboard

Adds the provided acceleration constraints for the following path segments.

Link copied to clipboard
fun addAngularConstraints(angVel: Angle, angAccel: Angle = Double.POSITIVE_INFINITY.rad, angJerk: Angle = Double.POSITIVE_INFINITY.rad): TrajectoryBuilder

Adds the provided angular constraints for the following turn segments.

Link copied to clipboard

Adds the provided constraints to the following path and turn segments.

Adds the provided constraints for the following path segments.

Link copied to clipboard
fun addLine(endPosition: Vector2d, headingInterpolation: HeadingInterpolation = TangentHeading, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a line segment with the specified heading interpolation.

Link copied to clipboard
fun addSpline(endPosition: Vector2d, endTangent: Angle, startTangentMag: Double = -1.0, endTangentMag: Double = -1.0, headingInterpolation: HeadingInterpolation = TangentHeading, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a spline segment with the specified heading interpolation.

Link copied to clipboard

Adds the provided velocity constraints for the following path segments.

Link copied to clipboard
fun back(distance: Double, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a line straight backward.

Link copied to clipboard
fun forward(distance: Double, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a line straight forward.

Link copied to clipboard
fun lineTo(endPosition: Vector2d, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a line segment with tangent heading interpolation.

Link copied to clipboard
fun lineToConstantHeading(endPosition: Vector2d, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a line segment with constant heading interpolation.

Link copied to clipboard
fun lineToLinearHeading(endPose: Pose2d, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a line segment with linear heading interpolation.

Link copied to clipboard
fun lineToSplineHeading(endPose: Pose2d, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a line segment with spline heading interpolation.

Link copied to clipboard
protected open override fun makePathSegment(path: Path): PathTrajectorySegment
Link copied to clipboard
protected open override fun makeTurnSegment(pose: Pose2d, angle: Angle): TurnSegment
Link copied to clipboard

Resets all constraints to the default constructor-provided values.

Link copied to clipboard

Resets the angular constraints to the default constructor-provided values.

Link copied to clipboard

Resets the path constraints to the default constructor-provided values.

Link copied to clipboard

Sets the acceleration constraints for the following path segments.

Link copied to clipboard
fun setAngularConstraints(angVelOverride: Angle, angAccelOverride: Angle = baseAngAccel, angJerkOverride: Angle = baseAngJerk): TrajectoryBuilder

Sets the angular constraints for the following turn segments.

Link copied to clipboard

Sets the constraints for the following segments using the provided constraints. Sets both the path and angular constraints.

Sets the constraints for the following path segments.

Link copied to clipboard

Sets the velocity constraints for the following path segments.

Link copied to clipboard
fun splineTo(endPosition: Vector2d, endTangent: Angle, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a spline segment with tangent heading interpolation.

Link copied to clipboard
fun splineToConstantHeading(endPosition: Vector2d, endTangent: Angle, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a spline segment with constant heading interpolation.

Link copied to clipboard
fun splineToLinearHeading(endPose: Pose2d, endTangent: Angle, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a spline segment with linear heading interpolation.

Link copied to clipboard
fun splineToSplineHeading(endPose: Pose2d, endTangent: Angle, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a spline segment with spline heading interpolation.

Link copied to clipboard
fun strafeLeft(distance: Double, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

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

Link copied to clipboard
fun strafeRight(distance: Double, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

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

Link copied to clipboard
fun strafeTo(endPosition: Vector2d, velConstraintOverride: TrajectoryVelocityConstraint, accelConstraintOverride: TrajectoryAccelerationConstraint = baseAccelConstraint): TrajectoryBuilder

Adds a strafe path segment.

Link copied to clipboard
fun turn(angle: Angle, angVelOverride: Angle, angAccelOverride: Angle = baseAngAccel, angJerkOverride: Angle = baseAngJerk): TrajectoryBuilder

Adds a turn segment that turns angle degrees.