Road Runner Trajectory Task Builder
Builder class for a trajectory and task sequence. This is a more advanced builder for creating a sequence of trajectories and tasks, allowing task queues and adding trajectory sequences standalone.
Constructors
Link copied to clipboard
constructor(drive: RoadRunnerDrive, startPose: Pose2d, startTangent: Double, baseVelConstraint: TrajectoryVelocityConstraint, baseAccelConstraint: TrajectoryAccelerationConstraint, baseTurnConstraintMaxAngVel: Double, baseTurnConstraintMaxAngAccel: Double, mirrorPoseRef: Boolean)
Create a new builder for a RoadRunner trajectory task.
constructor(drive: RoadRunnerDrive, startPose: Pose2d, baseVelConstraint: TrajectoryVelocityConstraint, baseAccelConstraint: TrajectoryAccelerationConstraint, baseTurnConstraintMaxAngVel: Double, baseTurnConstraintMaxAngAccel: Double, mirrorPoseRef: Boolean)
Create a new builder for a RoadRunner trajectory task.
Inherited properties
Functions
Link copied to clipboard
open fun addDisplacementMarker(displacementInches: DisplacementProducer, callback: MarkerCallback): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Add a displacement marker at a given displacement to run a callback at that displacement.
Link copied to clipboard
open fun addSpatialMarker(pointInches: Vector2d, callback: MarkerCallback): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Add a spatial marker at the current position to run a callback at that position.
Link copied to clipboard
Build the trajectory sequence and task, and add it automatically to the AutonomousBunyipsOpMode task queue.
Link copied to clipboard
open fun addTemporalMarker(time: TimeProducer, callback: MarkerCallback): RoadRunner.RoadRunnerTrajectoryTaskBuilder
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
open fun back(inches: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Move backward a given distance with custom velocity and acceleration constraints.
Link copied to clipboard
Build the trajectory sequence (and mirrored sequence) without creating a task.
Link copied to clipboard
Build the trajectory sequence and task for use by the user.
Link copied to clipboard
open fun forward(inches: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Move forward a given distance with custom velocity and acceleration constraints.
Link copied to clipboard
open fun lineTo(endPositionInches: Vector2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Move in a straight line to a given position with custom velocity and acceleration constraints.
Link copied to clipboard
open fun lineToConstantHeading(endPositionInches: Vector2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Move in a straight line to a given position with a constant heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun lineToLinearHeading(endPoseInchRad: Pose2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Move in a straight line to a given position with a linear heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun lineToSplineHeading(endPoseInchRad: Pose2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Move in a straight line to a given position with a spline heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun mirrorToRef(out: Reference<TrajectorySequence>): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Mirror a TrajectorySequence into the given Reference, which will effectively "flip" over the y-axis from the center of the field.
Link copied to clipboard
Reset the acceleration constraint to the base acceleration constraint.
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
open fun runSequence(sequence: TrajectorySequence, setDrivePoseToStart: Boolean): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Run a sequence of trajectories, useful if you do not need to build a trajectory but run one directly.
Link copied to clipboard
open fun setAccelConstraint(accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Set the acceleration constraint for the next builder instructions.
Link copied to clipboard
open fun setConstraints(velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Set the velocity and acceleration constraints for the next builder instructions.
Link copied to clipboard
Toggle mirrorToRef mirroring for the following builder instructions.
Link copied to clipboard
Reverse or unreverse the tangent of the next path.
Link copied to clipboard
Set the scale to multiply route distances by for the following builder instructions.
Link copied to clipboard
Set the tangent of the next path.
Link copied to clipboard
open fun setTurnConstraint(maxAngVel: Double, maxAngAccel: Double): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Set the turn constraints for the next builder instructions.
Link copied to clipboard
open fun setVelConstraint(velConstraint: TrajectoryVelocityConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Set the velocity constraint for the next builder instructions.
Link copied to clipboard
open fun splineTo(endPositionInches: Vector2d, endHeadingRad: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Spline to a given position with a given heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun splineToConstantHeading(endPositionInches: Vector2d, endHeadingRad: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Spline to a given position with a constant heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun splineToLinearHeading(endPoseInchRad: Pose2d, endHeadingRad: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Spline to a given position with a linear heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun splineToSplineHeading(endPoseInchRad: Pose2d, endHeadingRad: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Spline to a given position with a spline heading and custom velocity and acceleration constraints.
Link copied to clipboard
open fun strafeLeft(inches: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Strafe left a given distance with custom velocity and acceleration constraints.
Link copied to clipboard
open fun strafeRight(inches: Double, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Strafe right a given distance with custom velocity and acceleration constraints.
Link copied to clipboard
open fun strafeTo(endPositionInches: Vector2d, velConstraint: TrajectoryVelocityConstraint, accelConstraint: TrajectoryAccelerationConstraint): RoadRunner.RoadRunnerTrajectoryTaskBuilder
Move in a strafe straight line to a given position with custom velocity and acceleration constraints.
Link copied to clipboard
Wait for a given number of seconds.
Link copied to clipboard
Set the task name of the trajectory to show up in the telemetry.
Link copied to clipboard
Set the priority level of the task.
Link copied to clipboard
Set a timeout for the trajectory, to be applied to the overhead task running the trajectory.
Inherited functions
Link copied to clipboard
Add a displacement marker at the current displacement to run a callback at that displacement.
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
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
Link copied to clipboard
Move in a straight line to a given position with a constant heading.
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(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(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 angular acceleration to the base angular acceleration.
Link copied to clipboard
Reset the angular velocity to the base angular velocity.
Link copied to clipboard
Set the maximum angular acceleration for the next builder instructions.
Link copied to clipboard
Set the tangent of the next path.
Link copied to clipboard
Link copied to clipboard
Spline to a given position with a given heading.
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(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(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(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(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(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(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.