001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005/*
006 * MIT License
007 *
008 * Copyright (c) 2018 Team 254
009 *
010 * Permission is hereby granted, free of charge, to any person obtaining a copy
011 * of this software and associated documentation files (the "Software"), to deal
012 * in the Software without restriction, including without limitation the rights
013 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
014 * copies of the Software, and to permit persons to whom the Software is
015 * furnished to do so, subject to the following conditions:
016 *
017 * The above copyright notice and this permission notice shall be included in all
018 * copies or substantial portions of the Software.
019 *
020 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
021 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
022 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
023 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
024 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
025 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
026 * SOFTWARE.
027 */
028
029package edu.wpi.first.math.spline;
030
031import java.util.ArrayDeque;
032import java.util.ArrayList;
033import java.util.List;
034
035/** Class used to parameterize a spline by its arc length. */
036public final class SplineParameterizer {
037  private static final double kMaxDx = 0.127;
038  private static final double kMaxDy = 0.00127;
039  private static final double kMaxDtheta = 0.0872;
040
041  /**
042   * A malformed spline does not actually explode the LIFO stack size. Instead, the stack size stays
043   * at a relatively small number (e.g. 30) and never decreases. Because of this, we must count
044   * iterations. Even long, complex paths don't usually go over 300 iterations, so hitting this
045   * maximum should definitely indicate something has gone wrong.
046   */
047  private static final int kMaxIterations = 5000;
048
049  private static class StackContents {
050    final double t1;
051    final double t0;
052
053    StackContents(double t0, double t1) {
054      this.t0 = t0;
055      this.t1 = t1;
056    }
057  }
058
059  public static class MalformedSplineException extends RuntimeException {
060    /**
061     * Create a new exception with the given message.
062     *
063     * @param message the message to pass with the exception
064     */
065    private MalformedSplineException(String message) {
066      super(message);
067    }
068  }
069
070  /** Private constructor because this is a utility class. */
071  private SplineParameterizer() {}
072
073  /**
074   * Parametrizes the spline. This method breaks up the spline into various arcs until their dx, dy,
075   * and dtheta are within specific tolerances.
076   *
077   * @param spline The spline to parameterize.
078   * @return A list of poses and curvatures that represents various points on the spline.
079   * @throws MalformedSplineException When the spline is malformed (e.g. has close adjacent points
080   *     with approximately opposing headings)
081   */
082  public static List<PoseWithCurvature> parameterize(Spline spline) {
083    return parameterize(spline, 0.0, 1.0);
084  }
085
086  /**
087   * Parametrizes the spline. This method breaks up the spline into various arcs until their dx, dy,
088   * and dtheta are within specific tolerances.
089   *
090   * @param spline The spline to parameterize.
091   * @param t0 Starting internal spline parameter. It is recommended to use 0.0.
092   * @param t1 Ending internal spline parameter. It is recommended to use 1.0.
093   * @return A list of poses and curvatures that represents various points on the spline.
094   * @throws MalformedSplineException When the spline is malformed (e.g. has close adjacent points
095   *     with approximately opposing headings)
096   */
097  public static List<PoseWithCurvature> parameterize(Spline spline, double t0, double t1) {
098    var splinePoints = new ArrayList<PoseWithCurvature>();
099
100    // The parameterization does not add the initial point. Let's add that.
101    splinePoints.add(spline.getPoint(t0));
102
103    // We use an "explicit stack" to simulate recursion, instead of a recursive function call
104    // This give us greater control, instead of a stack overflow
105    var stack = new ArrayDeque<StackContents>();
106    stack.push(new StackContents(t0, t1));
107
108    StackContents current;
109    PoseWithCurvature start;
110    PoseWithCurvature end;
111    int iterations = 0;
112
113    while (!stack.isEmpty()) {
114      current = stack.removeFirst();
115      start = spline.getPoint(current.t0);
116      end = spline.getPoint(current.t1);
117
118      final var twist = start.poseMeters.log(end.poseMeters);
119      if (Math.abs(twist.dy) > kMaxDy
120          || Math.abs(twist.dx) > kMaxDx
121          || Math.abs(twist.dtheta) > kMaxDtheta) {
122        stack.addFirst(new StackContents((current.t0 + current.t1) / 2, current.t1));
123        stack.addFirst(new StackContents(current.t0, (current.t0 + current.t1) / 2));
124      } else {
125        splinePoints.add(spline.getPoint(current.t1));
126      }
127
128      iterations++;
129      if (iterations >= kMaxIterations) {
130        throw new MalformedSplineException(
131            "Could not parameterize a malformed spline. This means that you probably had two or "
132                + " more adjacent waypoints that were very close together with headings in "
133                + "opposing directions.");
134      }
135    }
136
137    return splinePoints;
138  }
139}