public class BaseTrajectoryBuilder<T extends BaseTrajectoryBuilder<T>>
Easy-to-use builder for creating class Trajectory
instances.
class Trajectory
protected BaseTrajectoryBuilder(@Nullable Pose2d startPose, @Nullable java.lang.Double startTangent, @Nullable Trajectory trajectory, @Nullable java.lang.Double t)
Easy-to-use builder for creating class Trajectory
instances.
startPose
- start posetrajectory
- initial trajectory (for splicing)t
- time index in previous trajectory to begin new trajectoryclass Trajectory
@NotNull protected PathBuilder getPathBuilder()
protected void setPathBuilder(@NotNull PathBuilder p)
@NotNull public T lineTo(@NotNull Vector2d endPosition)
Adds a line segment with tangent heading interpolation.
endPosition
- end position@NotNull public T lineToConstantHeading(@NotNull Vector2d endPosition)
Adds a line segment with constant heading interpolation.
endPosition
- end position@NotNull public T lineToLinearHeading(@NotNull Pose2d endPose)
Adds a line segment with linear heading interpolation.
endPose
- end pose@NotNull public T lineToSplineHeading(@NotNull Pose2d endPose)
Adds a line segment with spline heading interpolation.
endPose
- end pose@NotNull public T strafeTo(@NotNull Vector2d endPosition)
Adds a strafe path segment.
endPosition
- end position@NotNull public T forward(double distance)
Adds a line straight forward.
distance
- distance to travel forward@NotNull public T back(double distance)
Adds a line straight backward.
distance
- distance to travel backward@NotNull public T strafeLeft(double distance)
Adds a segment that strafes left in the robot reference frame.
distance
- distance to strafe left@NotNull public T strafeRight(double distance)
Adds a segment that strafes right in the robot reference frame.
distance
- distance to strafe right@NotNull public T splineTo(@NotNull Vector2d endPosition, double endTangent)
Adds a spline segment with tangent heading interpolation.
endPosition
- end positionendTangent
- end tangent@NotNull public T splineToConstantHeading(@NotNull Vector2d endPosition, double endTangent)
Adds a spline segment with constant heading interpolation.
endPosition
- end positionendTangent
- end tangent@NotNull public T splineToLinearHeading(@NotNull Pose2d endPose, double endTangent)
Adds a spline segment with linear heading interpolation.
endPose
- end poseendTangent
- end tangent@NotNull public T splineToSplineHeading(@NotNull Pose2d endPose, double endTangent)
Adds a spline segment with spline heading interpolation.
endPose
- end poseendTangent
- end tangent@NotNull public T addTemporalMarker(double time, @NotNull MarkerCallback callback)
Adds a marker to the trajectory at time
.
time
@NotNull public T addTemporalMarker(double scale, double offset, @NotNull MarkerCallback callback)
@NotNull public T addTemporalMarker(@NotNull kotlin.jvm.functions.Function1<? super java.lang.Double,java.lang.Double> time, @NotNull MarkerCallback callback)
Adds a marker to the trajectory at time
evaluated with the trajectory duration.
time
@NotNull public T addSpatialMarker(@NotNull Vector2d point, @NotNull MarkerCallback callback)
Adds a marker that will be triggered at the closest trajectory point to point
.
point
@NotNull public T addDisplacementMarker(@NotNull MarkerCallback callback)
Adds a marker at the current position of the trajectory.
@NotNull public T addDisplacementMarker(double displacement, @NotNull MarkerCallback callback)
Adds a marker to the trajectory at displacement
.
displacement
@NotNull public T addDisplacementMarker(double scale, double offset, @NotNull MarkerCallback callback)
@NotNull public T addDisplacementMarker(@NotNull kotlin.jvm.functions.Function1<? super java.lang.Double,java.lang.Double> displacement, @NotNull MarkerCallback callback)
Adds a marker to the trajectory at displacement
evaluated with path length.
displacement
@NotNull public Trajectory build()
Constructs the class Trajectory
instance.
class Trajectory
@NotNull protected Trajectory buildTrajectory(@NotNull Path path, @NotNull java.util.List<com.acmerobotics.roadrunner.trajectory.TemporalMarker> temporalMarkers, @NotNull java.util.List<com.acmerobotics.roadrunner.trajectory.DisplacementMarker> displacementMarkers, @NotNull java.util.List<com.acmerobotics.roadrunner.trajectory.SpatialMarker> spatialMarkers)
Build a trajectory from path
.
path