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; 006 007import edu.wpi.first.math.geometry.Translation2d; 008import edu.wpi.first.math.geometry.Translation3d; 009 010/** Math utility functions. */ 011public final class MathUtil { 012 private MathUtil() { 013 throw new AssertionError("utility class"); 014 } 015 016 /** 017 * Computes the linear interpolation between a and b if t ∈ [0, 1) and the linear extrapolation 018 * otherwise. 019 * 020 * @param a The start value. 021 * @param b The end value. 022 * @param t The fraction for interpolation. 023 * @return The interpolated value. 024 */ 025 public static double lerp(double a, double b, double t) { 026 return a + (b - a) * t; 027 } 028 029 /** 030 * Returns the interpolant t that reflects where q is with respect to the range (a, b). In other 031 * words, returns t such that q = a + (b - a)t. If a = b, then returns 0. 032 * 033 * @param a Lower part of interpolation range. 034 * @param b Upper part of interpolation range. 035 * @param q Query. 036 * @return Interpolant. 037 */ 038 public static double inverseLerp(double a, double b, double q) { 039 // q = a + (b − a)t 040 // (b − a)t = q − a 041 // t = (q − a)/(b − a) 042 if (Math.abs(a - b) < 1e-9) { 043 return 0.0; 044 } else { 045 return (q - a) / (b - a); 046 } 047 } 048 049 /** 050 * Returns 0.0 if the given value is within the specified range around zero. The remaining range 051 * between the deadband and the maximum magnitude is scaled from 0.0 to the maximum magnitude. 052 * 053 * @param value Value to clip. 054 * @param deadband Range around zero. 055 * @param maxMagnitude The maximum magnitude of the input. Can be infinite. 056 * @return The value after the deadband is applied. 057 */ 058 public static double applyDeadband(double value, double deadband, double maxMagnitude) { 059 if (Math.abs(value) < deadband) { 060 return 0; 061 } 062 if (value > 0.0) { 063 // Map deadband to 0 and map max to max with a linear relationship. 064 // 065 // y - y₁ = m(x - x₁) 066 // y - y₁ = (y₂ - y₁)/(x₂ - x₁) (x - x₁) 067 // y = (y₂ - y₁)/(x₂ - x₁) (x - x₁) + y₁ 068 // 069 // (x₁, y₁) = (deadband, 0) and (x₂, y₂) = (max, max). 070 // 071 // x₁ = deadband 072 // y₁ = 0 073 // x₂ = max 074 // y₂ = max 075 // y = (max - 0)/(max - deadband) (x - deadband) + 0 076 // y = max/(max - deadband) (x - deadband) 077 // 078 // To handle high values of max, rewrite so that max only appears on the denominator. 079 // 080 // y = ((max - deadband) + deadband)/(max - deadband) (x - deadband) 081 // y = (1 + deadband/(max - deadband)) (x - deadband) 082 return (1 + deadband / (maxMagnitude - deadband)) * (value - deadband); 083 } else { 084 // Map -deadband to 0 and map -max to -max with a linear relationship. 085 // 086 // y - y₁ = m(x - x₁) 087 // y - y₁ = (y₂ - y₁)/(x₂ - x₁) (x - x₁) 088 // y = (y₂ - y₁)/(x₂ - x₁) (x - x₁) + y₁ 089 // 090 // (x₁, y₁) = (-deadband, 0) and (x₂, y₂) = (-max, -max). 091 // 092 // x₁ = -deadband 093 // y₁ = 0 094 // x₂ = -max 095 // y₂ = -max 096 // y = (-max - 0)/(-max + deadband) (x + deadband) + 0 097 // y = max/(max - deadband) (x + deadband) 098 // 099 // To handle high values of max, rewrite so that max only appears on the denominator. 100 // 101 // y = ((max - deadband) + deadband)/(max - deadband) (x + deadband) 102 // y = (1 + deadband/(max - deadband)) (x + deadband) 103 return (1 + deadband / (maxMagnitude - deadband)) * (value + deadband); 104 } 105 } 106 107 /** 108 * Returns 0.0 if the given value is within the specified range around zero. The remaining range 109 * between the deadband and 1.0 is scaled from 0.0 to 1.0. 110 * 111 * @param value Value to clip. 112 * @param deadband Range around zero. 113 * @return The value after the deadband is applied. 114 */ 115 public static double applyDeadband(double value, double deadband) { 116 return applyDeadband(value, deadband, 1); 117 } 118 119 /** 120 * Returns a zero vector if the given vector is within the specified distance from the origin. The 121 * remaining distance between the deadband and the maximum distance is scaled from the origin to 122 * the maximum distance. 123 * 124 * @param value Value to clip. 125 * @param deadband Distance from origin. 126 * @param maxMagnitude The maximum distance from the origin of the input. Can be infinite. 127 * @param <R> The number of rows in the vector. 128 * @return The value after the deadband is applied. 129 */ 130 public static <R extends Num> Vector<R> applyDeadband( 131 Vector<R> value, double deadband, double maxMagnitude) { 132 if (value.norm() < 1e-9) { 133 return value.times(0); 134 } 135 return value.unit().times(applyDeadband(value.norm(), deadband, maxMagnitude)); 136 } 137 138 /** 139 * Returns a zero vector if the given vector is within the specified distance from the origin. The 140 * remaining distance between the deadband and a distance of 1.0 is scaled from the origin to a 141 * distance of 1.0. 142 * 143 * @param value Value to clip. 144 * @param deadband Distance from origin. 145 * @param <R> The number of rows in the vector. 146 * @return The value after the deadband is applied. 147 */ 148 public static <R extends Num> Vector<R> applyDeadband(Vector<R> value, double deadband) { 149 return applyDeadband(value, deadband, 1); 150 } 151 152 /** 153 * Raises the input to the power of the given exponent while preserving its sign. 154 * 155 * <p>The function normalizes the input value to the range [0, 1] based on the maximum magnitude, 156 * raises it to the power of the exponent, then scales the result back to the original range and 157 * copying the sign. This keeps the value in the original range and gives consistent curve 158 * behavior regardless of the input value's scale. 159 * 160 * <p>This is useful for applying smoother or more aggressive control response curves (e.g. 161 * joystick input shaping). 162 * 163 * @param value The input value to transform. 164 * @param exponent The exponent to apply (e.g. 1.0 = linear, 2.0 = squared curve). Must be 165 * positive. 166 * @param maxMagnitude The maximum expected absolute value of input. Must be positive. 167 * @return The transformed value with the same sign and scaled to the input range. 168 */ 169 public static double copyDirectionPow(double value, double exponent, double maxMagnitude) { 170 return Math.copySign(Math.pow(Math.abs(value) / maxMagnitude, exponent), value) * maxMagnitude; 171 } 172 173 /** 174 * Raises the input to the power of the given exponent while preserving its sign. 175 * 176 * <p>This is useful for applying smoother or more aggressive control response curves (e.g. 177 * joystick input shaping). 178 * 179 * @param value The input value to transform. 180 * @param exponent The exponent to apply (e.g. 1.0 = linear, 2.0 = squared curve). Must be 181 * positive. 182 * @return The transformed value with the same sign. 183 */ 184 public static double copyDirectionPow(double value, double exponent) { 185 return copyDirectionPow(value, exponent, 1); 186 } 187 188 /** 189 * Raises the norm of the input to the power of the given exponent while preserving its direction. 190 * 191 * <p>The function normalizes the norm of the input to the range [0, 1] based on the maximum 192 * distance, raises it to the power of the exponent, then scales the result back to the original 193 * range. This keeps the value in the original max distance and gives consistent curve behavior 194 * regardless of the input norm's scale. 195 * 196 * @param value The input vector to transform. 197 * @param exponent The exponent to apply (e.g. 1.0 = linear, 2.0 = squared curve). Must be 198 * positive. 199 * @param maxMagnitude The maximum expected distance from origin of input. Must be positive. 200 * @param <R> The number of rows in the vector. 201 * @return The transformed value with the same direction and norm scaled to the input range. 202 */ 203 public static <R extends Num> Vector<R> copyDirectionPow( 204 Vector<R> value, double exponent, double maxMagnitude) { 205 if (value.norm() < 1e-9) { 206 return value.times(0); 207 } 208 return value.unit().times(copyDirectionPow(value.norm(), exponent, maxMagnitude)); 209 } 210 211 /** 212 * Raises the norm of the input to the power of the given exponent while preserving its direction. 213 * 214 * @param value The input vector to transform. 215 * @param exponent The exponent to apply (e.g. 1.0 = linear, 2.0 = squared curve). Must be 216 * positive. 217 * @param <R> The number of rows in the vector. 218 * @return The transformed value with the same direction. 219 */ 220 public static <R extends Num> Vector<R> copyDirectionPow(Vector<R> value, double exponent) { 221 return copyDirectionPow(value, exponent, 1); 222 } 223 224 /** 225 * Returns modulus of input. 226 * 227 * @param input Input value to wrap. 228 * @param minimumInput The minimum value expected from the input. 229 * @param maximumInput The maximum value expected from the input. 230 * @return The wrapped value. 231 */ 232 public static double inputModulus(double input, double minimumInput, double maximumInput) { 233 double modulus = maximumInput - minimumInput; 234 235 // Wrap input if it's above the maximum input 236 int numMax = (int) ((input - minimumInput) / modulus); 237 input -= numMax * modulus; 238 239 // Wrap input if it's below the minimum input 240 int numMin = (int) ((input - maximumInput) / modulus); 241 input -= numMin * modulus; 242 243 return input; 244 } 245 246 /** 247 * Wraps an angle to the range -π to π radians. 248 * 249 * @param angleRadians Angle to wrap in radians. 250 * @return The wrapped angle. 251 */ 252 public static double angleModulus(double angleRadians) { 253 return inputModulus(angleRadians, -Math.PI, Math.PI); 254 } 255 256 /** 257 * Checks if the given value matches an expected value within a certain tolerance. 258 * 259 * @param expected The expected value 260 * @param actual The actual value 261 * @param tolerance The allowed difference between the actual and the expected value 262 * @return Whether or not the actual value is within the allowed tolerance 263 */ 264 public static boolean isNear(double expected, double actual, double tolerance) { 265 if (tolerance < 0) { 266 throw new IllegalArgumentException("Tolerance must be a non-negative number!"); 267 } 268 return Math.abs(expected - actual) < tolerance; 269 } 270 271 /** 272 * Checks if the given value matches an expected value within a certain tolerance. Supports 273 * continuous input for cases like absolute encoders. 274 * 275 * <p>Continuous input means that the min and max value are considered to be the same point, and 276 * tolerances can be checked across them. A common example would be for absolute encoders: calling 277 * isNear(2, 359, 5, 0, 360) returns true because 359 is 1 away from 360 (which is treated as the 278 * same as 0) and 2 is 2 away from 0, adding up to an error of 3 degrees, which is within the 279 * given tolerance of 5. 280 * 281 * @param expected The expected value 282 * @param actual The actual value 283 * @param tolerance The allowed difference between the actual and the expected value 284 * @param min Smallest value before wrapping around to the largest value 285 * @param max Largest value before wrapping around to the smallest value 286 * @return Whether or not the actual value is within the allowed tolerance 287 */ 288 public static boolean isNear( 289 double expected, double actual, double tolerance, double min, double max) { 290 if (tolerance < 0) { 291 throw new IllegalArgumentException("Tolerance must be a non-negative number!"); 292 } 293 // Max error is exactly halfway between the min and max 294 double errorBound = (max - min) / 2.0; 295 double error = MathUtil.inputModulus(expected - actual, -errorBound, errorBound); 296 return Math.abs(error) < tolerance; 297 } 298 299 /** 300 * Limits translation velocity. 301 * 302 * @param current Translation at current timestep. 303 * @param next Translation at next timestep. 304 * @param dt Timestep duration. 305 * @param maxVelocity Maximum translation velocity. 306 * @return Returns the next Translation2d limited to maxVelocity 307 */ 308 public static Translation2d slewRateLimit( 309 Translation2d current, Translation2d next, double dt, double maxVelocity) { 310 if (maxVelocity < 0) { 311 Exception e = new IllegalArgumentException(); 312 MathSharedStore.reportError( 313 "maxVelocity must be a non-negative number, got " + maxVelocity, e.getStackTrace()); 314 return next; 315 } 316 Translation2d diff = next.minus(current); 317 double dist = diff.getNorm(); 318 if (dist < 1e-9) { 319 return next; 320 } 321 if (dist > maxVelocity * dt) { 322 // Move maximum allowed amount in direction of the difference 323 return current.plus(diff.times(maxVelocity * dt / dist)); 324 } 325 return next; 326 } 327 328 /** 329 * Limits translation velocity. 330 * 331 * @param current Translation at current timestep. 332 * @param next Translation at next timestep. 333 * @param dt Timestep duration. 334 * @param maxVelocity Maximum translation velocity. 335 * @return Returns the next Translation3d limited to maxVelocity 336 */ 337 public static Translation3d slewRateLimit( 338 Translation3d current, Translation3d next, double dt, double maxVelocity) { 339 if (maxVelocity < 0) { 340 Exception e = new IllegalArgumentException(); 341 MathSharedStore.reportError( 342 "maxVelocity must be a non-negative number, got " + maxVelocity, e.getStackTrace()); 343 return next; 344 } 345 Translation3d diff = next.minus(current); 346 double dist = diff.getNorm(); 347 if (dist < 1e-9) { 348 return next; 349 } 350 if (dist > maxVelocity * dt) { 351 // Move maximum allowed amount in direction of the difference 352 return current.plus(diff.times(maxVelocity * dt / dist)); 353 } 354 return next; 355 } 356}