33 const Pose2d& start,
const std::vector<Translation2d>& interiorWaypoints,
36 if (interiorWaypoints.empty()) {
37 scalar = 1.2 * start.Translation().Distance(end.
Translation()).value();
40 1.2 * start.Translation().Distance(interiorWaypoints.front()).value();
42 const auto initialCV = CubicControlVector(scalar, start);
43 if (!interiorWaypoints.empty()) {
47 const auto finalCV = CubicControlVector(scalar, end);
48 return {initialCV, finalCV};
58 const std::vector<Pose2d>& waypoints) {
59 std::vector<QuinticHermiteSpline> splines;
60 splines.reserve(waypoints.size() - 1);
61 for (
size_t i = 0; i < waypoints.size() - 1; ++i) {
62 auto& p0 = waypoints[i];
63 auto& p1 = waypoints[i + 1];
67 1.2 * p0.Translation().Distance(p1.Translation()).value();
69 auto controlVectorA = QuinticControlVector(scalar, p0);
70 auto controlVectorB = QuinticControlVector(scalar, p1);
71 splines.emplace_back(controlVectorA.x, controlVectorB.x, controlVectorA.y,
96 std::vector<Translation2d> waypoints,
98 std::vector<CubicHermiteSpline> splines;
105 if (waypoints.size() > 1) {
106 waypoints.emplace(waypoints.begin(),
108 wpi::units::meter_t{yInitial[0]}});
109 waypoints.emplace_back(
Translation2d{wpi::units::meter_t{xFinal[0]},
110 wpi::units::meter_t{yFinal[0]}});
119 std::vector<double> a;
121 std::vector<double> b(waypoints.size() - 2, 4.0);
123 std::vector<double> c;
125 std::vector<double> dx, dy;
127 std::vector<double> fx(waypoints.size() - 2, 0.0),
128 fy(waypoints.size() - 2, 0.0);
132 for (
size_t i = 0; i < waypoints.size() - 3; ++i) {
140 3 * (waypoints[2].X().value() - waypoints[0].X().value()) -
143 3 * (waypoints[2].Y().value() - waypoints[0].Y().value()) -
145 if (waypoints.size() > 4) {
146 for (
size_t i = 1; i <= waypoints.size() - 4; ++i) {
152 3 * (waypoints[i + 2].X().value() - waypoints[i].X().value()));
154 3 * (waypoints[i + 2].Y().value() - waypoints[i].Y().value()));
157 dx.emplace_back(3 * (waypoints[waypoints.size() - 1].X().value() -
158 waypoints[waypoints.size() - 3].X().value()) -
160 dy.emplace_back(3 * (waypoints[waypoints.size() - 1].Y().value() -
161 waypoints[waypoints.size() - 3].Y().value()) -
165 ThomasAlgorithm(a, b, c, dx, &fx);
166 ThomasAlgorithm(a, b, c, dy, &fy);
168 fx.emplace(fx.begin(), xInitial[1]);
169 fx.emplace_back(xFinal[1]);
170 fy.emplace(fy.begin(), yInitial[1]);
171 fy.emplace_back(yFinal[1]);
173 for (
size_t i = 0; i < fx.size() - 1; ++i) {
176 {waypoints[i].X().value(), fx[i]},
177 {waypoints[i + 1].X().value(), fx[i + 1]},
178 {waypoints[i].Y().value(), fy[i]},
179 {waypoints[i + 1].Y().value(), fy[i + 1]}};
181 splines.push_back(spline);
183 }
else if (waypoints.size() == 1) {
184 const double xDeriv =
185 (3 * (xFinal[0] - xInitial[0]) - xFinal[1] - xInitial[1]) / 4.0;
186 const double yDeriv =
187 (3 * (yFinal[0] - yInitial[0]) - yFinal[1] - yInitial[1]) / 4.0;
194 splines.emplace_back(xInitial, midXControlVector, yInitial,
196 splines.emplace_back(midXControlVector, xFinal, midYControlVector,
201 const CubicHermiteSpline spline{xInitial, xFinal, yInitial, yFinal};
202 splines.push_back(spline);
219 std::vector<QuinticHermiteSpline> splines;
220 for (
size_t i = 0; i < controlVectors.size() - 1; ++i) {
221 auto& xInitial = controlVectors[i].x;
222 auto& yInitial = controlVectors[i].y;
223 auto& xFinal = controlVectors[i + 1].x;
224 auto& yFinal = controlVectors[i + 1].y;
225 splines.emplace_back(xInitial, xFinal, yInitial, yFinal);
239 const std::vector<QuinticHermiteSpline>& splines) {
242 if (splines.size() < 2) {
255 std::vector<QuinticHermiteSpline> optimizedSplines;
256 optimizedSplines.reserve(splines.size());
257 optimizedSplines.push_back(splines[0]);
259 for (
size_t i = 0; i < splines.size() - 1; ++i) {
260 const auto& a = splines[i];
261 const auto& b = splines[i + 1];
264 const auto& aInitial = a.GetInitialControlVector();
265 const auto& aFinal = a.GetFinalControlVector();
266 const auto& bInitial = b.GetInitialControlVector();
267 const auto& bFinal = b.GetFinalControlVector();
282 double ddxA = combinedA(4);
283 double ddyA = combinedA(5);
289 std::hypot(aFinal.x[0] - aInitial.x[0], aFinal.y[0] - aInitial.y[0]);
291 std::hypot(bFinal.x[0] - bInitial.x[0], bFinal.y[0] - bInitial.y[0]);
292 double alpha = dBC / (dAB + dBC);
293 double beta = dAB / (dAB + dBC);
296 double ddx = alpha * ddxA + beta * ddxB;
297 double ddy = alpha * ddyA + beta * ddyB;
300 optimizedSplines[i] = {aInitial.x,
301 {aFinal.x[0], aFinal.x[1], ddx},
303 {aFinal.y[0], aFinal.y[1], ddy}};
304 optimizedSplines.push_back({{bInitial.x[0], bInitial.x[1], ddx},
306 {bInitial.y[0], bInitial.y[1], ddy},
310 return optimizedSplines;
316 return {{point.
X().value(), scalar * point.
Rotation().
Cos()},
322 return {{point.X().value(), scalar * point.Rotation().Cos(), 0.0},
323 {point.Y().value(), scalar * point.Rotation().Sin(), 0.0}};
335 static void ThomasAlgorithm(
const std::vector<double>& a,
336 const std::vector<double>& b,
337 const std::vector<double>& c,
338 const std::vector<double>& d,
339 std::vector<double>* solutionVector) {
340 auto& f = *solutionVector;
348 std::vector<double> c_star(N, 0.0);
349 std::vector<double> d_star(N, 0.0);
353 c_star[0] = c[0] / b[0];
354 d_star[0] = d[0] / b[0];
357 for (
size_t i = 1; i < N; ++i) {
358 double m = 1.0 / (b[i] - a[i] * c_star[i - 1]);
359 c_star[i] = c[i] * m;
360 d_star[i] = (d[i] - a[i] * d_star[i - 1]) * m;
363 f[N - 1] = d_star[N - 1];
365 for (
int i = N - 2; i >= 0; i--) {
366 f[i] = d_star[i] - c_star[i] * f[i + 1];
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a hermite spline of degree 3.
Definition CubicHermiteSpline.hpp:16
Matrixd< 6, 3+1 > Coefficients() const override
Returns the coefficients matrix.
Definition CubicHermiteSpline.hpp:73
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition Pose2d.hpp:107
constexpr wpi::units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose2d.hpp:114
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition Pose2d.hpp:128
constexpr wpi::units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition Pose2d.hpp:121
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.hpp:235
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.hpp:242
Helper class that is used to generate cubic and quintic splines from user provided waypoints.
Definition SplineHelper.hpp:20
static wpi::util::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.
Definition SplineHelper.hpp:32
static std::vector< QuinticHermiteSpline > QuinticSplinesFromControlVectors(const std::vector< Spline< 5 >::ControlVector > &controlVectors)
Returns a set of quintic splines corresponding to the provided control vectors.
Definition SplineHelper.hpp:217
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.
Definition SplineHelper.hpp:94
static std::vector< QuinticHermiteSpline > QuinticSplinesFromWaypoints(const std::vector< Pose2d > &waypoints)
Returns quintic splines from a set of waypoints.
Definition SplineHelper.hpp:57
static std::vector< QuinticHermiteSpline > OptimizeCurvature(const std::vector< QuinticHermiteSpline > &splines)
Optimizes the curvature of 2 or more quintic splines at knot points.
Definition SplineHelper.hpp:238
Represents a translation in 2D space.
Definition Translation2d.hpp:30
constexpr wpi::units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2D space.
Definition Translation2d.hpp:76
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20
Eigen::Vector< double, Size > Vectord
Definition EigenCore.hpp:12
Represents a control vector for a spline.
Definition Spline.hpp:48
wpi::util::array< double,(Degree+1)/2 > x
The x components of the control vector.
Definition Spline.hpp:50
wpi::util::array< double,(Degree+1)/2 > y
The y components of the control vector.
Definition Spline.hpp:53