Skip to content

Geometry Util

pathplannerlib Index / Pathplannerlib / Geometry Util

Auto-generated documentation for pathplannerlib.geometry_util module.

calculateRadius

Show source in geometry_util.py:102

Calculate the curve radius given 3 points on the curve

Arguments

  • a - Point A
  • b - Point B
  • c - Point C

Returns

Curve radius

Signature

def calculateRadius(a: Translation2d, b: Translation2d, c: Translation2d) -> float: ...

cubicLerp

Show source in geometry_util.py:86

Cubic interpolation between Translation2ds

Arguments

  • a - Position 1
  • b - Position 2
  • c - Position 3
  • d - Position 4
  • t - Interpolation factor (0.0-1.0)

Returns

Interpolated value

Signature

def cubicLerp(
    a: Translation2d, b: Translation2d, c: Translation2d, d: Translation2d, t: float
) -> Translation2d: ...

decimal_range

Show source in geometry_util.py:127

Signature

def decimal_range(start: float, stop: float, increment: float): ...

flipFieldPos

Show source in geometry_util.py:7

Flip a field position to the other side of the field, maintaining a blue alliance origin

Arguments

  • pos - The position to flip

Returns

The flipped position

Signature

def flipFieldPos(pos: Translation2d) -> Translation2d: ...

flipFieldPose

Show source in geometry_util.py:26

Flip a field pose to the other side of the field, maintaining a blue alliance origin

Arguments

  • pose - The pose to flip

Returns

The flipped pose

Signature

def flipFieldPose(pose: Pose2d) -> Pose2d: ...

flipFieldRotation

Show source in geometry_util.py:17

Flip a field rotation to the other side of the field, maintaining a blue alliance origin

Arguments

  • rotation - The rotation to flip

Returns

The flipped rotation

Signature

def flipFieldRotation(rotation: Rotation2d) -> Rotation2d: ...

floatLerp

Show source in geometry_util.py:35

Interpolate between two floats

Arguments

  • start_val - Start value
  • end_val - End value
  • t - Interpolation factor (0.0-1.0)

Returns

Interpolated value

Signature

def floatLerp(start_val: float, end_val: float, t: float) -> float: ...

quadraticLerp

Show source in geometry_util.py:71

Quadratic interpolation between Translation2ds

Arguments

  • a - Position 1
  • b - Position 2
  • c - Position 3
  • t - Interpolation factor (0.0-1.0)

Returns

Interpolated value

Signature

def quadraticLerp(
    a: Translation2d, b: Translation2d, c: Translation2d, t: float
) -> Translation2d: ...

rotationLerp

Show source in geometry_util.py:59

Interpolate between two Rotation2ds

Arguments

  • a - Start value
  • b - End value
  • t - Interpolation factor (0.0-1.0)

Returns

Interpolated value

Signature

def rotationLerp(a: Rotation2d, b: Rotation2d, t: float) -> Rotation2d: ...

translationLerp

Show source in geometry_util.py:47

Linear interpolation between two Translation2ds

Arguments

  • a - Start value
  • b - End value
  • t - Interpolation factor (0.0-1.0)

Returns

Interpolated value

Signature

def translationLerp(a: Translation2d, b: Translation2d, t: float) -> Translation2d: ...