public class Path
Path composed of a list of parametric curves and heading interpolators.
Modifier and Type | Class and Description |
---|---|
static class |
Path.ProjectionResult
Simple container for the result of a projection (i.e., a
project call). |
Constructor and Description |
---|
Path(java.util.List<? extends com.acmerobotics.roadrunner.path.ParametricCurve> parametricCurves,
java.util.List<? extends com.acmerobotics.roadrunner.path.heading.HeadingInterpolator> interpolators,
java.util.List<java.lang.Boolean> reversed)
Path composed of a list of parametric curves and heading interpolators.
|
Path(java.util.List<? extends com.acmerobotics.roadrunner.path.ParametricCurve> parametricCurves,
java.util.List<? extends com.acmerobotics.roadrunner.path.heading.HeadingInterpolator> interpolators)
Path composed of a list of parametric curves and heading interpolators.
|
Path(java.util.List<? extends com.acmerobotics.roadrunner.path.ParametricCurve> parametricCurves)
Path composed of a list of parametric curves and heading interpolators.
|
Path()
Path composed of a list of parametric curves and heading interpolators.
|
Path(ParametricCurve parametricCurve,
HeadingInterpolator interpolator,
boolean reversed) |
Path(ParametricCurve parametricCurve,
HeadingInterpolator interpolator) |
Path(ParametricCurve parametricCurve) |
Modifier and Type | Method and Description |
---|---|
Pose2d |
deriv(double s,
double t)
Returns the pose derivative
s units along the path. |
Pose2d |
deriv(double s)
Returns the pose derivative
s units along the path. |
Pose2d |
end()
Returns the end pose.
|
Pose2d |
endDeriv()
Returns the end pose derivative.
|
Pose2d |
endSecondDeriv()
Returns the end pose second derivative.
|
Pose2d |
get(double s,
double t)
Returns the pose
s units along the path. |
Pose2d |
get(double s)
Returns the pose
s units along the path. |
java.util.List<com.acmerobotics.roadrunner.path.heading.HeadingInterpolator> |
getInterpolators()
heading interpolators
|
java.util.List<com.acmerobotics.roadrunner.path.ParametricCurve> |
getParametricCurves()
parametric curves
|
java.util.List<java.lang.Boolean> |
getReversed()
whether or not to travel along the path segment in reverse
|
double |
length()
Returns the length of the path.
|
Path.ProjectionResult |
project(Vector2d point,
double projectGuess)
Project
point onto the current path. |
Pose2d |
secondDeriv(double s,
double t)
Returns the pose second derivative
s units along the path. |
Pose2d |
secondDeriv(double s)
Returns the pose second derivative
s units along the path. |
Pose2d |
start()
Returns the start pose.
|
Pose2d |
startDeriv()
Returns the start pose derivative.
|
Pose2d |
startSecondDeriv()
Returns the start pose second derivative.
|
@JvmOverloads public Path(@NotNull java.util.List<? extends com.acmerobotics.roadrunner.path.ParametricCurve> parametricCurves, @NotNull java.util.List<? extends com.acmerobotics.roadrunner.path.heading.HeadingInterpolator> interpolators, @NotNull java.util.List<java.lang.Boolean> reversed)
Path composed of a list of parametric curves and heading interpolators.
parametricCurves
- parametric curvesinterpolators
- heading interpolatorsreversed
- whether or not to travel along the path segment in reverse@JvmOverloads public Path(@NotNull java.util.List<? extends com.acmerobotics.roadrunner.path.ParametricCurve> parametricCurves, @NotNull java.util.List<? extends com.acmerobotics.roadrunner.path.heading.HeadingInterpolator> interpolators)
Path composed of a list of parametric curves and heading interpolators.
parametricCurves
- parametric curvesinterpolators
- heading interpolators@JvmOverloads public Path(@NotNull java.util.List<? extends com.acmerobotics.roadrunner.path.ParametricCurve> parametricCurves)
Path composed of a list of parametric curves and heading interpolators.
parametricCurves
- parametric curves@JvmOverloads public Path()
Path composed of a list of parametric curves and heading interpolators.
@JvmOverloads public Path(@NotNull ParametricCurve parametricCurve, @NotNull HeadingInterpolator interpolator, boolean reversed)
parametricCurve
- parametric curveinterpolator
- heading interpolatorreversed
- whether or not to travel in reverse@JvmOverloads public Path(@NotNull ParametricCurve parametricCurve, @NotNull HeadingInterpolator interpolator)
parametricCurve
- parametric curveinterpolator
- heading interpolator@JvmOverloads public Path(@NotNull ParametricCurve parametricCurve)
parametricCurve
- parametric curvepublic double length()
Returns the length of the path.
@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
@NotNull public Path.ProjectionResult project(@NotNull Vector2d point, double projectGuess)
Project point
onto the current path.
point
- query pointprojectGuess
- guess for the projected point's s along the pathpoint
@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.ParametricCurve> getParametricCurves()
parametric curves
@NotNull public java.util.List<com.acmerobotics.roadrunner.path.heading.HeadingInterpolator> getInterpolators()
heading interpolators
@NotNull public java.util.List<java.lang.Boolean> getReversed()
whether or not to travel along the path segment in reverse