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