64 for (
int i = 0; i <= Degree; i++) {
65 polynomialBases(i) =
std::pow(t, Degree - i);
72 double dx, dy, ddx, ddy;
87 ddx = combined(4) / t / t;
88 ddy = combined(5) / t / t;
92 const auto curvature =
93 (dx * ddy - ddx * dy) / ((dx * dx + dy * dy) *
std::hypot(dx, dy));
129 return Eigen::Vector2d{translation.
X().value(), translation.
Y().value()};
139 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:23
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:138
PoseWithCurvature GetPoint(double t) const
Gets the pose and curvature at some point t on the spline.
Definition: Spline.h:60
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:128
Spline(const Spline &)=default
std::pair< Pose2d, units::curvature_t > PoseWithCurvature
Definition: Spline.h:27
virtual const ControlVector & GetFinalControlVector() const =0
Returns the final control vector that created this spline.
Spline(Spline &&)=default
Spline & operator=(Spline &&)=default
virtual const ControlVector & GetInitialControlVector() const =0
Returns the initial control vector that created this spline.
Represents a translation in 2D space.
Definition: Translation2d.h:27
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:76
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition: Translation2d.h:83
This class is a wrapper around std::array that does compile time size checking.
Definition: array.h:26
UnitTypeLhs hypot(const UnitTypeLhs &x, const UnitTypeRhs &y)
Computes the square root of the sum-of-squares of x and y.
Definition: math.h:505
Definition: AprilTagPoseEstimator.h:15
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition: EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12
auto pow(const UnitType &value) noexcept -> unit_t< typename units::detail::power_of_unit< power, typename units::traits::unit_t_traits< UnitType >::unit_type >::type, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the value of value raised to the power
Definition: base.h:2806
Represents a control vector for a spline.
Definition: Spline.h:46
wpi::array< double,(Degree+1)/2 > x
The x components of the control vector.
Definition: Spline.h:48
wpi::array< double,(Degree+1)/2 > y
The y components of the control vector.
Definition: Spline.h:51