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