makeTrajectory

Begin building a RoadRunner trajectory from the last-known robot position when this method is called. For deferring this starting pose dynamically, consider a DynamicTask (util. `Task.defer`) builder.

Return

extended RoadRunner trajectory task builder


open fun makeTrajectory(@NonNull poseMap: PoseMap): TaskBuilder

Begin building a RoadRunner trajectory from the inverse (PoseMap piped) last-known robot position when this method is called. For deferring this starting pose dynamically, consider a DynamicTask (util. `Task.defer`) builder.

Return

extended RoadRunner trajectory task builder

Parameters

poseMap

the PoseMap to use for this builder, note that the implicit last-known position is used and automatically passed into the PoseMap now to later 'invert' it. This assumes your PoseMap is idempotent to inversion. For most mappings, this will result in the absolute last-known position being used as the starting pose, which is usually the case when you are trying to use the current position of the robot. If you wish the PoseMap to apply normally, consider using the other makeTrajectory methods and manually passing the last-known position from Storage.


open fun makeTrajectory(@NonNull startPose: Pose2d): TaskBuilder

Begin building a RoadRunner trajectory from the supplied pose when this method is called. For deferring this starting pose dynamically, consider a DynamicTask (util. `Task.defer`) builder.

Return

extended RoadRunner trajectory task builder

Parameters

startPose

the pose to start the trajectory generation from


open fun makeTrajectory(@NonNull startPose: Pose2d, @NonNull poseMap: PoseMap): TaskBuilder

Begin building a RoadRunner trajectory from the supplied pose when this method is called. For deferring this starting pose dynamically, consider a DynamicTask (util. `Task.defer`) builder.

Return

extended RoadRunner trajectory task builder

Parameters

startPose

the pose to start the trajectory generation from

poseMap

the PoseMap to use for this builder


open fun makeTrajectory(@NonNull startVec: Vector2d, @NonNull distUnit: Distance, ang: Double, @NonNull angUnit: Angle): TaskBuilder

Begin building a RoadRunner trajectory from the supplied pose when this method is called. For deferring this starting pose dynamically, consider a DynamicTask (util. `Task.defer`) builder.

Return

extended RoadRunner trajectory task builder

Parameters

startVec

the vector to start the trajectory at and where the robot will be placed

distUnit

the unit of distance of the start pose

ang

the angle of the start pose

angUnit

the unit of angle of the start pose


open fun makeTrajectory(@NonNull startVec: Vector2d, @NonNull distUnit: Distance, ang: Double, @NonNull angUnit: Angle, @NonNull poseMap: PoseMap): TaskBuilder

Begin building a RoadRunner trajectory from the supplied pose when this method is called. For deferring this starting pose dynamically, consider a DynamicTask (util. `Task.defer`) builder.

Return

extended RoadRunner trajectory task builder

Parameters

startVec

the vector to start the trajectory at and where the robot will be placed

distUnit

the unit of distance of the start pose

ang

the angle of the start pose

angUnit

the unit of angle of the start pose

poseMap

the PoseMap to use for this builder