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

Public Member Functions

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
 

Member Function Documentation

◆ calculateRobotRelativeSpeeds()

virtual frc::ChassisSpeeds pathplanner::PathFollowingController::calculateRobotRelativeSpeeds ( const frc::Pose2d &  currentPose,
const PathPlannerTrajectoryState targetState 
)
pure virtual

Calculates the next output of the path following controller

Parameters
currentPoseThe current robot pose
targetStateThe desired trajectory state
Returns
The next robot relative output of the path following controller

Implemented in pathplanner::PPHolonomicDriveController, and pathplanner::PPLTVController.

◆ getPositionalError()

virtual units::meter_t pathplanner::PathFollowingController::getPositionalError ( )
pure virtual

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

Returns
Positional error, in meters

Implemented in pathplanner::PPHolonomicDriveController, and pathplanner::PPLTVController.

◆ isHolonomic()

virtual bool pathplanner::PathFollowingController::isHolonomic ( )
pure virtual

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

Implemented in pathplanner::PPHolonomicDriveController, and pathplanner::PPLTVController.

◆ reset()

virtual void pathplanner::PathFollowingController::reset ( const frc::Pose2d &  currentPose,
const frc::ChassisSpeeds &  currentSpeeds 
)
pure virtual

Resets the controller based on the current state of the robot

Parameters
currentPoseCurrent robot pose
currentSpeedsCurrent robot relative chassis speeds

Implemented in pathplanner::PPHolonomicDriveController, and pathplanner::PPLTVController.


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