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,
max_module_speed: float,
drive_base_radius: float,
period: float = 0.02,
): ...
See also
PPHolonomicDriveController().calculateRobotRelativeSpeeds
Show source in controller.py:97
Calculates the next output of the path following controller
Arguments
current_pose
- The current robot posetarget_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: State
) -> ChassisSpeeds: ...
PPHolonomicDriveController().getPositionalError
Show source in controller.py:155
Get the current positional error between the robot's actual and target positions
Returns
Positional error, in meters
Signature
PPHolonomicDriveController().isHolonomic
Show source in controller.py:163
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
PPHolonomicDriveController().reset
Show source in controller.py:146
Resets the controller based on the current state of the robot
Arguments
current_pose
- Current robot posecurrent_speeds
- Current robot relative chassis speeds
Signature
PPHolonomicDriveController().setEnabled
Show source in controller.py:89
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
PPHolonomicDriveController.setRotationTargetOverride
Show source in controller.py:171
Set a supplier that will be used to override the rotation target when path following.
This function should return an empty optional to use the rotation targets in the path
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 posetarget_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: State
) -> ChassisSpeeds: ...
PPLTVController().getPositionalError
Show source in controller.py:306
Get the current positional error between the robot's actual and target positions
Returns
Positional error, in meters
Signature
PPLTVController().isHolonomic
Show source in controller.py:314
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
PPLTVController().reset
Show source in controller.py:297
Resets the controller based on the current state of the robot
Arguments
current_pose
- Current robot posecurrent_speeds
- Current robot relative chassis speeds
Signature
PPRamseteController
Show source in controller.py:184
Signature
class PPRamseteController(PathFollowingController, RamseteController):
def __init__(self, *args, **kwargs): ...
See also
PPRamseteController().calculateRobotRelativeSpeeds
Show source in controller.py:209
Calculates the next output of the path following controller
Arguments
current_pose
- The current robot posetarget_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: State
) -> ChassisSpeeds: ...
PPRamseteController().getPositionalError
Show source in controller.py:231
Get the current positional error between the robot's actual and target positions
Returns
Positional error, in meters
Signature
PPRamseteController().isHolonomic
Show source in controller.py:239
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
PPRamseteController().reset
Show source in controller.py:222
Resets the controller based on the current state of the robot
Arguments
current_pose
- Current robot posecurrent_speeds
- Current robot relative chassis speeds
Signature
PathFollowingController
Show source in controller.py:11
Signature
PathFollowingController().calculateRobotRelativeSpeeds
Show source in controller.py:12
Calculates the next output of the path following controller
Arguments
current_pose
- The current robot posetarget_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: State
) -> 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
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
PathFollowingController().reset
Show source in controller.py:22
Resets the controller based on the current state of the robot
Arguments
current_pose
- Current robot posecurrent_speeds
- Current robot relative chassis speeds