14 #include "frc/spline/CubicHermiteSpline.h"
15 #include "frc/spline/QuinticHermiteSpline.h"
33 static std::array<Spline<3>::ControlVector, 2>
35 const Pose2d& start,
const std::vector<Translation2d>& interiorWaypoints,
44 static std::vector<Spline<5>::ControlVector>
66 std::vector<Translation2d> waypoints,
107 static void ThomasAlgorithm(
const std::vector<double>& a,
108 const std::vector<double>& b,
109 const std::vector<double>& c,
110 const std::vector<double>& d,
111 std::vector<double>* solutionVector);
Represents a two-dimensional parametric spline that interpolates between two points.
Definition: Spline.h:33
static std::vector< CubicHermiteSpline > CubicSplinesFromControlVectors(const Spline< 3 >::ControlVector &start, std::vector< Translation2d > waypoints, const Spline< 3 >::ControlVector &end)
Returns a set of cubic splines corresponding to the provided control vectors.
double Cos() const
Returns the cosine of the rotation.
Definition: Rotation2d.h:160
units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:61
const Translation2d & Translation() const
Returns the underlying translation.
Definition: Pose2d.h:104
Helper class that is used to generate cubic and quintic splines from user provided waypoints.
Definition: SplineHelper.h:22
Represents a 2d pose containing translational and rotational elements.
Definition: Pose2d.h:23
double Sin() const
Returns the sine of the rotation.
Definition: Rotation2d.h:167
const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition: Pose2d.h:111
static std::array< Spline< 3 >::ControlVector, 2 > CubicControlVectorsFromWaypoints(const Pose2d &start, const std::vector< Translation2d > &interiorWaypoints, const Pose2d &end)
Returns 2 cubic control vectors from a set of exterior waypoints and interior translations.
static std::vector< Spline< 5 >::ControlVector > QuinticControlVectorsFromWaypoints(const std::vector< Pose2d > &waypoints)
Returns quintic control vectors from a set of waypoints.
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16
units::meter_t Y() const
Returns the Y component of the translation.
Definition: Translation2d.h:68
static std::vector< QuinticHermiteSpline > QuinticSplinesFromControlVectors(const std::vector< Spline< 5 >::ControlVector > &controlVectors)
Returns a set of quintic splines corresponding to the provided control vectors.