TrajectoryActionBuilder

Builder that combines trajectories, turns, and other actions.

Constructors

Link copied to clipboard
constructor(turnActionFactory: TurnActionFactory, trajectoryActionFactory: TrajectoryActionFactory, beginPose: Pose2d, eps: Double, beginEndVel: Double, baseTurnConstraints: TurnConstraints, baseVelConstraint: VelConstraint, baseAccelConstraint: AccelConstraint, dispResolution: Double, angResolution: Double, poseMap: PoseMap = IdentityPoseMap())

Properties

Link copied to clipboard
Link copied to clipboard
val baseAccelConstraint: AccelConstraint
Link copied to clipboard
val baseVelConstraint: VelConstraint
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
val eps: Double
Link copied to clipboard
val poseMap: PoseMap
Link copied to clipboard

Functions

Link copied to clipboard

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.

Link copied to clipboard

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

Link copied to clipboard
fun build(): 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 at the current pose, tangent.

Link copied to clipboard
fun lineToX(posX: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun lineToXConstantHeading(posX: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun lineToXLinearHeading(posX: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun lineToXLinearHeading(posX: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun lineToXSplineHeading(posX: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun lineToXSplineHeading(posX: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun lineToY(posY: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun lineToYConstantHeading(posY: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun lineToYLinearHeading(posY: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun lineToYLinearHeading(posY: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun lineToYSplineHeading(posY: Double, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun lineToYSplineHeading(posY: Double, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
fun splineTo(pos: Vector2d, tangent: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun splineTo(pos: Vector2d, tangent: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun splineToConstantHeading(pos: Vector2d, tangent: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun splineToConstantHeading(pos: Vector2d, tangent: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun splineToLinearHeading(pose: Pose2d, tangent: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun splineToLinearHeading(pose: Pose2d, tangent: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun splineToSplineHeading(pose: Pose2d, tangent: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun splineToSplineHeading(pose: Pose2d, tangent: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard

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

Link copied to clipboard
fun strafeTo(pos: Vector2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun strafeToConstantHeading(pos: Vector2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun strafeToLinearHeading(pos: Vector2d, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun strafeToLinearHeading(pos: Vector2d, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun strafeToSplineHeading(pos: Vector2d, heading: Rotation2d, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
fun strafeToSplineHeading(pos: Vector2d, heading: Double, velConstraintOverride: VelConstraint? = null, accelConstraintOverride: AccelConstraint? = null): TrajectoryActionBuilder
Link copied to clipboard
fun turn(angle: Double, turnConstraintsOverride: TurnConstraints? = null): TrajectoryActionBuilder
Link copied to clipboard
fun turnTo(heading: Rotation2d, turnConstraintsOverride: TurnConstraints? = null): TrajectoryActionBuilder
fun turnTo(heading: Double, turnConstraintsOverride: TurnConstraints? = null): TrajectoryActionBuilder
Link copied to clipboard