WPILibC++ 2025.2.1
|
Represents a two-dimensional parametric spline that interpolates between two points. More...
#include <frc/spline/Spline.h>
Classes | |
struct | ControlVector |
Represents a control vector for a spline. More... | |
Public Types | |
using | PoseWithCurvature = std::pair<Pose2d, units::curvature_t> |
Public Member Functions | |
constexpr | Spline ()=default |
constexpr | Spline (const Spline &)=default |
constexpr Spline & | operator= (const Spline &)=default |
constexpr | Spline (Spline &&)=default |
constexpr Spline & | operator= (Spline &&)=default |
virtual constexpr | ~Spline ()=default |
std::optional< PoseWithCurvature > | GetPoint (double t) const |
Gets the pose and curvature at some point t on the spline. | |
virtual constexpr Matrixd< 6, Degree+1 > | Coefficients () const =0 |
Returns the coefficients of the spline. | |
virtual constexpr const ControlVector & | GetInitialControlVector () const =0 |
Returns the initial control vector that created this spline. | |
virtual constexpr const ControlVector & | GetFinalControlVector () const =0 |
Returns the final control vector that created this spline. | |
Static Protected Member Functions | |
static constexpr Eigen::Vector2d | ToVector (const Translation2d &translation) |
Converts a Translation2d into a vector that is compatible with Eigen. | |
static constexpr Translation2d | FromVector (const Eigen::Vector2d &vector) |
Converts an Eigen vector into a Translation2d. | |
Represents a two-dimensional parametric spline that interpolates between two points.
Degree | The degree of the spline. |
using frc::Spline< Degree >::PoseWithCurvature = std::pair<Pose2d, units::curvature_t> |
|
constexprdefault |
|
constexprdefault |
|
constexprdefault |
|
constexprvirtualdefault |
|
constexprpure virtual |
Returns the coefficients of the spline.
Implemented in frc::CubicHermiteSpline, and frc::QuinticHermiteSpline.
|
inlinestaticconstexprprotected |
Converts an Eigen vector into a Translation2d.
vector | The vector to convert. |
|
constexprpure virtual |
Returns the final control vector that created this spline.
Implemented in frc::CubicHermiteSpline, and frc::QuinticHermiteSpline.
|
constexprpure virtual |
Returns the initial control vector that created this spline.
Implemented in frc::CubicHermiteSpline, and frc::QuinticHermiteSpline.
|
inline |
Gets the pose and curvature at some point t on the spline.
t | The point t |
|
constexprdefault |
|
constexprdefault |
|
inlinestaticconstexprprotected |
Converts a Translation2d into a vector that is compatible with Eigen.
translation | The Translation2d to convert. |