Skip to content

Util

pathplannerlib Index / Pathplannerlib / Util

Auto-generated documentation for pathplannerlib.util module.

DriveFeedforwards

Show source in util.py:22

Signature

class DriveFeedforwards: ...

DriveFeedforwards().flip

Show source in util.py:70

Flip the feedforwards for the other side of the field. Only does anything if mirrored symmetry is used

Returns

Flipped feedforwards

Signature

def flip(self) -> "DriveFeedforwards": ...

DriveFeedforwards().interpolate

Show source in util.py:45

Signature

def interpolate(self, endVal: "DriveFeedforwards", t: float) -> "DriveFeedforwards": ...

DriveFeedforwards().reverse

Show source in util.py:54

Reverse the feedforwards for driving backwards. This should only be used for differential drive robots.

Returns

Reversed feedforwards

Signature

def reverse(self) -> "DriveFeedforwards": ...

DriveFeedforwards.zeros

Show source in util.py:29

Create drive feedforwards consisting of all zeros

Arguments

  • numModules - Number of drive modules

Returns

Zero feedforwards

Signature

@staticmethod
def zeros(numModules: int) -> "DriveFeedforwards": ...

FieldSymmetry

Show source in util.py:16

Signature

class FieldSymmetry(Enum): ...

FlippingUtil

Show source in util.py:89

Signature

class FlippingUtil: ...

FlippingUtil.flipFeedforwards

Show source in util.py:141

Flip a list of drive feedforwards for the other side of the field. Only does anything if mirrored symmetry is used

Arguments

  • feedforwards - List of drive feedforwards

Returns

The flipped feedforwards

Signature

@staticmethod
def flipFeedforwards(feedforwards: List[float]) -> List[float]: ...

FlippingUtil.flipFieldPose

Show source in util.py:117

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

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

FlippingUtil.flipFieldPosition

Show source in util.py:94

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

@staticmethod
def flipFieldPosition(pos: Translation2d) -> Translation2d: ...

FlippingUtil.flipFieldRotation

Show source in util.py:107

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

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

FlippingUtil.flipFieldSpeeds

Show source in util.py:128

Flip field relative chassis speeds for the other side of the field, maintaining a blue alliance origin

Arguments

  • fieldSpeeds - Field relative chassis speeds

Returns

Flipped speeds

Signature

@staticmethod
def flipFieldSpeeds(fieldSpeeds: ChassisSpeeds) -> ChassisSpeeds: ...

calculateRadius

Show source in util.py:237

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 util.py:221

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 util.py:262

Signature

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

floatLerp

Show source in util.py:158

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: ...

poseLerp

Show source in util.py:194

Interpolate between two Pose2ds

Arguments

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

Returns

Interpolated value

Signature

def poseLerp(a: Pose2d, b: Pose2d, t: float) -> Pose2d: ...

quadraticLerp

Show source in util.py:206

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 util.py:182

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: ...

translation2dFromJson

Show source in util.py:10

Signature

def translation2dFromJson(translationJson: dict) -> Translation2d: ...

translationLerp

Show source in util.py:170

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: ...