PathPlannerLib
Loading...
Searching...
No Matches
pathplanner::PPHolonomicDriveController Class Reference
Inheritance diagram for pathplanner::PPHolonomicDriveController:
pathplanner::PathFollowingController

Public Member Functions

 PPHolonomicDriveController (PIDConstants translationConstants, PIDConstants rotationConstants, units::second_t period=0.02_s)
 
constexpr void setEnabled (bool enabled)
 
void reset (const frc::Pose2d &currentPose, const frc::ChassisSpeeds &currentSpeeds) override
 
units::meter_t getPositionalError () override
 
frc::ChassisSpeeds calculateRobotRelativeSpeeds (const frc::Pose2d &currentPose, const PathPlannerTrajectoryState &referenceState) override
 
bool isHolonomic () override
 
virtual frc::ChassisSpeeds calculateRobotRelativeSpeeds (const frc::Pose2d &currentPose, const PathPlannerTrajectoryState &targetState)=0
 
virtual void reset (const frc::Pose2d &currentPose, const frc::ChassisSpeeds &currentSpeeds)=0
 
virtual units::meter_t getPositionalError ()=0
 
virtual bool isHolonomic ()=0
 

Static Public Member Functions

static void setRotationTargetOverride (std::function< std::optional< frc::Rotation2d >()> rotationTargetOverride)
 
static void overrideXFeedback (std::function< units::meters_per_second_t()> xFeedbackOverride)
 
static void clearXFeedbackOverride ()
 
static void overrideYFeedback (std::function< units::meters_per_second_t()> yFeedbackOverride)
 
static void clearYFeedbackOverride ()
 
static void overrideXYFeedback (std::function< units::meters_per_second_t()> xFeedbackOverride, std::function< units::meters_per_second_t()> yFeedbackOverride)
 
static void clearXYFeedbackOverride ()
 
static void overrideRotationFeedback (std::function< units::radians_per_second_t()> rotationFeedbackOverride)
 
static void clearRotationFeedbackOverride ()
 
static void clearFeedbackOverrides ()
 

Constructor & Destructor Documentation

◆ PPHolonomicDriveController()

PPHolonomicDriveController::PPHolonomicDriveController ( PIDConstants  translationConstants,
PIDConstants  rotationConstants,
units::second_t  period = 0.02_s 
)

Constructs a PPHolonomicDriveController

Parameters
translationConstantsPID constants for the translation PID controllers
rotationConstantsPID constants for the rotation controller
periodPeriod of the control loop in seconds

Member Function Documentation

◆ calculateRobotRelativeSpeeds()

frc::ChassisSpeeds PPHolonomicDriveController::calculateRobotRelativeSpeeds ( const frc::Pose2d &  currentPose,
const PathPlannerTrajectoryState referenceState 
)
overridevirtual

Calculates the next output of the holonomic drive controller

Parameters
currentPoseThe current pose
referenceStateThe 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

Get the last positional error of the controller

Returns
Positional error, in meters

Implements pathplanner::PathFollowingController.

◆ 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
rotationFeedbackOverrideFunction 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
xFeedbackOverrideFunction 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
xFeedbackOverrideFunction that returns the desired FIELD-RELATIVE X feedback in meters/sec
yFeedbackOverrideFunction 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
yFeedbackOverrideFunction 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
currentPoseCurrent robot pose
currentSpeedsCurrent 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
enabledIf 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
rotationTargetOverrideSupplier to override rotation targets

The documentation for this class was generated from the following files: