62 std::optional<PoseWithCurvature>
GetPoint(
double t)
const {
66 for (
int i = 0; i <= Degree; i++) {
67 polynomialBases(i) =
gcem::pow(t, Degree - i);
74 double dx, dy, ddx, ddy;
89 ddx = combined(4) / t / t;
90 ddy = combined(5) / t / t;
98 const auto curvature =
99 (dx * ddy - ddx * dy) / ((dx * dx + dy * dy) *
gcem::hypot(dx, dy));
135 return Eigen::Vector2d{{translation.
X().value()},
136 {translation.
Y().value()}};
146 return Translation2d{units::meter_t{vector(0)}, units::meter_t{vector(1)}};
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
Represents a two-dimensional parametric spline that interpolates between two points.
Definition Spline.h:27
constexpr Spline()=default
virtual constexpr const ControlVector & GetInitialControlVector() const =0
Returns the initial control vector that created this spline.
constexpr Spline & operator=(const Spline &)=default
static constexpr Translation2d FromVector(const Eigen::Vector2d &vector)
Converts an Eigen vector into a Translation2d.
Definition Spline.h:145
virtual constexpr ~Spline()=default
constexpr Spline & operator=(Spline &&)=default
static constexpr Eigen::Vector2d ToVector(const Translation2d &translation)
Converts a Translation2d into a vector that is compatible with Eigen.
Definition Spline.h:134
constexpr Spline(Spline &&)=default
constexpr Spline(const Spline &)=default
virtual constexpr Matrixd< 6, Degree+1 > Coefficients() const =0
Returns the coefficients of the spline.
std::pair< Pose2d, units::curvature_t > PoseWithCurvature
Definition Spline.h:29
virtual constexpr const ControlVector & GetFinalControlVector() const =0
Returns the final control vector that created this spline.
std::optional< PoseWithCurvature > GetPoint(double t) const
Gets the pose and curvature at some point t on the spline.
Definition Spline.h:62
Represents a translation in 2D space.
Definition Translation2d.h:29
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.h:83
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.h:90
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
constexpr common_return_t< T1, T2 > hypot(const T1 x, const T2 y) noexcept
Compile-time Pythagorean addition function.
Definition hypot.hpp:147
constexpr common_t< T1, T2 > pow(const T1 base, const T2 exp_term) noexcept
Compile-time power function.
Definition pow.hpp:82
Represents a control vector for a spline.
Definition Spline.h:48
wpi::array< double,(Degree+1)/2 > x
The x components of the control vector.
Definition Spline.h:50
wpi::array< double,(Degree+1)/2 > y
The y components of the control vector.
Definition Spline.h:53