/*----------------------------------------------------------------------------*/ /* Copyright (c) 2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ /*----------------------------------------------------------------------------*/ #include "frc/spline/SplineHelper.h" #include using namespace frc; std::vector SplineHelper::CubicSplinesFromWaypoints( const Pose2d& start, std::vector waypoints, const Pose2d& end) { std::vector splines; double scalar; // This just makes the splines look better. if (waypoints.empty()) { scalar = 1.2 * start.Translation().Distance(end.Translation()).to(); } else { scalar = 1.2 * start.Translation().Distance(waypoints.front()).to(); } std::array startXControlVector{ start.Translation().X().to(), start.Rotation().Cos() * scalar}; std::array startYControlVector{ start.Translation().Y().to(), start.Rotation().Sin() * scalar}; // This just makes the splines look better. if (!waypoints.empty()) { scalar = 1.2 * end.Translation().Distance(waypoints.back()).to(); } std::array endXControlVector{end.Translation().X().to(), end.Rotation().Cos() * scalar}; std::array endYControlVector{end.Translation().Y().to(), end.Rotation().Sin() * scalar}; if (waypoints.size() > 1) { waypoints.emplace(waypoints.begin(), start.Translation()); waypoints.emplace_back(end.Translation()); std::vector a; std::vector b(waypoints.size() - 2, 4.0); std::vector c; std::vector dx, dy; std::vector fx(waypoints.size() - 2, 0.0), fy(waypoints.size() - 2, 0.0); a.emplace_back(0); for (unsigned int i = 0; i < waypoints.size() - 3; i++) { a.emplace_back(1); c.emplace_back(1); } c.emplace_back(0); dx.emplace_back( 3 * (waypoints[2].X().to() - waypoints[0].X().to()) - startXControlVector[1]); dy.emplace_back( 3 * (waypoints[2].Y().to() - waypoints[0].Y().to()) - startYControlVector[1]); if (waypoints.size() > 4) { for (unsigned int i = 1; i <= waypoints.size() - 4; i++) { dx.emplace_back(3 * (waypoints[i + 1].X().to() - waypoints[i - 1].X().to())); dy.emplace_back(3 * (waypoints[i + 1].Y().to() - waypoints[i - 1].Y().to())); } } dx.emplace_back(3 * (waypoints[waypoints.size() - 1].X().to() - waypoints[waypoints.size() - 3].X().to()) - endXControlVector[1]); dy.emplace_back(3 * (waypoints[waypoints.size() - 1].Y().to() - waypoints[waypoints.size() - 3].Y().to()) - endYControlVector[1]); ThomasAlgorithm(a, b, c, dx, &fx); ThomasAlgorithm(a, b, c, dy, &fy); fx.emplace(fx.begin(), startXControlVector[1]); fx.emplace_back(endXControlVector[1]); fy.emplace(fy.begin(), startYControlVector[1]); fy.emplace_back(endYControlVector[1]); for (unsigned int i = 0; i < fx.size() - 1; i++) { // Create the spline. const CubicHermiteSpline spline{ {waypoints[i].X().to(), fx[i]}, {waypoints[i + 1].X().to(), fx[i + 1]}, {waypoints[i].Y().to(), fy[i]}, {waypoints[i + 1].Y().to(), fy[i + 1]}}; splines.push_back(spline); } } else if (waypoints.size() == 1) { const double xDeriv = (3 * (end.Translation().X().to() - start.Translation().X().to()) - endXControlVector[1] - startXControlVector[1]) / 4.0; const double yDeriv = (3 * (end.Translation().Y().to() - start.Translation().Y().to()) - endYControlVector[1] - startYControlVector[1]) / 4.0; std::array midXControlVector{waypoints[0].X().to(), xDeriv}; std::array midYControlVector{waypoints[0].Y().to(), yDeriv}; splines.emplace_back(startXControlVector, midXControlVector, startYControlVector, midYControlVector); splines.emplace_back(midXControlVector, endXControlVector, midYControlVector, endYControlVector); } else { // Create the spline. const CubicHermiteSpline spline{startXControlVector, endXControlVector, startYControlVector, endYControlVector}; splines.push_back(spline); } return splines; } std::vector SplineHelper::QuinticSplinesFromWaypoints( const std::vector& waypoints) { std::vector splines; for (unsigned int i = 0; i < waypoints.size() - 1; i++) { auto& p0 = waypoints[i]; auto& p1 = waypoints[i + 1]; // This just makes the splines look better. const auto scalar = 1.2 * p0.Translation().Distance(p1.Translation()).to(); const std::array xInitialControlVector{ p0.Translation().X().to(), p0.Rotation().Cos() * scalar, 0.0}; const std::array xFinalControlVector{ p1.Translation().X().to(), p1.Rotation().Cos() * scalar, 0.0}; const std::array yInitialControlVector{ p0.Translation().Y().to(), p0.Rotation().Sin() * scalar, 0.0}; const std::array yFinalControlVector{ p1.Translation().Y().to(), p1.Rotation().Sin() * scalar, 0.0}; splines.emplace_back(xInitialControlVector, xFinalControlVector, yInitialControlVector, yFinalControlVector); } return splines; } void SplineHelper::ThomasAlgorithm(const std::vector& a, const std::vector& b, const std::vector& c, const std::vector& d, std::vector* solutionVector) { auto& f = *solutionVector; size_t N = d.size(); // Create the temporary vectors // Note that this is inefficient as it is possible to call // this function many times. A better implementation would // pass these temporary matrices by non-const reference to // save excess allocation and deallocation std::vector c_star(N, 0.0); std::vector d_star(N, 0.0); // This updates the coefficients in the first row // Note that we should be checking for division by zero here c_star[0] = c[0] / b[0]; d_star[0] = d[0] / b[0]; // Create the c_star and d_star coefficients in the forward sweep for (unsigned int i = 1; i < N; i++) { double m = 1.0 / (b[i] - a[i] * c_star[i - 1]); c_star[i] = c[i] * m; d_star[i] = (d[i] - a[i] * d_star[i - 1]) * m; } f[N - 1] = d_star[N - 1]; // This is the reverse sweep, used to update the solution vector f for (int i = N - 2; i >= 0; i--) { f[i] = d_star[i] - c_star[i] * f[i + 1]; } }