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

Public Member Functions

 PPLTVController (units::second_t dt, units::velocity::meters_per_second_t maxVelocity=9_mps)
 
 PPLTVController (const wpi::array< double, 3 > &Qelems, const wpi::array< double, 2 > &Relems, units::second_t dt, units::meters_per_second_t maxVelocity=9_mps)
 
frc::ChassisSpeeds calculateRobotRelativeSpeeds (const frc::Pose2d &currentPose, const PathPlannerTrajectoryState &targetState) override
 
void reset (const frc::Pose2d &currentPose, const frc::ChassisSpeeds &currentSpeeds) override
 
units::meter_t getPositionalError () 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
 

Constructor & Destructor Documentation

◆ PPLTVController() [1/2]

pathplanner::PPLTVController::PPLTVController ( units::second_t  dt,
units::velocity::meters_per_second_t  maxVelocity = 9_mps 
)
inline

Constructs a linear time-varying unicycle controller with default maximum desired error tolerances of (0.0625 m, 0.125 m, 2 rad) and default maximum desired control effort of (1 m/s, 2 rad/s).

Parameters
dtDiscretization timestep in seconds.
maxVelocityThe maximum velocity in meters per second for the controller gain lookup table. The default is 9 m/s.

◆ PPLTVController() [2/2]

pathplanner::PPLTVController::PPLTVController ( const wpi::array< double, 3 > &  Qelems,
const wpi::array< double, 2 > &  Relems,
units::second_t  dt,
units::meters_per_second_t  maxVelocity = 9_mps 
)
inline

Constructs a linear time-varying unicycle controller.

See https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning for how to select the tolerances.

Parameters
QelemsThe maximum desired error tolerance for each state.
RelemsThe maximum desired control effort for each input.
dtDiscretization timestep in seconds.
maxVelocityThe maximum velocity in meters per second for the controller gain lookup table. The default is 9 m/s.
Exceptions
IllegalArgumentExceptionif maxVelocity <= 0 m/s or >= 15 m/s.

Member Function Documentation

◆ calculateRobotRelativeSpeeds()

frc::ChassisSpeeds pathplanner::PPLTVController::calculateRobotRelativeSpeeds ( const frc::Pose2d &  currentPose,
const PathPlannerTrajectoryState targetState 
)
inlineoverridevirtual

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

Implements pathplanner::PathFollowingController.

◆ getPositionalError()

units::meter_t pathplanner::PPLTVController::getPositionalError ( )
inlineoverridevirtual

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

Returns
Positional error, in meters

Implements pathplanner::PathFollowingController.

◆ isHolonomic()

bool pathplanner::PPLTVController::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.

◆ reset()

void pathplanner::PPLTVController::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.


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