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
007/** Math utility functions. */
008public final class MathUtil {
009  private MathUtil() {
010    throw new AssertionError("utility class");
011  }
012
013  /**
014   * Returns value clamped between low and high boundaries.
015   *
016   * @param value Value to clamp.
017   * @param low The lower boundary to which to clamp value.
018   * @param high The higher boundary to which to clamp value.
019   * @return The clamped value.
020   */
021  public static int clamp(int value, int low, int high) {
022    return Math.max(low, Math.min(value, high));
023  }
024
025  /**
026   * Returns value clamped between low and high boundaries.
027   *
028   * @param value Value to clamp.
029   * @param low The lower boundary to which to clamp value.
030   * @param high The higher boundary to which to clamp value.
031   * @return The clamped value.
032   */
033  public static double clamp(double value, double low, double high) {
034    return Math.max(low, Math.min(value, high));
035  }
036
037  /**
038   * Returns 0.0 if the given value is within the specified range around zero. The remaining range
039   * between the deadband and the maximum magnitude is scaled from 0.0 to the maximum magnitude.
040   *
041   * @param value Value to clip.
042   * @param deadband Range around zero.
043   * @param maxMagnitude The maximum magnitude of the input. Can be infinite.
044   * @return The value after the deadband is applied.
045   */
046  public static double applyDeadband(double value, double deadband, double maxMagnitude) {
047    if (Math.abs(value) > deadband) {
048      if (maxMagnitude / deadband > 1.0e12) {
049        // If max magnitude is sufficiently large, the implementation encounters
050        // roundoff error.  Implementing the limiting behavior directly avoids
051        // the problem.
052        return value > 0.0 ? value - deadband : value + deadband;
053      }
054      if (value > 0.0) {
055        // Map deadband to 0 and map max to max.
056        //
057        // y - y₁ = m(x - x₁)
058        // y - y₁ = (y₂ - y₁)/(x₂ - x₁) (x - x₁)
059        // y = (y₂ - y₁)/(x₂ - x₁) (x - x₁) + y₁
060        //
061        // (x₁, y₁) = (deadband, 0) and (x₂, y₂) = (max, max).
062        // x₁ = deadband
063        // y₁ = 0
064        // x₂ = max
065        // y₂ = max
066        //
067        // y = (max - 0)/(max - deadband) (x - deadband) + 0
068        // y = max/(max - deadband) (x - deadband)
069        // y = max (x - deadband)/(max - deadband)
070        return maxMagnitude * (value - deadband) / (maxMagnitude - deadband);
071      } else {
072        // Map -deadband to 0 and map -max to -max.
073        //
074        // y - y₁ = m(x - x₁)
075        // y - y₁ = (y₂ - y₁)/(x₂ - x₁) (x - x₁)
076        // y = (y₂ - y₁)/(x₂ - x₁) (x - x₁) + y₁
077        //
078        // (x₁, y₁) = (-deadband, 0) and (x₂, y₂) = (-max, -max).
079        // x₁ = -deadband
080        // y₁ = 0
081        // x₂ = -max
082        // y₂ = -max
083        //
084        // y = (-max - 0)/(-max + deadband) (x + deadband) + 0
085        // y = max/(max - deadband) (x + deadband)
086        // y = max (x + deadband)/(max - deadband)
087        return maxMagnitude * (value + deadband) / (maxMagnitude - deadband);
088      }
089    } else {
090      return 0.0;
091    }
092  }
093
094  /**
095   * Returns 0.0 if the given value is within the specified range around zero. The remaining range
096   * between the deadband and 1.0 is scaled from 0.0 to 1.0.
097   *
098   * @param value Value to clip.
099   * @param deadband Range around zero.
100   * @return The value after the deadband is applied.
101   */
102  public static double applyDeadband(double value, double deadband) {
103    return applyDeadband(value, deadband, 1);
104  }
105
106  /**
107   * Returns modulus of input.
108   *
109   * @param input Input value to wrap.
110   * @param minimumInput The minimum value expected from the input.
111   * @param maximumInput The maximum value expected from the input.
112   * @return The wrapped value.
113   */
114  public static double inputModulus(double input, double minimumInput, double maximumInput) {
115    double modulus = maximumInput - minimumInput;
116
117    // Wrap input if it's above the maximum input
118    int numMax = (int) ((input - minimumInput) / modulus);
119    input -= numMax * modulus;
120
121    // Wrap input if it's below the minimum input
122    int numMin = (int) ((input - maximumInput) / modulus);
123    input -= numMin * modulus;
124
125    return input;
126  }
127
128  /**
129   * Wraps an angle to the range -pi to pi radians.
130   *
131   * @param angleRadians Angle to wrap in radians.
132   * @return The wrapped angle.
133   */
134  public static double angleModulus(double angleRadians) {
135    return inputModulus(angleRadians, -Math.PI, Math.PI);
136  }
137
138  /**
139   * Perform linear interpolation between two values.
140   *
141   * @param startValue The value to start at.
142   * @param endValue The value to end at.
143   * @param t How far between the two values to interpolate. This is clamped to [0, 1].
144   * @return The interpolated value.
145   */
146  public static double interpolate(double startValue, double endValue, double t) {
147    return startValue + (endValue - startValue) * MathUtil.clamp(t, 0, 1);
148  }
149
150  /**
151   * Return where within interpolation range [0, 1] q is between startValue and endValue.
152   *
153   * @param startValue Lower part of interpolation range.
154   * @param endValue Upper part of interpolation range.
155   * @param q Query.
156   * @return Interpolant in range [0, 1].
157   */
158  public static double inverseInterpolate(double startValue, double endValue, double q) {
159    double totalRange = endValue - startValue;
160    if (totalRange <= 0) {
161      return 0.0;
162    }
163    double queryToStart = q - startValue;
164    if (queryToStart <= 0) {
165      return 0.0;
166    }
167    return queryToStart / totalRange;
168  }
169
170  /**
171   * Checks if the given value matches an expected value within a certain tolerance.
172   *
173   * @param expected The expected value
174   * @param actual The actual value
175   * @param tolerance The allowed difference between the actual and the expected value
176   * @return Whether or not the actual value is within the allowed tolerance
177   */
178  public static boolean isNear(double expected, double actual, double tolerance) {
179    if (tolerance < 0) {
180      throw new IllegalArgumentException("Tolerance must be a non-negative number!");
181    }
182    return Math.abs(expected - actual) < tolerance;
183  }
184
185  /**
186   * Checks if the given value matches an expected value within a certain tolerance. Supports
187   * continuous input for cases like absolute encoders.
188   *
189   * <p>Continuous input means that the min and max value are considered to be the same point, and
190   * tolerances can be checked across them. A common example would be for absolute encoders: calling
191   * isNear(2, 359, 5, 0, 360) returns true because 359 is 1 away from 360 (which is treated as the
192   * same as 0) and 2 is 2 away from 0, adding up to an error of 3 degrees, which is within the
193   * given tolerance of 5.
194   *
195   * @param expected The expected value
196   * @param actual The actual value
197   * @param tolerance The allowed difference between the actual and the expected value
198   * @param min Smallest value before wrapping around to the largest value
199   * @param max Largest value before wrapping around to the smallest value
200   * @return Whether or not the actual value is within the allowed tolerance
201   */
202  public static boolean isNear(
203      double expected, double actual, double tolerance, double min, double max) {
204    if (tolerance < 0) {
205      throw new IllegalArgumentException("Tolerance must be a non-negative number!");
206    }
207    // Max error is exactly halfway between the min and max
208    double errorBound = (max - min) / 2.0;
209    double error = MathUtil.inputModulus(expected - actual, -errorBound, errorBound);
210    return Math.abs(error) < tolerance;
211  }
212}