Class GeometryUtil

java.lang.Object
com.pathplanner.lib.util.GeometryUtil

public class GeometryUtil extends Object
Utility class for various geometry functions used during generation
  • Constructor Details

    • GeometryUtil

      public GeometryUtil()
  • Method Details

    • quadraticLerp

      public static Translation2d quadraticLerp(Translation2d a, Translation2d b, Translation2d c, double t)
      Quadratic interpolation between Translation2ds
      Parameters:
      a - Position 1
      b - Position 2
      c - Position 3
      t - Interpolation factor (0.0-1.0)
      Returns:
      Interpolated value
    • cubicLerp

      public static Translation2d cubicLerp(Translation2d a, Translation2d b, Translation2d c, Translation2d d, double t)
      Cubic interpolation between Translation2ds
      Parameters:
      a - Position 1
      b - Position 2
      c - Position 3
      d - Position 4
      t - Interpolation factor (0.0-1.0)
      Returns:
      Interpolated value
    • calculateRadius

      public static double calculateRadius(Translation2d a, Translation2d b, Translation2d c)
      Calculate the curve radius given 3 points on the curve
      Parameters:
      a - Point A
      b - Point B
      c - Point C
      Returns:
      Curve radius