◆ PPHolonomicDriveController()
PPHolonomicDriveController::PPHolonomicDriveController |
( |
PIDConstants |
translationConstants, |
|
|
PIDConstants |
rotationConstants, |
|
|
units::second_t |
period = 0.02_s |
|
) |
| |
Constructs a PPHolonomicDriveController
- Parameters
-
translationConstants | PID constants for the translation PID controllers |
rotationConstants | PID constants for the rotation controller |
period | Period of the control loop in seconds |
◆ calculateRobotRelativeSpeeds()
frc::ChassisSpeeds PPHolonomicDriveController::calculateRobotRelativeSpeeds |
( |
const frc::Pose2d & |
currentPose, |
|
|
const PathPlannerTrajectoryState & |
referenceState |
|
) |
| |
|
overridevirtual |
Calculates the next output of the holonomic drive controller
- Parameters
-
currentPose | The current pose |
referenceState | The desired trajectory state |
- Returns
- The next output of the holonomic drive controller (robot relative)
Implements pathplanner::PathFollowingController.
◆ clearFeedbackOverrides()
static void pathplanner::PPHolonomicDriveController::clearFeedbackOverrides |
( |
| ) |
|
|
inlinestatic |
Clear all feedback overrides and return to purely using path following error for feedback
◆ clearRotationFeedbackOverride()
static void pathplanner::PPHolonomicDriveController::clearRotationFeedbackOverride |
( |
| ) |
|
|
inlinestatic |
Stop overriding the rotation feedback, and return to calculating it based on path following error.
◆ clearXFeedbackOverride()
static void pathplanner::PPHolonomicDriveController::clearXFeedbackOverride |
( |
| ) |
|
|
inlinestatic |
Stop overriding the X axis feedback, and return to calculating it based on path following error.
◆ clearXYFeedbackOverride()
static void pathplanner::PPHolonomicDriveController::clearXYFeedbackOverride |
( |
| ) |
|
|
inlinestatic |
Stop overriding the X and Y axis feedback, and return to calculating them based on path following error.
◆ clearYFeedbackOverride()
static void pathplanner::PPHolonomicDriveController::clearYFeedbackOverride |
( |
| ) |
|
|
inlinestatic |
Stop overriding the Y axis feedback, and return to calculating it based on path following error.
◆ getPositionalError()
units::meter_t pathplanner::PPHolonomicDriveController::getPositionalError |
( |
| ) |
|
|
inlineoverridevirtual |
◆ isHolonomic()
bool pathplanner::PPHolonomicDriveController::isHolonomic |
( |
| ) |
|
|
inlineoverridevirtual |
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
Implements pathplanner::PathFollowingController.
◆ overrideRotationFeedback()
static void pathplanner::PPHolonomicDriveController::overrideRotationFeedback |
( |
std::function< units::radians_per_second_t()> |
rotationFeedbackOverride | ) |
|
|
inlinestatic |
Begin overriding the rotation feedback.
- Parameters
-
rotationFeedbackOverride | Function that returns the desired rotation feedback in radians/sec |
◆ overrideXFeedback()
static void pathplanner::PPHolonomicDriveController::overrideXFeedback |
( |
std::function< units::meters_per_second_t()> |
xFeedbackOverride | ) |
|
|
inlinestatic |
Begin overriding the X axis feedback.
- Parameters
-
xFeedbackOverride | Function that returns the desired FIELD-RELATIVE X feedback in meters/sec |
◆ overrideXYFeedback()
static void pathplanner::PPHolonomicDriveController::overrideXYFeedback |
( |
std::function< units::meters_per_second_t()> |
xFeedbackOverride, |
|
|
std::function< units::meters_per_second_t()> |
yFeedbackOverride |
|
) |
| |
|
inlinestatic |
Begin overriding the X and Y axis feedback.
- Parameters
-
xFeedbackOverride | Function that returns the desired FIELD-RELATIVE X feedback in meters/sec |
yFeedbackOverride | Function that returns the desired FIELD-RELATIVE Y feedback in meters/sec |
◆ overrideYFeedback()
static void pathplanner::PPHolonomicDriveController::overrideYFeedback |
( |
std::function< units::meters_per_second_t()> |
yFeedbackOverride | ) |
|
|
inlinestatic |
Begin overriding the Y axis feedback.
- Parameters
-
yFeedbackOverride | Function that returns the desired FIELD-RELATIVE Y feedback in meters/sec |
◆ reset()
void pathplanner::PPHolonomicDriveController::reset |
( |
const frc::Pose2d & |
currentPose, |
|
|
const frc::ChassisSpeeds & |
currentSpeeds |
|
) |
| |
|
inlineoverridevirtual |
Resets the controller based on the current state of the robot
- Parameters
-
currentPose | Current robot pose |
currentSpeeds | Current robot relative chassis speeds |
Implements pathplanner::PathFollowingController.
◆ setEnabled()
constexpr void pathplanner::PPHolonomicDriveController::setEnabled |
( |
bool |
enabled | ) |
|
|
inlineconstexpr |
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 |
◆ setRotationTargetOverride()
static void pathplanner::PPHolonomicDriveController::setRotationTargetOverride |
( |
std::function< std::optional< frc::Rotation2d >()> |
rotationTargetOverride | ) |
|
|
inlinestatic |
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
- Parameters
-
rotationTargetOverride | Supplier to override rotation targets |
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/controllers/PPHolonomicDriveController.h
- src/main/native/cpp/pathplanner/lib/controllers/PPHolonomicDriveController.cpp