WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
SplineHelper.hpp
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <cstddef>
8#include <vector>
9
13#include "wpi/util/array.hpp"
14
15namespace wpi::math {
16/**
17 * Helper class that is used to generate cubic and quintic splines from user
18 * provided waypoints.
19 */
21 public:
22 /**
23 * Returns 2 cubic control vectors from a set of exterior waypoints and
24 * interior translations.
25 *
26 * @param start The starting pose.
27 * @param interiorWaypoints The interior waypoints.
28 * @param end The ending pose.
29 * @return 2 cubic control vectors.
30 */
33 const Pose2d& start, const std::vector<Translation2d>& interiorWaypoints,
34 const Pose2d& end) {
35 double scalar;
36 if (interiorWaypoints.empty()) {
37 scalar = 1.2 * start.Translation().Distance(end.Translation()).value();
38 } else {
39 scalar =
40 1.2 * start.Translation().Distance(interiorWaypoints.front()).value();
41 }
42 const auto initialCV = CubicControlVector(scalar, start);
43 if (!interiorWaypoints.empty()) {
44 scalar =
45 1.2 * end.Translation().Distance(interiorWaypoints.back()).value();
46 }
47 const auto finalCV = CubicControlVector(scalar, end);
48 return {initialCV, finalCV};
49 }
50
51 /**
52 * Returns quintic splines from a set of waypoints.
53 *
54 * @param waypoints The waypoints
55 * @return List of quintic splines.
56 */
57 static std::vector<QuinticHermiteSpline> QuinticSplinesFromWaypoints(
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];
64
65 // This just makes the splines look better.
66 const auto scalar =
67 1.2 * p0.Translation().Distance(p1.Translation()).value();
68
69 auto controlVectorA = QuinticControlVector(scalar, p0);
70 auto controlVectorB = QuinticControlVector(scalar, p1);
71 splines.emplace_back(controlVectorA.x, controlVectorB.x, controlVectorA.y,
72 controlVectorB.y);
73 }
74 return splines;
75 }
76
77 /**
78 * Returns a set of cubic splines corresponding to the provided control
79 * vectors. The user is free to set the direction of the start and end
80 * point. The directions for the middle waypoints are determined
81 * automatically to ensure continuous curvature throughout the path.
82 *
83 * The derivation for the algorithm used can be found here:
84 * <https://www.uio.no/studier/emner/matnat/ifi/nedlagte-emner/INF-MAT4350/h08/undervisningsmateriale/chap7alecture.pdf>
85 *
86 * @param start The starting control vector.
87 * @param waypoints The middle waypoints. This can be left blank if you
88 * only wish to create a path with two waypoints.
89 * @param end The ending control vector.
90 *
91 * @return A vector of cubic hermite splines that interpolate through the
92 * provided waypoints.
93 */
94 static std::vector<CubicHermiteSpline> CubicSplinesFromControlVectors(
95 const Spline<3>::ControlVector& start,
96 std::vector<Translation2d> waypoints,
97 const Spline<3>::ControlVector& end) {
98 std::vector<CubicHermiteSpline> splines;
99
100 wpi::util::array<double, 2> xInitial = start.x;
101 wpi::util::array<double, 2> yInitial = start.y;
102 wpi::util::array<double, 2> xFinal = end.x;
103 wpi::util::array<double, 2> yFinal = end.y;
104
105 if (waypoints.size() > 1) {
106 waypoints.emplace(waypoints.begin(),
107 Translation2d{wpi::units::meter_t{xInitial[0]},
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]}});
111
112 // Populate tridiagonal system for clamped cubic
113 /* See:
114 https://www.uio.no/studier/emner/matnat/ifi/nedlagte-emner/INF-MAT4350/h08
115 /undervisningsmateriale/chap7alecture.pdf
116 */
117
118 // Above-diagonal of tridiagonal matrix, zero-padded
119 std::vector<double> a;
120 // Diagonal of tridiagonal matrix
121 std::vector<double> b(waypoints.size() - 2, 4.0);
122 // Below-diagonal of tridiagonal matrix, zero-padded
123 std::vector<double> c;
124 // rhs vectors
125 std::vector<double> dx, dy;
126 // solution vectors
127 std::vector<double> fx(waypoints.size() - 2, 0.0),
128 fy(waypoints.size() - 2, 0.0);
129
130 // populate above-diagonal and below-diagonal vectors
131 a.emplace_back(0);
132 for (size_t i = 0; i < waypoints.size() - 3; ++i) {
133 a.emplace_back(1);
134 c.emplace_back(1);
135 }
136 c.emplace_back(0);
137
138 // populate rhs vectors
139 dx.emplace_back(
140 3 * (waypoints[2].X().value() - waypoints[0].X().value()) -
141 xInitial[1]);
142 dy.emplace_back(
143 3 * (waypoints[2].Y().value() - waypoints[0].Y().value()) -
144 yInitial[1]);
145 if (waypoints.size() > 4) {
146 for (size_t i = 1; i <= waypoints.size() - 4; ++i) {
147 // dx and dy represent the derivatives of the internal waypoints. The
148 // derivative of the second internal waypoint should involve the third
149 // and first internal waypoint, which have indices of 1 and 3 in the
150 // waypoints list (which contains ALL waypoints).
151 dx.emplace_back(
152 3 * (waypoints[i + 2].X().value() - waypoints[i].X().value()));
153 dy.emplace_back(
154 3 * (waypoints[i + 2].Y().value() - waypoints[i].Y().value()));
155 }
156 }
157 dx.emplace_back(3 * (waypoints[waypoints.size() - 1].X().value() -
158 waypoints[waypoints.size() - 3].X().value()) -
159 xFinal[1]);
160 dy.emplace_back(3 * (waypoints[waypoints.size() - 1].Y().value() -
161 waypoints[waypoints.size() - 3].Y().value()) -
162 yFinal[1]);
163
164 // Compute solution to tridiagonal system
165 ThomasAlgorithm(a, b, c, dx, &fx);
166 ThomasAlgorithm(a, b, c, dy, &fy);
167
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]);
172
173 for (size_t i = 0; i < fx.size() - 1; ++i) {
174 // Create the spline.
175 const CubicHermiteSpline spline{
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]}};
180
181 splines.push_back(spline);
182 }
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;
188
189 wpi::util::array<double, 2> midXControlVector{waypoints[0].X().value(),
190 xDeriv};
191 wpi::util::array<double, 2> midYControlVector{waypoints[0].Y().value(),
192 yDeriv};
193
194 splines.emplace_back(xInitial, midXControlVector, yInitial,
195 midYControlVector);
196 splines.emplace_back(midXControlVector, xFinal, midYControlVector,
197 yFinal);
198
199 } else {
200 // Create the spline.
201 const CubicHermiteSpline spline{xInitial, xFinal, yInitial, yFinal};
202 splines.push_back(spline);
203 }
204
205 return splines;
206 }
207
208 /**
209 * Returns a set of quintic splines corresponding to the provided control
210 * vectors. The user is free to set the direction of all waypoints. Continuous
211 * curvature is guaranteed throughout the path.
212 *
213 * @param controlVectors The control vectors.
214 * @return A vector of quintic hermite splines that interpolate through the
215 * provided waypoints.
216 */
217 static std::vector<QuinticHermiteSpline> QuinticSplinesFromControlVectors(
218 const std::vector<Spline<5>::ControlVector>& controlVectors) {
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);
226 }
227 return splines;
228 }
229
230 /**
231 * Optimizes the curvature of 2 or more quintic splines at knot points.
232 * Overall, this reduces the integral of the absolute value of the second
233 * derivative across the set of splines.
234 *
235 * @param splines A vector of un-optimized quintic splines.
236 * @return A vector of optimized quintic splines.
237 */
238 static std::vector<QuinticHermiteSpline> OptimizeCurvature(
239 const std::vector<QuinticHermiteSpline>& splines) {
240 // If there's only one spline in the vector, we can't optimize anything so
241 // just return that.
242 if (splines.size() < 2) {
243 return splines;
244 }
245
246 // Implements Section 4.1.2 of
247 // http://www2.informatik.uni-freiburg.de/~lau/students/Sprunk2008.pdf.
248
249 // Cubic splines minimize the integral of the second derivative's absolute
250 // value. Therefore, we can create cubic splines with the same 0th and 1st
251 // derivatives and the provided quintic splines, find the second derivative
252 // of those cubic splines and then use a weighted average for the second
253 // derivatives of the quintic splines.
254
255 std::vector<QuinticHermiteSpline> optimizedSplines;
256 optimizedSplines.reserve(splines.size());
257 optimizedSplines.push_back(splines[0]);
258
259 for (size_t i = 0; i < splines.size() - 1; ++i) {
260 const auto& a = splines[i];
261 const auto& b = splines[i + 1];
262
263 // Get the control vectors that created the quintic splines above.
264 const auto& aInitial = a.GetInitialControlVector();
265 const auto& aFinal = a.GetFinalControlVector();
266 const auto& bInitial = b.GetInitialControlVector();
267 const auto& bFinal = b.GetFinalControlVector();
268
269 // Create cubic splines with the same control vectors.
270 auto Trim = [](const wpi::util::array<double, 3>& a) {
271 return wpi::util::array<double, 2>{a[0], a[1]};
272 };
273 CubicHermiteSpline ca{Trim(aInitial.x), Trim(aFinal.x), Trim(aInitial.y),
274 Trim(aFinal.y)};
275 CubicHermiteSpline cb{Trim(bInitial.x), Trim(bFinal.x), Trim(bInitial.y),
276 Trim(bFinal.y)};
277
278 // Calculate the second derivatives at the knot points.
279 wpi::math::Vectord<4> bases{1.0, 1.0, 1.0, 1.0};
280 wpi::math::Vectord<6> combinedA = ca.Coefficients() * bases;
281
282 double ddxA = combinedA(4);
283 double ddyA = combinedA(5);
284 double ddxB = cb.Coefficients()(4, 1);
285 double ddyB = cb.Coefficients()(5, 1);
286
287 // Calculate the parameters for weighted average.
288 double dAB =
289 std::hypot(aFinal.x[0] - aInitial.x[0], aFinal.y[0] - aInitial.y[0]);
290 double dBC =
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);
294
295 // Calculate the weighted average.
296 double ddx = alpha * ddxA + beta * ddxB;
297 double ddy = alpha * ddyA + beta * ddyB;
298
299 // Create new splines.
300 optimizedSplines[i] = {aInitial.x,
301 {aFinal.x[0], aFinal.x[1], ddx},
302 aInitial.y,
303 {aFinal.y[0], aFinal.y[1], ddy}};
304 optimizedSplines.push_back({{bInitial.x[0], bInitial.x[1], ddx},
305 bFinal.x,
306 {bInitial.y[0], bInitial.y[1], ddy},
307 bFinal.y});
308 }
309
310 return optimizedSplines;
311 }
312
313 private:
314 static Spline<3>::ControlVector CubicControlVector(double scalar,
315 const Pose2d& point) {
316 return {{point.X().value(), scalar * point.Rotation().Cos()},
317 {point.Y().value(), scalar * point.Rotation().Sin()}};
318 }
319
320 static Spline<5>::ControlVector QuinticControlVector(double scalar,
321 const Pose2d& point) {
322 return {{point.X().value(), scalar * point.Rotation().Cos(), 0.0},
323 {point.Y().value(), scalar * point.Rotation().Sin(), 0.0}};
324 }
325
326 /**
327 * Thomas algorithm for solving tridiagonal systems Af = d.
328 *
329 * @param a the values of A above the diagonal
330 * @param b the values of A on the diagonal
331 * @param c the values of A below the diagonal
332 * @param d the vector on the rhs
333 * @param solutionVector the unknown (solution) vector, modified in-place
334 */
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;
341 size_t N = d.size();
342
343 // Create the temporary vectors
344 // Note that this is inefficient as it is possible to call
345 // this function many times. A better implementation would
346 // pass these temporary matrices by non-const reference to
347 // save excess allocation and deallocation
348 std::vector<double> c_star(N, 0.0);
349 std::vector<double> d_star(N, 0.0);
350
351 // This updates the coefficients in the first row
352 // Note that we should be checking for division by zero here
353 c_star[0] = c[0] / b[0];
354 d_star[0] = d[0] / b[0];
355
356 // Create the c_star and d_star coefficients in the forward sweep
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;
361 }
362
363 f[N - 1] = d_star[N - 1];
364 // This is the reverse sweep, used to update the solution vector f
365 for (int i = N - 2; i >= 0; i--) {
366 f[i] = d_star[i] - c_star[i] * f[i + 1];
367 }
368 }
369};
370} // namespace wpi::math
#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