Class LightningMath


  • public final class LightningMath
    extends java.lang.Object
    • Method Summary

      All Methods Static Methods Concrete Methods 
      Modifier and Type Method Description
      static double angleModulus​(double angleRadians)
      Wraps an angle to the range -pi to pi radians.
      static double boundTheta0To2Pi​(double theta)  
      static double boundTheta0to360​(double theta)  
      static double boundThetaNeg180to180​(double theta)  
      static double boundThetaNegPiToPi​(double theta)  
      static double clamp​(double value, double low, double high)
      Returns value clamped between low and high boundaries.
      static int clamp​(int value, int low, int high)
      Returns value clamped between low and high boundaries.
      static double constrain​(double value, double low, double high)  
      static int constrain​(int value, int low, int high)  
      static double deadZone​(double input, double deadband)  
      static double deltaThetaInDegrees​(double from, double to)  
      static double deltaThetaInRadians​(double from, double to)  
      static double inputModulus​(double input, double minimumInput, double maximumInput)
      Returns modulus of input.
      static double lerp​(double startValue, double endValue, double t)
      Linearly interpolates between two values.
      static edu.wpi.first.math.geometry.Pose2d lerp​(edu.wpi.first.math.geometry.Pose2d startValue, edu.wpi.first.math.geometry.Pose2d endValue, double t)
      Linearly interpolates between two poses.
      static double limit​(double input)  
      static double limit​(double v, double limit)  
      static double limit​(double v, double low, double high)  
      static double max​(double... values)
      Finds the maximum value of the given inputs.
      static double rpmToMetersPerSecond​(double rpm, double gearReduction, double wheelCircumference)
      Converts motor rotational speed to linear speed
      static double scale​(double input, double lowInput, double highInput, double lowOutput, double highOutput)  
      static int scale​(int input, int lowInput, int highInput, int lowOutput, int highOutput)  
      static double ticksToDistance​(double ticks, double wheelDiameter, double gearReduction, double ticksPerRev)
      Converts encoder ticks to a distance (units of input)
      • Methods inherited from class java.lang.Object

        clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
    • Method Detail

      • clamp

        public static int clamp​(int value,
                                int low,
                                int high)
        Returns value clamped between low and high boundaries.
        Parameters:
        value - Value to clamp.
        low - The lower boundary to which to clamp value.
        high - The higher boundary to which to clamp value.
        Returns:
        clamped value.
      • clamp

        public static double clamp​(double value,
                                   double low,
                                   double high)
        Returns value clamped between low and high boundaries.
        Parameters:
        value - Value to clamp.
        low - The lower boundary to which to clamp value.
        high - The higher boundary to which to clamp value.
        Returns:
        clamped value.
      • inputModulus

        public static double inputModulus​(double input,
                                          double minimumInput,
                                          double maximumInput)
        Returns modulus of input.
        Parameters:
        input - Input value to wrap.
        minimumInput - The minimum value expected from the input.
        maximumInput - The maximum value expected from the input.
        Returns:
        mod of input value
      • angleModulus

        public static double angleModulus​(double angleRadians)
        Wraps an angle to the range -pi to pi radians.
        Parameters:
        angleRadians - Angle to wrap in radians.
        Returns:
        constrained angle from -pi to pi
      • max

        public static double max​(double... values)
        Finds the maximum value of the given inputs.
        Parameters:
        values - Multiple floating-point values.
        Returns:
        The maximum of the values given.
      • constrain

        public static int constrain​(int value,
                                    int low,
                                    int high)
      • constrain

        public static double constrain​(double value,
                                       double low,
                                       double high)
      • limit

        public static double limit​(double v,
                                   double low,
                                   double high)
      • limit

        public static double limit​(double v,
                                   double limit)
      • limit

        public static double limit​(double input)
      • boundThetaNegPiToPi

        public static double boundThetaNegPiToPi​(double theta)
      • boundTheta0To2Pi

        public static double boundTheta0To2Pi​(double theta)
      • boundThetaNeg180to180

        public static double boundThetaNeg180to180​(double theta)
      • boundTheta0to360

        public static double boundTheta0to360​(double theta)
      • deltaThetaInDegrees

        public static double deltaThetaInDegrees​(double from,
                                                 double to)
      • deltaThetaInRadians

        public static double deltaThetaInRadians​(double from,
                                                 double to)
      • scale

        public static int scale​(int input,
                                int lowInput,
                                int highInput,
                                int lowOutput,
                                int highOutput)
      • scale

        public static double scale​(double input,
                                   double lowInput,
                                   double highInput,
                                   double lowOutput,
                                   double highOutput)
      • deadZone

        public static double deadZone​(double input,
                                      double deadband)
      • lerp

        public static double lerp​(double startValue,
                                  double endValue,
                                  double t)
        Linearly interpolates between two values.
        Parameters:
        startValue - The start value.
        endValue - The end value.
        t - The fraction for interpolation.
        Returns:
        The interpolated value.
      • lerp

        public static edu.wpi.first.math.geometry.Pose2d lerp​(edu.wpi.first.math.geometry.Pose2d startValue,
                                                              edu.wpi.first.math.geometry.Pose2d endValue,
                                                              double t)
        Linearly interpolates between two poses.
        Parameters:
        startValue - The start pose.
        endValue - The end pose.
        t - The fraction for interpolation.
        Returns:
        The interpolated pose.
      • rpmToMetersPerSecond

        public static double rpmToMetersPerSecond​(double rpm,
                                                  double gearReduction,
                                                  double wheelCircumference)
        Converts motor rotational speed to linear speed
        Parameters:
        rpm - input speed to convert
        gearReduction - reduction between driver and actuator
        wheelCircumference - circumference of wheel (inches)
        Returns:
        the speed in meters per second
      • ticksToDistance

        public static double ticksToDistance​(double ticks,
                                             double wheelDiameter,
                                             double gearReduction,
                                             double ticksPerRev)
        Converts encoder ticks to a distance (units of input)
        Parameters:
        ticks - input to convert
        wheelDiameter - diameter of wheel
        gearReduction - reduction in gearbox
        ticksPerRev - ticks pre revolution of motor shaft
        Returns:
        distance wheel has travled, in units of the wheel diameter supplied