Skip to content

Controller

pathplannerlib Index / Pathplannerlib / Controller

Auto-generated documentation for pathplannerlib.controller module.

PPHolonomicDriveController

Show source in controller.py:48

Signature

class PPHolonomicDriveController(PathFollowingController):
    def __init__(
        self,
        translation_constants: PIDConstants,
        rotation_constants: PIDConstants,
        period: float = 0.02,
    ): ...

See also

PPHolonomicDriveController().calculateRobotRelativeSpeeds

Show source in controller.py:91

Calculates the next output of the path following controller

Arguments

  • current_pose - The current robot pose
  • target_state - The desired trajectory state

Returns

The next robot relative output of the path following controller

Signature

def calculateRobotRelativeSpeeds(
    self, current_pose: Pose2d, target_state: PathPlannerTrajectoryState
) -> ChassisSpeeds: ...

PPHolonomicDriveController.clearFeedbackOverrides

Show source in controller.py:238

Clear all feedback overrides and return to purely using path following error for feedback

Signature

@staticmethod
def clearFeedbackOverrides() -> None: ...

PPHolonomicDriveController.clearRotationFeedbackOverride

Show source in controller.py:231

Stop overriding the rotation feedback, and return to calculating it based on path following error.

Signature

@staticmethod
def clearRotationFeedbackOverride() -> None: ...

PPHolonomicDriveController.clearXFeedbackOverride

Show source in controller.py:180

Stop overriding the X axis feedback, and return to calculating it based on path following error.

Signature

@staticmethod
def clearXFeedbackOverride() -> None: ...

PPHolonomicDriveController.clearXYFeedbackOverride

Show source in controller.py:214

Stop overriding the X and Y axis feedback, and return to calculating it based on path following error.

Signature

@staticmethod
def clearXYFeedbackOverride() -> None: ...

PPHolonomicDriveController.clearYFeedbackOverride

Show source in controller.py:196

Stop overriding the Y axis feedback, and return to calculating it based on path following error.

Signature

@staticmethod
def clearYFeedbackOverride() -> None: ...

PPHolonomicDriveController().getPositionalError

Show source in controller.py:144

Get the current positional error between the robot's actual and target positions

Returns

Positional error, in meters

Signature

def getPositionalError(self) -> float: ...

PPHolonomicDriveController().isHolonomic

Show source in controller.py:152

Is this controller for holonomic drivetrains? Used to handle some differences in functionality in the path following command.

Returns

True if this controller is for a holonomic drive train

Signature

def isHolonomic(self) -> bool: ...

PPHolonomicDriveController.overrideRotationFeedback

Show source in controller.py:222

Begin overriding the rotation feedback.

Arguments

  • rotationFeedbackOverride - Callable that returns the desired rotation feedback in radians/sec

Signature

@staticmethod
def overrideRotationFeedback(rotationFeedbackOverride: Callable[[], float]) -> None: ...

PPHolonomicDriveController.overrideXFeedback

Show source in controller.py:171

Begin overriding the X axis feedback.

Arguments

  • xFeedbackOverride - Callable that returns the desired FIELD-RELATIVE X feedback in meters/sec

Signature

@staticmethod
def overrideXFeedback(xFeedbackOverride: Callable[[], float]) -> None: ...

PPHolonomicDriveController.overrideXYFeedback

Show source in controller.py:203

Begin overriding the X and Y axis feedback.

Arguments

  • xFeedbackOverride - Callable that returns the desired FIELD-RELATIVE X feedback in meters/sec
  • yFeedbackOverride - Callable that returns the desired FIELD-RELATIVE Y feedback in meters/sec

Signature

@staticmethod
def overrideXYFeedback(
    xFeedbackOverride: Callable[[], float], yFeedbackOverride: Callable[[], float]
) -> None: ...

PPHolonomicDriveController.overrideYFeedback

Show source in controller.py:187

Begin overriding the Y axis feedback.

Arguments

  • yFeedbackOverride - Callable that returns the desired FIELD-RELATIVE Y feedback in meters/sec

Signature

@staticmethod
def overrideYFeedback(yFeedbackOverride: Callable[[], float]) -> None: ...

PPHolonomicDriveController().reset

Show source in controller.py:133

Resets the controller based on the current state of the robot

Arguments

  • current_pose - Current robot pose
  • current_speeds - Current robot relative chassis speeds

Signature

def reset(self, current_pose: Pose2d, current_speeds: ChassisSpeeds) -> None: ...

PPHolonomicDriveController().setEnabled

Show source in controller.py:83

Enables and disables the controller for troubleshooting. When calculate() is called on a disabled controller, only feedforward values are returned.

Arguments

  • enabled - If the controller is enabled or not

Signature

def setEnabled(self, enabled: bool) -> None: ...

PPHolonomicDriveController.setRotationTargetOverride

Show source in controller.py:160

Set a supplier that will be used to override the rotation target when path following.

Use overrideRotationFeedback instead, with the output of your own PID controller

Arguments

  • rotation_target_override - Supplier to override rotation targets

Signature

@staticmethod
def setRotationTargetOverride(
    rotation_target_override: Union[Callable[[], Union[Rotation2d, None]], None],
) -> None: ...

PPLTVController

Show source in controller.py:248

Signature

class PPLTVController(PathFollowingController, LTVUnicycleController):
    def __init__(self, *args, **kwargs): ...

See also

PPLTVController().calculateRobotRelativeSpeeds

Show source in controller.py:284

Calculates the next output of the path following controller

Arguments

  • current_pose - The current robot pose
  • target_state - The desired trajectory state

Returns

The next robot relative output of the path following controller

Signature

def calculateRobotRelativeSpeeds(
    self, current_pose: Pose2d, target_state: PathPlannerTrajectoryState
) -> ChassisSpeeds: ...

PPLTVController().getPositionalError

Show source in controller.py:307

Get the current positional error between the robot's actual and target positions

Returns

Positional error, in meters

Signature

def getPositionalError(self) -> float: ...

PPLTVController().isHolonomic

Show source in controller.py:315

Is this controller for holonomic drivetrains? Used to handle some differences in functionality in the path following command.

Returns

True if this controller is for a holonomic drive train

Signature

def isHolonomic(self) -> bool: ...

PPLTVController().reset

Show source in controller.py:298

Resets the controller based on the current state of the robot

Arguments

  • current_pose - Current robot pose
  • current_speeds - Current robot relative chassis speeds

Signature

def reset(self, current_pose: Pose2d, current_speeds: ChassisSpeeds) -> None: ...

PathFollowingController

Show source in controller.py:10

Signature

class PathFollowingController: ...

PathFollowingController().calculateRobotRelativeSpeeds

Show source in controller.py:11

Calculates the next output of the path following controller

Arguments

  • current_pose - The current robot pose
  • target_state - The desired trajectory state

Returns

The next robot relative output of the path following controller

Signature

def calculateRobotRelativeSpeeds(
    self, current_pose: Pose2d, target_state: PathPlannerTrajectoryState
) -> ChassisSpeeds: ...

PathFollowingController().getPositionalError

Show source in controller.py:31

Get the current positional error between the robot's actual and target positions

Returns

Positional error, in meters

Signature

def getPositionalError(self) -> float: ...

PathFollowingController().isHolonomic

Show source in controller.py:39

Is this controller for holonomic drivetrains? Used to handle some differences in functionality in the path following command.

Returns

True if this controller is for a holonomic drive train

Signature

def isHolonomic(self) -> bool: ...

PathFollowingController().reset

Show source in controller.py:22

Resets the controller based on the current state of the robot

Arguments

  • current_pose - Current robot pose
  • current_speeds - Current robot relative chassis speeds

Signature

def reset(self, current_pose: Pose2d, current_speeds: ChassisSpeeds) -> None: ...