Trajectory Sequence Builder
RoadRunner trajectory sequence builder. See RoadRunner.
Since
1.0.0-pre
Parameters
<T>
The type of the subclass (used for derived builder patterns to return this)
Inheritors
Constructors
Link copied to clipboard
constructor(startPose: Pose2d, startTangent: Double, baseVelConstraint: TrajectoryVelocityConstraint, baseAccelConstraint: TrajectoryAccelerationConstraint, baseTurnConstraintMaxAngVel: Double, baseTurnConstraintMaxAngAccel: Double)
Create a new TrajectorySequenceBuilder
constructor(startPose: Pose2d, baseVelConstraint: TrajectoryVelocityConstraint, baseAccelConstraint: TrajectoryAccelerationConstraint, baseTurnConstraintMaxAngVel: Double, baseTurnConstraintMaxAngAccel: Double)
Create a new TrajectorySequenceBuilder
Properties
Functions
Link copied to clipboard
Add a displacement marker at the current displacement to run a callback at that displacement.
open fun addDisplacementMarker(displacementInches: DisplacementProducer, callback: MarkerCallback): T
open fun addDisplacementMarker(displacement: DisplacementProducer, inUnit: Distance, callback: MarkerCallback): T
open fun addDisplacementMarker(scale: Double, offset: Double, inUnit: Distance, callback: MarkerCallback): T
Add a displacement marker at a given displacement to run a callback at that displacement.
Link copied to clipboard
Add a spatial marker at the current position to run a callback at that position.
Link copied to clipboard
Add a temporal marker at the current duration to run a callback at that time.
Add a temporal marker at a given time to run a callback at that time.
Link copied to clipboard
Add a trajectory to the sequence.
Link copied to clipboard
Move backward a given distance.
open fun back(inches: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun back(distance: Double, inUnit: Distance, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Move backward a given distance with custom velocity and acceleration constraints.
Link copied to clipboard
Create a TrajectorySequence from the current builder state.
Link copied to clipboard
open fun constraintIn(inUnit: Velocity<Distance>, constraint: TrajectoryVelocityConstraint): TrajectoryVelocityConstraint
open fun constraintIn(inUnit: Velocity<Velocity<Distance>>, constraint: TrajectoryAccelerationConstraint): TrajectoryAccelerationConstraint
Convert a constraint to a new unit.
Link copied to clipboard
Move forward a given distance.
open fun forward(inches: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun forward(distance: Double, inUnit: Distance, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Move forward a given distance with custom velocity and acceleration constraints.
Link copied to clipboard
Move in a straight line to a given position.
open fun lineTo(endPositionInches: Vector2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun lineTo(endPositionInches: Vector2d, inUnit: Distance, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Move in a straight line to a given position with custom velocity and acceleration constraints.
Link copied to clipboard
Move in a straight line to a given position with a constant heading.
open fun lineToConstantHeading(endPositionInches: Vector2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun lineToConstantHeading(endPosition: Vector2d, inUnit: Distance, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Move in a straight line to a given position with a constant heading and custom velocity and acceleration constraints.
Link copied to clipboard
Move in a straight line to a given position with a linear heading.
open fun lineToLinearHeading(endPoseInchRad: Pose2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun lineToLinearHeading(endPose: Pose2d, distanceUnit: Distance, angleUnit: Angle, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Move in a straight line to a given position with a linear heading and custom velocity and acceleration constraints.
Link copied to clipboard
Move in a straight line to a given position with a spline heading.
open fun lineToSplineHeading(endPoseInchRad: Pose2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun lineToSplineHeading(endPose: Pose2d, distanceUnit: Distance, angleUnit: Angle, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Move in a straight line to a given position with a spline heading and custom velocity and acceleration constraints.
Link copied to clipboard
Reset the acceleration constraint to the base acceleration constraint.
Link copied to clipboard
Reset the angular acceleration to the base angular acceleration.
Link copied to clipboard
Reset the angular velocity to the base angular velocity.
Link copied to clipboard
Reset the velocity and acceleration constraints to the base constraints.
Link copied to clipboard
Reset the turn constraints to the base turn constraints.
Link copied to clipboard
Reset the velocity constraint to the base velocity constraint.
Link copied to clipboard
Set the acceleration constraint for the next builder instructions.
Link copied to clipboard
Set the maximum angular acceleration for the next builder instructions.
Link copied to clipboard
open fun setConstraints(velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Set the velocity and acceleration constraints for the next builder instructions.
Link copied to clipboard
Reverse or unreverse the tangent of the next path.
Link copied to clipboard
Set the tangent of the next path.
Link copied to clipboard
Link copied to clipboard
Set the velocity constraint for the next builder instructions.
Link copied to clipboard
Spline to a given position with a given heading.
open fun splineTo(endPositionInches: Vector2d, endHeadingRad: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun splineTo(endPosition: Vector2d, inUnit: Distance, endHeading: Double, angleUnit: Angle, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Spline to a given position with a given heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun splineToConstantHeading(endPosition: Vector2d, inUnit: Distance, endHeading: Double, angleUnit: Angle): T
Spline to a given position with a constant heading.
open fun splineToConstantHeading(endPositionInches: Vector2d, endHeadingRad: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun splineToConstantHeading(endPosition: Vector2d, inUnit: Distance, endHeading: Double, angleUnit: Angle, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Spline to a given position with a constant heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun splineToLinearHeading(endPose: Pose2d, distanceUnit: Distance, angleUnit: Angle, endHeading: Double, endAngleUnit: Angle): T
Spline to a given position with a linear heading.
open fun splineToLinearHeading(endPoseInchRad: Pose2d, endHeadingRad: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun splineToLinearHeading(endPose: Pose2d, distanceUnit: Distance, angleUnit: Angle, endHeading: Double, endAngleUnit: Angle, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Spline to a given position with a linear heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun splineToSplineHeading(endPose: Pose2d, distanceUnit: Distance, angleUnit: Angle, endHeading: Double, endAngleUnit: Angle): T
Spline to a given position with a spline heading.
open fun splineToSplineHeading(endPoseInchRad: Pose2d, endHeadingRad: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun splineToSplineHeading(endPose: Pose2d, distanceUnit: Distance, angleUnit: Angle, endHeading: Double, endAngleUnit: Angle, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Spline to a given position with a spline heading and custom velocity and acceleration constraints.
Link copied to clipboard
Strafe left a given distance.
open fun strafeLeft(inches: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun strafeLeft(distance: Double, inUnit: Distance, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Strafe left a given distance with custom velocity and acceleration constraints.
Link copied to clipboard
Strafe right a given distance.
open fun strafeRight(inches: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun strafeRight(distance: Double, inUnit: Distance, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Strafe right a given distance with custom velocity and acceleration constraints.
Link copied to clipboard
Move in a strafe straight line to a given position.
open fun strafeTo(endPositionInches: Vector2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
open fun strafeTo(endPosition: Vector2d, inUnit: Distance, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): T
Move in a strafe straight line to a given position with custom velocity and acceleration constraints.
Link copied to clipboard
open fun UNSTABLE_addDisplacementMarkerOffset(offset: Double, inUnit: Distance, callback: MarkerCallback): T
Add a displacement marker at the current displacement plus an offset to run a callback at that displacement.
Link copied to clipboard
Add a temporal marker at the current duration plus an offset to run a callback at that time.
Link copied to clipboard
Wait for a given number of seconds.