WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
frc::Spline< Degree > Class Template Referenceabstract

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 Splineoperator= (const Spline &)=default
 
constexpr Spline (Spline &&)=default
 
constexpr Splineoperator= (Spline &&)=default
 
virtual constexpr ~Spline ()=default
 
std::optional< PoseWithCurvatureGetPoint (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 ControlVectorGetInitialControlVector () const =0
 Returns the initial control vector that created this spline.
 
virtual constexpr const ControlVectorGetFinalControlVector () 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.
 

Detailed Description

template<int Degree>
class frc::Spline< Degree >

Represents a two-dimensional parametric spline that interpolates between two points.

Template Parameters
DegreeThe degree of the spline.

Member Typedef Documentation

◆ PoseWithCurvature

template<int Degree>
using frc::Spline< Degree >::PoseWithCurvature = std::pair<Pose2d, units::curvature_t>

Constructor & Destructor Documentation

◆ Spline() [1/3]

template<int Degree>
frc::Spline< Degree >::Spline ( )
constexprdefault

◆ Spline() [2/3]

template<int Degree>
frc::Spline< Degree >::Spline ( const Spline< Degree > & )
constexprdefault

◆ Spline() [3/3]

template<int Degree>
frc::Spline< Degree >::Spline ( Spline< Degree > && )
constexprdefault

◆ ~Spline()

template<int Degree>
virtual constexpr frc::Spline< Degree >::~Spline ( )
constexprvirtualdefault

Member Function Documentation

◆ Coefficients()

template<int Degree>
virtual constexpr Matrixd< 6, Degree+1 > frc::Spline< Degree >::Coefficients ( ) const
constexprpure virtual

Returns the coefficients of the spline.

Returns
The coefficients of the spline.

Implemented in frc::CubicHermiteSpline, and frc::QuinticHermiteSpline.

◆ FromVector()

template<int Degree>
static constexpr Translation2d frc::Spline< Degree >::FromVector ( const Eigen::Vector2d & vector)
inlinestaticconstexprprotected

Converts an Eigen vector into a Translation2d.

Parameters
vectorThe vector to convert.
Returns
The Translation2d.

◆ GetFinalControlVector()

template<int Degree>
virtual constexpr const ControlVector & frc::Spline< Degree >::GetFinalControlVector ( ) const
constexprpure virtual

Returns the final control vector that created this spline.

Returns
The final control vector that created this spline.

Implemented in frc::CubicHermiteSpline, and frc::QuinticHermiteSpline.

◆ GetInitialControlVector()

template<int Degree>
virtual constexpr const ControlVector & frc::Spline< Degree >::GetInitialControlVector ( ) const
constexprpure virtual

Returns the initial control vector that created this spline.

Returns
The initial control vector that created this spline.

Implemented in frc::CubicHermiteSpline, and frc::QuinticHermiteSpline.

◆ GetPoint()

template<int Degree>
std::optional< PoseWithCurvature > frc::Spline< Degree >::GetPoint ( double t) const
inline

Gets the pose and curvature at some point t on the spline.

Parameters
tThe point t
Returns
The pose and curvature at that point.

◆ operator=() [1/2]

template<int Degree>
Spline & frc::Spline< Degree >::operator= ( const Spline< Degree > & )
constexprdefault

◆ operator=() [2/2]

template<int Degree>
Spline & frc::Spline< Degree >::operator= ( Spline< Degree > && )
constexprdefault

◆ ToVector()

template<int Degree>
static constexpr Eigen::Vector2d frc::Spline< Degree >::ToVector ( const Translation2d & translation)
inlinestaticconstexprprotected

Converts a Translation2d into a vector that is compatible with Eigen.

Parameters
translationThe Translation2d to convert.
Returns
The vector.

The documentation for this class was generated from the following file: