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 @SuppressWarnings("MemberName") 050 private static class StackContents { 051 final double t1; 052 final double t0; 053 054 StackContents(double t0, double t1) { 055 this.t0 = t0; 056 this.t1 = t1; 057 } 058 } 059 060 @SuppressWarnings("serial") 061 public static class MalformedSplineException extends RuntimeException { 062 /** 063 * Create a new exception with the given message. 064 * 065 * @param message the message to pass with the exception 066 */ 067 private MalformedSplineException(String message) { 068 super(message); 069 } 070 } 071 072 /** Private constructor because this is a utility class. */ 073 private SplineParameterizer() {} 074 075 /** 076 * Parameterizes the spline. This method breaks up the spline into various arcs until their dx, 077 * dy, and dtheta are within specific tolerances. 078 * 079 * @param spline The spline to parameterize. 080 * @return A list of poses and curvatures that represents various points on the spline. 081 * @throws MalformedSplineException When the spline is malformed (e.g. has close adjacent points 082 * with approximately opposing headings) 083 */ 084 public static List<PoseWithCurvature> parameterize(Spline spline) { 085 return parameterize(spline, 0.0, 1.0); 086 } 087 088 /** 089 * Parameterizes the spline. This method breaks up the spline into various arcs until their dx, 090 * dy, and dtheta are within specific tolerances. 091 * 092 * @param spline The spline to parameterize. 093 * @param t0 Starting internal spline parameter. It is recommended to use 0.0. 094 * @param t1 Ending internal spline parameter. It is recommended to use 1.0. 095 * @return A list of poses and curvatures that represents various points on the spline. 096 * @throws MalformedSplineException When the spline is malformed (e.g. has close adjacent points 097 * with approximately opposing headings) 098 */ 099 public static List<PoseWithCurvature> parameterize(Spline spline, double t0, double t1) { 100 var splinePoints = new ArrayList<PoseWithCurvature>(); 101 102 // The parameterization does not add the initial point. Let's add that. 103 splinePoints.add(spline.getPoint(t0)); 104 105 // We use an "explicit stack" to simulate recursion, instead of a recursive function call 106 // This give us greater control, instead of a stack overflow 107 var stack = new ArrayDeque<StackContents>(); 108 stack.push(new StackContents(t0, t1)); 109 110 StackContents current; 111 PoseWithCurvature start; 112 PoseWithCurvature end; 113 int iterations = 0; 114 115 while (!stack.isEmpty()) { 116 current = stack.removeFirst(); 117 start = spline.getPoint(current.t0); 118 end = spline.getPoint(current.t1); 119 120 final var twist = start.poseMeters.log(end.poseMeters); 121 if (Math.abs(twist.dy) > kMaxDy 122 || Math.abs(twist.dx) > kMaxDx 123 || Math.abs(twist.dtheta) > kMaxDtheta) { 124 stack.addFirst(new StackContents((current.t0 + current.t1) / 2, current.t1)); 125 stack.addFirst(new StackContents(current.t0, (current.t0 + current.t1) / 2)); 126 } else { 127 splinePoints.add(spline.getPoint(current.t1)); 128 } 129 130 iterations++; 131 if (iterations >= kMaxIterations) { 132 throw new MalformedSplineException( 133 "Could not parameterize a malformed spline. This means that you probably had two or " 134 + " more adjacent waypoints that were very close together with headings in " 135 + "opposing directions."); 136 } 137 } 138 139 return splinePoints; 140 } 141}