TaskBuilder

class TaskBuilder @JvmOverloads constructor(constants: Constants, startPose: Pose2d, poseMap: PoseMap, caller: RoadRunnerDrive? = null)

Extension of a RoadRunner trajectory builder to provide WPIUnits and task building support.

Author

Lucas Bubner, 2024

Since

6.0.0

Constructors

Link copied to clipboard
constructor(constants: Constants, startPose: Pose2d, poseMap: PoseMap, caller: RoadRunnerDrive? = null)

Functions

Link copied to clipboard
fun addTask()

Build the current trajectory and add it to the current AutonomousBunyipsOpMode task queue with the settings defined in this builder.

Link copied to clipboard
fun afterDisp(ds: Double, unit: Distance = Inches, a: Action): TaskBuilder

Schedules action a to execute in parallel starting at a displacement ds after the last trajectory segment. The action start is clamped to the span of the current trajectory.

fun afterDisp(ds: Double, unit: Distance = Inches, f: InstantFunction): TaskBuilder

Schedules function f to execute in parallel starting at a displacement ds after the last trajectory segment. The action start is clamped to the span of the current trajectory.

Link copied to clipboard
fun afterTime(dt: Double, unit: Time = Seconds, a: Action): TaskBuilder

Schedules action a to execute in parallel starting dt seconds after the last trajectory segment, turn, or other action.

fun afterTime(dt: Double, unit: Time = Seconds, f: InstantFunction): TaskBuilder

Schedules function f to execute in parallel starting dt seconds after the last trajectory segment, turn, or other action.

Link copied to clipboard

Build the current trajectory and return it as a Task/Action.

Link copied to clipboard

Ends the current trajectory in progress. No-op if no trajectory segments are pending.

Link copied to clipboard

Creates a new builder with the same settings and default constraints at the current pose, tangent.

Link copied to clipboard
fun lineToX(posX: Double, unit: Distance = Inches): TaskBuilder

Move to the specified posX coordinate in the direction of the current heading.

Link copied to clipboard

Move to the specified posX coordinate in the direction of the current heading.

Link copied to clipboard
fun lineToXLinearHeading(posX: Double, posUnit: Distance = Inches, heading: Rotation2d): TaskBuilder
fun lineToXLinearHeading(posX: Double, posUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians): TaskBuilder

Move to the specified posX coordinate in the direction of the current heading while linearly interpolating the heading to heading.

Link copied to clipboard
fun lineToXSplineHeading(posX: Double, posUnit: Distance = Inches, heading: Rotation2d): TaskBuilder
fun lineToXSplineHeading(posX: Double, posUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians): TaskBuilder

Move to the specified posX coordinate in the direction of the current heading while spline interpolating the heading to heading.

Link copied to clipboard
fun lineToY(posY: Double, unit: Distance = Inches): TaskBuilder

Move to the specified posY coordinate in the direction of the current heading.

Link copied to clipboard

Move to the specified posY coordinate in the direction of the current heading.

Link copied to clipboard
fun lineToYLinearHeading(posY: Double, posUnit: Distance = Inches, heading: Rotation2d): TaskBuilder
fun lineToYLinearHeading(posY: Double, posUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians): TaskBuilder

Move to the specified posY coordinate in the direction of the current heading while linearly interpolating the heading to heading.

Link copied to clipboard
fun lineToYSplineHeading(posY: Double, posUnit: Distance = Inches, heading: Rotation2d): TaskBuilder
fun lineToYSplineHeading(posY: Double, posUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians): TaskBuilder

Move to the specified posY coordinate in the direction of the current heading while spline interpolating the heading to heading.

Link copied to clipboard

Reset the acceleration constraints to default.

Link copied to clipboard

Reset the turn constraints to default.

Link copied to clipboard

Reset the velocity constraints to default.

Link copied to clipboard

Set the acceleration constraints as defined by an Accel object.

fun setAccelConstraints(accelConstraints: AccelConstraint): TaskBuilder

Set the acceleration constraints for future builder instructions in units of inches.

Link copied to clipboard

Set the reversed tangent state of the builder.

Link copied to clipboard
fun setTangent(r: Rotation2d): TaskBuilder
fun setTangent(r: Double, unit: Angle = Radians): TaskBuilder

Sets the tangent of the builder.

Link copied to clipboard

Set the turn constraints as defined by a Turn object.

fun setTurnConstraints(constraintsInches: TurnConstraints): TaskBuilder

Set the turn constraints for future builder instructions in units of inches.

Link copied to clipboard
fun setVelConstraints(constraints: Vel): TaskBuilder

Set the velocity constraints as defined by a Vel object.

fun setVelConstraints(velConstraintsInches: VelConstraint): TaskBuilder

Set the velocity constraints for future builder instructions in units of inches.

Link copied to clipboard
fun splineTo(pos: Vector2d, unit: Distance = Inches, tangent: Rotation2d): TaskBuilder
fun splineTo(pos: Vector2d, unit: Distance = Inches, tangent: Double, tangentUnit: Angle = Radians): TaskBuilder

Move to the specified pos in a spline path while following the specified tangent.

Link copied to clipboard
fun splineToConstantHeading(pos: Vector2d, unit: Distance = Inches, tangent: Rotation2d): TaskBuilder
fun splineToConstantHeading(pos: Vector2d, unit: Distance = Inches, tangent: Double, tangentUnit: Angle = Radians): TaskBuilder

Move to the specified pos in a spline path while maintaining the current heading.

Link copied to clipboard
fun splineToLinearHeading(poseHeadingRad: Pose2d, vectorUnit: Distance = Inches, tangent: Rotation2d): TaskBuilder
fun splineToLinearHeading(poseHeadingRad: Pose2d, vectorUnit: Distance = Inches, tangent: Double, tangentUnit: Angle = Radians): TaskBuilder

Move to the specified poseHeadingRad in a spline path while linearly interpolating the heading to tangent.

fun splineToLinearHeading(vector: Vector2d, vectorUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians, tangent: Rotation2d): TaskBuilder
fun splineToLinearHeading(vector: Vector2d, vectorUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians, tangent: Double, tangentUnit: Angle = Radians): TaskBuilder

Move to the specified vector tangent to heading in a spline path while linearly interpolating the robot heading to tangent.

Link copied to clipboard
fun splineToSplineHeading(poseHeadingRad: Pose2d, vectorUnit: Distance = Inches, tangent: Rotation2d): TaskBuilder
fun splineToSplineHeading(poseHeadingRad: Pose2d, vectorUnit: Distance = Inches, tangent: Double, tangentUnit: Angle = Radians): TaskBuilder

Move to the specified poseHeadingRad in a spline path while spline interpolating the heading to tangent.

fun splineToSplineHeading(vector: Vector2d, vectorUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians, tangent: Rotation2d): TaskBuilder
fun splineToSplineHeading(vector: Vector2d, vectorUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians, tangent: Double, tangentUnit: Angle = Radians): TaskBuilder

Move to the specified vector tangent to heading in a spline path while spline interpolating the robot heading to tangent.

Link copied to clipboard
fun stopAndAdd(a: Action): TaskBuilder

Stops the current trajectory (like endTrajectory) and adds action a next.

fun stopAndAdd(f: InstantFunction): TaskBuilder

Stops the current trajectory (like endTrajectory) and adds the instant function f next.

Link copied to clipboard
fun strafeTo(pos: Vector2d, unit: Distance = Inches): TaskBuilder

Move to the specified pos vector while maintaining the current heading.

Link copied to clipboard
fun strafeToConstantHeading(pos: Vector2d, unit: Distance = Inches): TaskBuilder

Move to the specified pos vector while maintaining the current heading.

Link copied to clipboard
fun strafeToLinearHeading(pos: Vector2d, posUnit: Distance = Inches, heading: Rotation2d): TaskBuilder
fun strafeToLinearHeading(pos: Vector2d, posUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians): TaskBuilder

Move to the specified pos vector while linearly interpolating the heading to heading.

Link copied to clipboard
fun strafeToSplineHeading(pos: Vector2d, posUnit: Distance = Inches, heading: Rotation2d): TaskBuilder
fun strafeToSplineHeading(pos: Vector2d, posUnit: Distance = Inches, heading: Double, headingUnit: Angle = Radians): TaskBuilder

Move to the specified pos vector while spline interpolating the heading to heading.

Link copied to clipboard
fun turn(angle: Double, unit: Angle = Radians): TaskBuilder

Turn the robot by angle in unit.

Link copied to clipboard
fun turnTo(heading: Rotation2d): TaskBuilder

Turn the robot to the heading, specified as a Rotation2d in radians.

fun turnTo(heading: Double, unit: Angle = Radians): TaskBuilder

Turn the robot to the heading in unit.

Link copied to clipboard
fun waitFor(t: Double, unit: Time = Seconds): TaskBuilder

Waits t time units of unit.

Link copied to clipboard

Waits t seconds.

Link copied to clipboard

Set the name for the underlying task.

Link copied to clipboard

Set the priority for the underlying task if using addTask.

Link copied to clipboard

Set the timeout for the underlying task.