61 for (
int i = 0; i <= Degree; i++) {
62 polynomialBases(i) =
std::pow(t, Degree - i);
69 double dx, dy, ddx, ddy;
84 ddx = combined(4) / t / t;
85 ddy = combined(5) / t / t;
89 const auto curvature =
90 (dx * ddy - ddx * dy) / ((dx * dx + dy * dy) *
std::hypot(dx, dy));
112 return Eigen::Vector2d{translation.
X().value(), translation.
Y().value()};
122 return Translation2d{units::meter_t{vector(0)}, units::meter_t{vector(1)}};
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:180
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Represents a two-dimensional parametric spline that interpolates between two points.
Definition: Spline.h:25
virtual ~Spline()=default
virtual Matrixd< 6, Degree+1 > Coefficients() const =0
Returns the coefficients of the spline.
static Translation2d FromVector(const Eigen::Vector2d &vector)
Converts an Eigen vector into a Translation2d.
Definition: Spline.h:121
PoseWithCurvature GetPoint(double t) const
Gets the pose and curvature at some point t on the spline.
Definition: Spline.h:57
Spline & operator=(const Spline &)=default
static Eigen::Vector2d ToVector(const Translation2d &translation)
Converts a Translation2d into a vector that is compatible with Eigen.
Definition: Spline.h:111
Spline(const Spline &)=default
std::pair< Pose2d, units::curvature_t > PoseWithCurvature
Definition: Spline.h:27
Spline(Spline &&)=default
Spline & operator=(Spline &&)=default
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:70
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition: Translation2d.h:77
This class is a wrapper around std::array that does compile time size checking.
Definition: array.h:26
constexpr common_return_t< T1, T2 > hypot(const T1 x, const T2 y) noexcept
Compile-time Pythagorean addition function.
Definition: hypot.hpp:84
Definition: AprilTagPoseEstimator.h:15
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12
constexpr common_t< T1, T2 > pow(const T1 base, const T2 exp_term) noexcept
Compile-time power function.
Definition: pow.hpp:76
Represents a control vector for a spline.
Definition: Spline.h:46
wpi::array< double,(Degree+1)/2 > x
Definition: Spline.h:47
wpi::array< double,(Degree+1)/2 > y
Definition: Spline.h:48