Helper class that is used to generate cubic and quintic splines from user provided waypoints.
More...
#include <frc/spline/SplineHelper.h>
Helper class that is used to generate cubic and quintic splines from user provided waypoints.
◆ CubicControlVectorsFromWaypoints()
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.
◆ CubicSplinesFromControlVectors()
static std::vector< CubicHermiteSpline > frc::SplineHelper::CubicSplinesFromControlVectors |
( |
const Spline< 3 >::ControlVector & |
start, |
|
|
std::vector< Translation2d > |
waypoints, |
|
|
const Spline< 3 >::ControlVector & |
end |
|
) |
| |
|
static |
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.
The derivation for the algorithm used can be found here: https://www.uio.no/studier/emner/matnat/ifi/nedlagte-emner/INF-MAT4350/h08/undervisningsmateriale/chap7alecture.pdf
- 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.
◆ 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 | A vector of un-optimized quintic splines. |
- Returns
- A vector of optimized quintic splines.
◆ QuinticSplinesFromControlVectors()
static std::vector< QuinticHermiteSpline > frc::SplineHelper::QuinticSplinesFromControlVectors |
( |
const std::vector< Spline< 5 >::ControlVector > & |
controlVectors | ) |
|
|
static |
Returns a set of quintic splines corresponding to the provided control vectors.
The user is free to set the direction of all waypoints. 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.
◆ QuinticSplinesFromWaypoints()
static std::vector< QuinticHermiteSpline > frc::SplineHelper::QuinticSplinesFromWaypoints |
( |
const std::vector< Pose2d > & |
waypoints | ) |
|
|
static |
Returns quintic splines from a set of waypoints.
- Parameters
-
- Returns
- List of quintic splines.
The documentation for this class was generated from the following file: