59 const std::vector<Pose2d>& waypoints) {
60 std::vector<QuinticHermiteSpline> splines;
61 splines.reserve(waypoints.size() - 1);
62 for (
size_t i = 0; i < waypoints.size() - 1; ++i) {
63 auto& p0 = waypoints[i];
64 auto& p1 = waypoints[i + 1];
68 1.2 * p0.Translation().Distance(p1.Translation()).value();
70 auto controlVectorA = QuinticControlVector(
scalar, p0);
71 auto controlVectorB = QuinticControlVector(
scalar, p1);
72 splines.emplace_back(controlVectorA.x, controlVectorB.x, controlVectorA.y,
97 std::vector<Translation2d> waypoints,
99 std::vector<CubicHermiteSpline> splines;
106 if (waypoints.size() > 1) {
107 waypoints.emplace(waypoints.begin(),
109 units::meter_t{yInitial[0]}});
110 waypoints.emplace_back(
111 Translation2d{units::meter_t{xFinal[0]}, units::meter_t{yFinal[0]}});
120 std::vector<double> a;
122 std::vector<double> b(waypoints.size() - 2, 4.0);
124 std::vector<double> c;
126 std::vector<double> dx, dy;
128 std::vector<double> fx(waypoints.size() - 2, 0.0),
129 fy(waypoints.size() - 2, 0.0);
133 for (
size_t i = 0; i < waypoints.size() - 3; ++i) {
141 3 * (waypoints[2].X().value() - waypoints[0].X().value()) -
144 3 * (waypoints[2].Y().value() - waypoints[0].Y().value()) -
146 if (waypoints.size() > 4) {
147 for (
size_t i = 1; i <= waypoints.size() - 4; ++i) {
153 3 * (waypoints[i + 2].X().value() - waypoints[i].X().value()));
155 3 * (waypoints[i + 2].Y().value() - waypoints[i].Y().value()));
158 dx.emplace_back(3 * (waypoints[waypoints.size() - 1].X().value() -
159 waypoints[waypoints.size() - 3].X().value()) -
161 dy.emplace_back(3 * (waypoints[waypoints.size() - 1].Y().value() -
162 waypoints[waypoints.size() - 3].Y().value()) -
166 ThomasAlgorithm(a, b, c, dx, &fx);
167 ThomasAlgorithm(a, b, c, dy, &fy);
169 fx.emplace(fx.begin(), xInitial[1]);
170 fx.emplace_back(xFinal[1]);
171 fy.emplace(fy.begin(), yInitial[1]);
172 fy.emplace_back(yFinal[1]);
174 for (
size_t i = 0; i < fx.size() - 1; ++i) {
177 {waypoints[i].X().value(), fx[i]},
178 {waypoints[i + 1].X().value(), fx[i + 1]},
179 {waypoints[i].Y().value(), fy[i]},
180 {waypoints[i + 1].Y().value(), fy[i + 1]}};
182 splines.push_back(spline);
184 }
else if (waypoints.size() == 1) {
185 const double xDeriv =
186 (3 * (xFinal[0] - xInitial[0]) - xFinal[1] - xInitial[1]) / 4.0;
187 const double yDeriv =
188 (3 * (yFinal[0] - yInitial[0]) - yFinal[1] - yInitial[1]) / 4.0;
193 splines.emplace_back(xInitial, midXControlVector, yInitial,
195 splines.emplace_back(midXControlVector, xFinal, midYControlVector,
200 const CubicHermiteSpline spline{xInitial, xFinal, yInitial, yFinal};
201 splines.push_back(spline);
218 std::vector<QuinticHermiteSpline> splines;
219 for (
size_t i = 0; i < controlVectors.size() - 1; ++i) {
220 auto& xInitial = controlVectors[i].x;
221 auto& yInitial = controlVectors[i].y;
222 auto& xFinal = controlVectors[i + 1].x;
223 auto& yFinal = controlVectors[i + 1].y;
224 splines.emplace_back(xInitial, xFinal, yInitial, yFinal);
238 const std::vector<QuinticHermiteSpline>& splines) {
241 if (splines.size() < 2) {
254 std::vector<QuinticHermiteSpline> optimizedSplines;
255 optimizedSplines.reserve(splines.size());
256 optimizedSplines.push_back(splines[0]);
258 for (
size_t i = 0; i < splines.size() - 1; ++i) {
259 const auto& a = splines[i];
260 const auto& b = splines[i + 1];
263 const auto& aInitial = a.GetInitialControlVector();
264 const auto& aFinal = a.GetFinalControlVector();
265 const auto& bInitial = b.GetInitialControlVector();
266 const auto& bFinal = b.GetFinalControlVector();
281 double ddxA = combinedA(4);
282 double ddyA = combinedA(5);
283 double ddxB = cb.Coefficients()(4, 1);
284 double ddyB = cb.Coefficients()(5, 1);
288 std::hypot(aFinal.x[0] - aInitial.x[0], aFinal.y[0] - aInitial.y[0]);
290 std::hypot(bFinal.x[0] - bInitial.x[0], bFinal.y[0] - bInitial.y[0]);
291 double alpha = dBC / (dAB + dBC);
292 double beta = dAB / (dAB + dBC);
295 double ddx = alpha * ddxA + beta * ddxB;
296 double ddy = alpha * ddyA + beta * ddyB;
299 optimizedSplines[i] = {aInitial.x,
300 {aFinal.x[0], aFinal.x[1], ddx},
302 {aFinal.y[0], aFinal.y[1], ddy}};
303 optimizedSplines.push_back({{bInitial.x[0], bInitial.x[1], ddx},
305 {bInitial.y[0], bInitial.y[1], ddy},
309 return optimizedSplines;