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 005package edu.wpi.first.math.spline; 006 007import edu.wpi.first.math.geometry.Pose2d; 008import edu.wpi.first.math.geometry.Translation2d; 009import java.util.Arrays; 010import java.util.List; 011 012public final class SplineHelper { 013 /** Private constructor because this is a utility class. */ 014 private SplineHelper() {} 015 016 /** 017 * Returns 2 cubic control vectors from a set of exterior waypoints and interior translations. 018 * 019 * @param start The starting pose. 020 * @param interiorWaypoints The interior waypoints. 021 * @param end The ending pose. 022 * @return 2 cubic control vectors. 023 */ 024 public static Spline.ControlVector[] getCubicControlVectorsFromWaypoints( 025 Pose2d start, Translation2d[] interiorWaypoints, Pose2d end) { 026 // Generate control vectors from poses. 027 Spline.ControlVector initialCV; 028 Spline.ControlVector endCV; 029 030 // Chooses a magnitude automatically that makes the splines look better. 031 if (interiorWaypoints.length < 1) { 032 double scalar = start.getTranslation().getDistance(end.getTranslation()) * 1.2; 033 initialCV = getCubicControlVector(scalar, start); 034 endCV = getCubicControlVector(scalar, end); 035 } else { 036 double scalar = start.getTranslation().getDistance(interiorWaypoints[0]) * 1.2; 037 initialCV = getCubicControlVector(scalar, start); 038 scalar = 039 end.getTranslation().getDistance(interiorWaypoints[interiorWaypoints.length - 1]) * 1.2; 040 endCV = getCubicControlVector(scalar, end); 041 } 042 return new Spline.ControlVector[] {initialCV, endCV}; 043 } 044 045 /** 046 * Returns quintic splines from a set of waypoints. 047 * 048 * @param waypoints The waypoints 049 * @return List of splines. 050 */ 051 public static QuinticHermiteSpline[] getQuinticSplinesFromWaypoints(List<Pose2d> waypoints) { 052 QuinticHermiteSpline[] splines = new QuinticHermiteSpline[waypoints.size() - 1]; 053 for (int i = 0; i < waypoints.size() - 1; ++i) { 054 var p0 = waypoints.get(i); 055 var p1 = waypoints.get(i + 1); 056 057 // This just makes the splines look better. 058 final var scalar = 1.2 * p0.getTranslation().getDistance(p1.getTranslation()); 059 060 var controlVecA = getQuinticControlVector(scalar, p0); 061 var controlVecB = getQuinticControlVector(scalar, p1); 062 063 splines[i] = 064 new QuinticHermiteSpline(controlVecA.x, controlVecB.x, controlVecA.y, controlVecB.y); 065 } 066 return splines; 067 } 068 069 /** 070 * Returns a set of cubic splines corresponding to the provided control vectors. The user is free 071 * to set the direction of the start and end point. The directions for the middle waypoints are 072 * determined automatically to ensure continuous curvature throughout the path. 073 * 074 * @param start The starting control vector. 075 * @param waypoints The middle waypoints. This can be left blank if you only wish to create a path 076 * with two waypoints. 077 * @param end The ending control vector. 078 * @return A vector of cubic hermite splines that interpolate through the provided waypoints and 079 * control vectors. 080 */ 081 @SuppressWarnings("LocalVariableName") 082 public static CubicHermiteSpline[] getCubicSplinesFromControlVectors( 083 Spline.ControlVector start, Translation2d[] waypoints, Spline.ControlVector end) { 084 CubicHermiteSpline[] splines = new CubicHermiteSpline[waypoints.length + 1]; 085 086 double[] xInitial = start.x; 087 double[] yInitial = start.y; 088 double[] xFinal = end.x; 089 double[] yFinal = end.y; 090 091 if (waypoints.length > 1) { 092 Translation2d[] newWaypts = new Translation2d[waypoints.length + 2]; 093 094 // Create an array of all waypoints, including the start and end. 095 newWaypts[0] = new Translation2d(xInitial[0], yInitial[0]); 096 System.arraycopy(waypoints, 0, newWaypts, 1, waypoints.length); 097 newWaypts[newWaypts.length - 1] = new Translation2d(xFinal[0], yFinal[0]); 098 099 // Populate tridiagonal system for clamped cubic 100 /* See: 101 https://www.uio.no/studier/emner/matnat/ifi/nedlagte-emner/INF-MAT4350/h08 102 /undervisningsmateriale/chap7alecture.pdf 103 */ 104 // Above-diagonal of tridiagonal matrix, zero-padded 105 final double[] a = new double[newWaypts.length - 2]; 106 107 // Diagonal of tridiagonal matrix 108 final double[] b = new double[newWaypts.length - 2]; 109 Arrays.fill(b, 4.0); 110 111 // Below-diagonal of tridiagonal matrix, zero-padded 112 final double[] c = new double[newWaypts.length - 2]; 113 114 // rhs vectors 115 final double[] dx = new double[newWaypts.length - 2]; 116 final double[] dy = new double[newWaypts.length - 2]; 117 118 // solution vectors 119 final double[] fx = new double[newWaypts.length - 2]; 120 final double[] fy = new double[newWaypts.length - 2]; 121 122 // populate above-diagonal and below-diagonal vectors 123 a[0] = 0.0; 124 for (int i = 0; i < newWaypts.length - 3; i++) { 125 a[i + 1] = 1; 126 c[i] = 1; 127 } 128 c[c.length - 1] = 0.0; 129 130 // populate rhs vectors 131 dx[0] = 3 * (newWaypts[2].getX() - newWaypts[0].getX()) - xInitial[1]; 132 dy[0] = 3 * (newWaypts[2].getY() - newWaypts[0].getY()) - yInitial[1]; 133 134 if (newWaypts.length > 4) { 135 for (int i = 1; i <= newWaypts.length - 4; i++) { 136 // dx and dy represent the derivatives of the internal waypoints. The derivative 137 // of the second internal waypoint should involve the third and first internal waypoint, 138 // which have indices of 1 and 3 in the newWaypts list (which contains ALL waypoints). 139 dx[i] = 3 * (newWaypts[i + 2].getX() - newWaypts[i].getX()); 140 dy[i] = 3 * (newWaypts[i + 2].getY() - newWaypts[i].getY()); 141 } 142 } 143 144 dx[dx.length - 1] = 145 3 * (newWaypts[newWaypts.length - 1].getX() - newWaypts[newWaypts.length - 3].getX()) 146 - xFinal[1]; 147 dy[dy.length - 1] = 148 3 * (newWaypts[newWaypts.length - 1].getY() - newWaypts[newWaypts.length - 3].getY()) 149 - yFinal[1]; 150 151 // Compute solution to tridiagonal system 152 thomasAlgorithm(a, b, c, dx, fx); 153 thomasAlgorithm(a, b, c, dy, fy); 154 155 double[] newFx = new double[fx.length + 2]; 156 double[] newFy = new double[fy.length + 2]; 157 158 newFx[0] = xInitial[1]; 159 newFy[0] = yInitial[1]; 160 System.arraycopy(fx, 0, newFx, 1, fx.length); 161 System.arraycopy(fy, 0, newFy, 1, fy.length); 162 newFx[newFx.length - 1] = xFinal[1]; 163 newFy[newFy.length - 1] = yFinal[1]; 164 165 for (int i = 0; i < newFx.length - 1; i++) { 166 splines[i] = 167 new CubicHermiteSpline( 168 new double[] {newWaypts[i].getX(), newFx[i]}, 169 new double[] {newWaypts[i + 1].getX(), newFx[i + 1]}, 170 new double[] {newWaypts[i].getY(), newFy[i]}, 171 new double[] {newWaypts[i + 1].getY(), newFy[i + 1]}); 172 } 173 } else if (waypoints.length == 1) { 174 final var xDeriv = (3 * (xFinal[0] - xInitial[0]) - xFinal[1] - xInitial[1]) / 4.0; 175 final var yDeriv = (3 * (yFinal[0] - yInitial[0]) - yFinal[1] - yInitial[1]) / 4.0; 176 177 double[] midXControlVector = {waypoints[0].getX(), xDeriv}; 178 double[] midYControlVector = {waypoints[0].getY(), yDeriv}; 179 180 splines[0] = 181 new CubicHermiteSpline( 182 xInitial, midXControlVector, 183 yInitial, midYControlVector); 184 splines[1] = 185 new CubicHermiteSpline( 186 midXControlVector, xFinal, 187 midYControlVector, yFinal); 188 } else { 189 splines[0] = 190 new CubicHermiteSpline( 191 xInitial, xFinal, 192 yInitial, yFinal); 193 } 194 return splines; 195 } 196 197 /** 198 * Returns a set of quintic splines corresponding to the provided control vectors. The user is 199 * free to set the direction of all control vectors. Continuous curvature is guaranteed throughout 200 * the path. 201 * 202 * @param controlVectors The control vectors. 203 * @return A vector of quintic hermite splines that interpolate through the provided waypoints. 204 */ 205 @SuppressWarnings("LocalVariableName") 206 public static QuinticHermiteSpline[] getQuinticSplinesFromControlVectors( 207 Spline.ControlVector[] controlVectors) { 208 QuinticHermiteSpline[] splines = new QuinticHermiteSpline[controlVectors.length - 1]; 209 for (int i = 0; i < controlVectors.length - 1; i++) { 210 var xInitial = controlVectors[i].x; 211 var xFinal = controlVectors[i + 1].x; 212 var yInitial = controlVectors[i].y; 213 var yFinal = controlVectors[i + 1].y; 214 splines[i] = 215 new QuinticHermiteSpline( 216 xInitial, xFinal, 217 yInitial, yFinal); 218 } 219 return splines; 220 } 221 222 /** 223 * Thomas algorithm for solving tridiagonal systems Af = d. 224 * 225 * @param a the values of A above the diagonal 226 * @param b the values of A on the diagonal 227 * @param c the values of A below the diagonal 228 * @param d the vector on the rhs 229 * @param solutionVector the unknown (solution) vector, modified in-place 230 */ 231 @SuppressWarnings({"ParameterName", "LocalVariableName"}) 232 private static void thomasAlgorithm( 233 double[] a, double[] b, double[] c, double[] d, double[] solutionVector) { 234 int N = d.length; 235 236 double[] cStar = new double[N]; 237 double[] dStar = new double[N]; 238 239 // This updates the coefficients in the first row 240 // Note that we should be checking for division by zero here 241 cStar[0] = c[0] / b[0]; 242 dStar[0] = d[0] / b[0]; 243 244 // Create the c_star and d_star coefficients in the forward sweep 245 for (int i = 1; i < N; i++) { 246 double m = 1.0 / (b[i] - a[i] * cStar[i - 1]); 247 cStar[i] = c[i] * m; 248 dStar[i] = (d[i] - a[i] * dStar[i - 1]) * m; 249 } 250 solutionVector[N - 1] = dStar[N - 1]; 251 // This is the reverse sweep, used to update the solution vector f 252 for (int i = N - 2; i >= 0; i--) { 253 solutionVector[i] = dStar[i] - cStar[i] * solutionVector[i + 1]; 254 } 255 } 256 257 private static Spline.ControlVector getCubicControlVector(double scalar, Pose2d point) { 258 return new Spline.ControlVector( 259 new double[] {point.getX(), scalar * point.getRotation().getCos()}, 260 new double[] {point.getY(), scalar * point.getRotation().getSin()}); 261 } 262 263 private static Spline.ControlVector getQuinticControlVector(double scalar, Pose2d point) { 264 return new Spline.ControlVector( 265 new double[] {point.getX(), scalar * point.getRotation().getCos(), 0.0}, 266 new double[] {point.getY(), scalar * point.getRotation().getSin(), 0.0}); 267 } 268}