Package com.pathplanner.lib.controllers
Class PPHolonomicDriveController
java.lang.Object
com.pathplanner.lib.controllers.PPHolonomicDriveController
- All Implemented Interfaces:
PathFollowingController
Path following controller for holonomic drive trains
-
Constructor Summary
ConstructorDescriptionPPHolonomicDriveController
(PIDConstants translationConstants, PIDConstants rotationConstants) Constructs a HolonomicDriveControllerPPHolonomicDriveController
(PIDConstants translationConstants, PIDConstants rotationConstants, double period) Constructs a HolonomicDriveController -
Method Summary
Modifier and TypeMethodDescriptioncalculateRobotRelativeSpeeds
(Pose2d currentPose, PathPlannerTrajectoryState targetState) Calculates the next output of the path following controllerstatic void
Clear all feedback overrides and return to purely using path following error for feedbackstatic void
Stop overriding the rotation feedback, and return to calculating it based on path following error.static void
Stop overriding the X axis feedback, and return to calculating it based on path following error.static void
Stop overriding the X and Y axis feedback, and return to calculating them based on path following error.static void
Stop overriding the Y axis feedback, and return to calculating it based on path following error.boolean
Is this controller for holonomic drivetrains? Used to handle some differences in functionality in the path following command.static void
overrideRotationFeedback
(DoubleSupplier rotationFeedbackOverride) Begin overriding the rotation feedback.static void
overrideXFeedback
(DoubleSupplier xFeedbackOverride) Begin overriding the X axis feedback.static void
overrideXYFeedback
(DoubleSupplier xFeedbackOverride, DoubleSupplier yFeedbackOverride) Begin overriding the X and Y axis feedback.static void
overrideYFeedback
(DoubleSupplier yFeedbackOverride) Begin overriding the Y axis feedback.void
reset
(Pose2d currentPose, ChassisSpeeds currentSpeeds) Resets the controller based on the current state of the robotvoid
setEnabled
(boolean enabled) Enables and disables the controller for troubleshooting.static void
setRotationTargetOverride
(Supplier<Optional<Rotation2d>> rotationTargetOverride) Deprecated.Use overrideRotationFeedback instead, with the output of your own PID controller
-
Constructor Details
-
PPHolonomicDriveController
public PPHolonomicDriveController(PIDConstants translationConstants, PIDConstants rotationConstants, double period) Constructs a HolonomicDriveController- Parameters:
translationConstants
- PID constants for the translation PID controllersrotationConstants
- PID constants for the rotation controllerperiod
- Period of the control loop in seconds
-
PPHolonomicDriveController
public PPHolonomicDriveController(PIDConstants translationConstants, PIDConstants rotationConstants) Constructs a HolonomicDriveController- Parameters:
translationConstants
- PID constants for the translation PID controllersrotationConstants
- PID constants for the rotation controller
-
-
Method Details
-
setEnabled
public void setEnabled(boolean enabled) Enables and disables the controller for troubleshooting. When calculate() is called on a disabled controller, only feedforward values are returned.- Parameters:
enabled
- If the controller is enabled or not
-
reset
Resets the controller based on the current state of the robot- Specified by:
reset
in interfacePathFollowingController
- Parameters:
currentPose
- Current robot posecurrentSpeeds
- Current robot relative chassis speeds
-
calculateRobotRelativeSpeeds
public ChassisSpeeds calculateRobotRelativeSpeeds(Pose2d currentPose, PathPlannerTrajectoryState targetState) Calculates the next output of the path following controller- Specified by:
calculateRobotRelativeSpeeds
in interfacePathFollowingController
- Parameters:
currentPose
- The current robot posetargetState
- The desired trajectory state- Returns:
- The next robot relative output of the path following controller
-
isHolonomic
public boolean isHolonomic()Is this controller for holonomic drivetrains? Used to handle some differences in functionality in the path following command.- Specified by:
isHolonomic
in interfacePathFollowingController
- Returns:
- True if this controller is for a holonomic drive train
-
setRotationTargetOverride
@Deprecated public static void setRotationTargetOverride(Supplier<Optional<Rotation2d>> rotationTargetOverride) Deprecated.Use overrideRotationFeedback instead, with the output of your own PID controllerSet 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
- Parameters:
rotationTargetOverride
- Supplier to override rotation targets
-
overrideXFeedback
Begin overriding the X axis feedback.- Parameters:
xFeedbackOverride
- Double supplier that returns the desired FIELD-RELATIVE X feedback in meters/sec
-
clearXFeedbackOverride
public static void clearXFeedbackOverride()Stop overriding the X axis feedback, and return to calculating it based on path following error. -
overrideYFeedback
Begin overriding the Y axis feedback.- Parameters:
yFeedbackOverride
- Double supplier that returns the desired FIELD-RELATIVE Y feedback in meters/sec
-
clearYFeedbackOverride
public static void clearYFeedbackOverride()Stop overriding the Y axis feedback, and return to calculating it based on path following error. -
overrideXYFeedback
public static void overrideXYFeedback(DoubleSupplier xFeedbackOverride, DoubleSupplier yFeedbackOverride) Begin overriding the X and Y axis feedback.- Parameters:
xFeedbackOverride
- Double supplier that returns the desired FIELD-RELATIVE X feedback in meters/secyFeedbackOverride
- Double supplier that returns the desired FIELD-RELATIVE Y feedback in meters/sec
-
clearXYFeedbackOverride
public static void clearXYFeedbackOverride()Stop overriding the X and Y axis feedback, and return to calculating them based on path following error. -
overrideRotationFeedback
Begin overriding the rotation feedback.- Parameters:
rotationFeedbackOverride
- Double supplier that returns the desired rotation feedback in radians/sec
-
clearRotationFeedbackOverride
public static void clearRotationFeedbackOverride()Stop overriding the rotation feedback, and return to calculating it based on path following error. -
clearFeedbackOverrides
public static void clearFeedbackOverrides()Clear all feedback overrides and return to purely using path following error for feedback
-