public class Path
Path composed of a parametric curve and a heading interpolator.
| Modifier and Type | Class and Description |
|---|---|
static class |
Path.ProjectionResult |
| 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 parametric curve and a heading interpolator.
|
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 parametric curve and a heading interpolator.
|
Path(java.util.List<? extends com.acmerobotics.roadrunner.path.ParametricCurve> parametricCurves)
Path composed of a parametric curve and a heading interpolator.
|
Path(ParametricCurve parametricCurve,
HeadingInterpolator interpolator,
boolean reversed) |
Path(ParametricCurve parametricCurve,
HeadingInterpolator interpolator) |
Path(ParametricCurve parametricCurve) |
| Modifier and Type | Method and Description |
|---|---|
Pose2d |
deriv(double displacement)
Returns the pose derivative displacement 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 displacement)
Returns the pose displacement units along the path.
|
java.util.List<com.acmerobotics.roadrunner.path.heading.HeadingInterpolator> |
getInterpolators() |
java.util.List<com.acmerobotics.roadrunner.path.ParametricCurve> |
getParametricCurves() |
java.util.List<java.lang.Boolean> |
getReversed()
whether or not to travel along the path 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 displacement)
Returns the pose second derivative displacement 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.
|
public 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 parametric curve and a heading interpolator.
reversed - whether or not to travel along the path in reversereversed - whether or not to travel along the path in reversepublic 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 parametric curve and a heading interpolator.
public Path(java.util.List<? extends com.acmerobotics.roadrunner.path.ParametricCurve> parametricCurves)
Path composed of a parametric curve and a heading interpolator.
public Path(ParametricCurve parametricCurve, HeadingInterpolator interpolator, boolean reversed)
public Path(ParametricCurve parametricCurve, HeadingInterpolator interpolator)
public Path(ParametricCurve parametricCurve)
public double length()
Returns the length of the path.
public Pose2d get(double displacement)
Returns the pose displacement units along the path.
public Pose2d deriv(double displacement)
Returns the pose derivative displacement units along the path.
public Pose2d secondDeriv(double displacement)
Returns the pose second derivative displacement units along the path.
public Path.ProjectionResult project(Vector2d point, double projectGuess)
Project point onto the current path.
point - query pointprojectGuess - guess for the projected point's displacement along the pathpublic Pose2d start()
Returns the start pose.
public Pose2d startDeriv()
Returns the start pose derivative.
public Pose2d startSecondDeriv()
Returns the start pose second derivative.
public Pose2d end()
Returns the end pose.
public Pose2d endDeriv()
Returns the end pose derivative.
public Pose2d endSecondDeriv()
Returns the end pose second derivative.
public java.util.List<com.acmerobotics.roadrunner.path.ParametricCurve> getParametricCurves()
public java.util.List<com.acmerobotics.roadrunner.path.heading.HeadingInterpolator> getInterpolators()
public java.util.List<java.lang.Boolean> getReversed()
whether or not to travel along the path in reverse