Package edu.wpi.first.math.spline
Class SplineHelper
java.lang.Object
edu.wpi.first.math.spline.SplineHelper
public final class SplineHelper extends Object
Helper class that is used to generate cubic and quintic splines from user provided waypoints.
-
Method Summary
Modifier and Type Method Description static Spline.ControlVector[]
getCubicControlVectorsFromWaypoints(Pose2d start, Translation2d[] interiorWaypoints, Pose2d end)
Returns 2 cubic control vectors from a set of exterior waypoints and interior translations.static CubicHermiteSpline[]
getCubicSplinesFromControlVectors(Spline.ControlVector start, Translation2d[] waypoints, Spline.ControlVector end)
Returns a set of cubic splines corresponding to the provided control vectors.static QuinticHermiteSpline[]
getQuinticSplinesFromControlVectors(Spline.ControlVector[] controlVectors)
Returns a set of quintic splines corresponding to the provided control vectors.static QuinticHermiteSpline[]
getQuinticSplinesFromWaypoints(List<Pose2d> waypoints)
Returns quintic splines from a set of waypoints.static QuinticHermiteSpline[]
optimizeCurvature(QuinticHermiteSpline[] splines)
Optimizes the curvature of 2 or more quintic splines at knot points.
-
Method Details
-
getCubicControlVectorsFromWaypoints
public static Spline.ControlVector[] getCubicControlVectorsFromWaypoints(Pose2d start, Translation2d[] interiorWaypoints, Pose2d end)Returns 2 cubic control vectors from a set of exterior waypoints and interior translations.- Parameters:
start
- The starting pose.interiorWaypoints
- The interior waypoints.end
- The ending pose.- Returns:
- 2 cubic control vectors.
-
getQuinticSplinesFromWaypoints
Returns quintic splines from a set of waypoints.- Parameters:
waypoints
- The waypoints- Returns:
- array of splines.
-
getCubicSplinesFromControlVectors
public static CubicHermiteSpline[] getCubicSplinesFromControlVectors(Spline.ControlVector start, Translation2d[] waypoints, Spline.ControlVector end)Returns a set of cubic splines corresponding to the provided control vectors. The user is free to set the direction of the start and end point. The directions for the middle waypoints are determined automatically to ensure continuous curvature throughout the path.- Parameters:
start
- The starting control vector.waypoints
- The middle waypoints. This can be left blank if you only wish to create a path with two waypoints.end
- The ending control vector.- Returns:
- A vector of cubic hermite splines that interpolate through the provided waypoints and control vectors.
-
getQuinticSplinesFromControlVectors
public static QuinticHermiteSpline[] getQuinticSplinesFromControlVectors(Spline.ControlVector[] controlVectors)Returns a set of quintic splines corresponding to the provided control vectors. The user is free to set the direction of all control vectors. Continuous curvature is guaranteed throughout the path.- Parameters:
controlVectors
- The control vectors.- Returns:
- A vector of quintic hermite splines that interpolate through the provided waypoints.
-
optimizeCurvature
Optimizes the curvature of 2 or more quintic splines at knot points. Overall, this reduces the integral of the absolute value of the second derivative across the set of splines.- Parameters:
splines
- An array of un-optimized quintic splines.- Returns:
- An array of optimized quintic splines.
-