Interface Interpolator<T>

Type Parameters:
T - The type that the Interpolator will operate on.
All Known Subinterfaces:
Kinematics<S,P>
All Known Implementing Classes:
DifferentialDriveKinematics, MecanumDriveKinematics, SwerveDriveKinematics
Functional Interface:
This is a functional interface and can therefore be used as the assignment target for a lambda expression or method reference.

An interpolation function that returns a value interpolated between an upper and lower bound. This behavior can be linear or nonlinear.
  • Method Summary

    Modifier and Type
    Method
    Description
    Returns interpolator for Double.
    interpolate(T startValue, T endValue, double t)
    Perform interpolation between two values.
  • Method Details

    • interpolate

      T interpolate(T startValue, T endValue, double t)
      Perform interpolation between two values.
      Parameters:
      startValue - The value to start at.
      endValue - The value to end at.
      t - How far between the two values to interpolate. This should be bounded to [0, 1].
      Returns:
      The interpolated value.
    • forDouble

      Returns interpolator for Double.
      Returns:
      Interpolator for Double.