73 constexpr const char* kMalformedSplineExceptionMsg =
74 "Could not parameterize a malformed spline. This means that you "
75 "probably had two or more adjacent waypoints that were very close "
76 "together with headings in opposing directions.";
77 std::vector<PoseWithCurvature> splinePoints;
80 if (
auto point = spline.
GetPoint(t0)) {
81 splinePoints.push_back(point.value());
88 std::stack<StackContents> stack;
89 stack.emplace(StackContents{t0, t1});
93 while (!stack.empty()) {
94 auto current = stack.top();
97 auto start = spline.
GetPoint(current.t0);
102 auto end = spline.
GetPoint(current.t1);
107 const auto twist = (end.value().first - start.value().first).Log();
109 if (wpi::units::math::abs(twist.dy) > kMaxDy ||
110 wpi::units::math::abs(twist.dx) > kMaxDx ||
111 wpi::units::math::abs(twist.dtheta) > kMaxDtheta) {
112 stack.emplace(StackContents{(current.t0 + current.t1) / 2, current.t1});
113 stack.emplace(StackContents{current.t0, (current.t0 + current.t1) / 2});
115 splinePoints.push_back(end.value());
118 if (iterations++ >= kMaxIterations) {