public class Path
Path composed of a list of parametric curves and heading interpolators.
public Path(@NotNull java.util.List<com.acmerobotics.roadrunner.path.PathSegment> segments)
Path composed of a list of parametric curves and heading interpolators.
segments
- list of path segmentspublic Path(@NotNull PathSegment segment)
segment
- single path segmentpublic double length()
Returns the length of the path.
@NotNull public kotlin.Pair<com.acmerobotics.roadrunner.path.PathSegment,java.lang.Double> segment(double s)
@JvmOverloads @NotNull public Pose2d get(double s, double t)
Returns the pose s
units along the path.
s
@JvmOverloads @NotNull public Pose2d get(double s)
Returns the pose s
units along the path.
s
@JvmOverloads @NotNull public Pose2d deriv(double s, double t)
Returns the pose derivative s
units along the path.
s
@JvmOverloads @NotNull public Pose2d deriv(double s)
Returns the pose derivative s
units along the path.
s
@JvmOverloads @NotNull public Pose2d secondDeriv(double s, double t)
Returns the pose second derivative s
units along the path.
s
@JvmOverloads @NotNull public Pose2d secondDeriv(double s)
Returns the pose second derivative s
units along the path.
s
public double fastProject(@NotNull Vector2d queryPoint, double projectGuess)
Project queryPoint
onto the current path using the iterative method described
here.
queryPoint
- query queryPointprojectGuess
- guess for the projected queryPoint's s along the pathqueryPoint
,
herepublic double project(@NotNull Vector2d queryPoint, double ds)
Project queryPoint
onto the current path by applying fastProject
with various
guesses along the path.
queryPoint
- query queryPointds
- spacing between guessesqueryPoint
,
fastProject
@NotNull public Pose2d start()
Returns the start pose.
@NotNull public Pose2d startDeriv()
Returns the start pose derivative.
@NotNull public Pose2d startSecondDeriv()
Returns the start pose second derivative.
@NotNull public Pose2d end()
Returns the end pose.
@NotNull public Pose2d endDeriv()
Returns the end pose derivative.
@NotNull public Pose2d endSecondDeriv()
Returns the end pose second derivative.
@NotNull public java.util.List<com.acmerobotics.roadrunner.path.PathSegment> getSegments()
list of path segments