|
| 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 ¤tPose, const PathPlannerTrajectoryState &targetState) override |
|
void | reset (const frc::Pose2d ¤tPose, const frc::ChassisSpeeds ¤tSpeeds) override |
|
units::meter_t | getPositionalError () override |
|
bool | isHolonomic () override |
|
virtual frc::ChassisSpeeds | calculateRobotRelativeSpeeds (const frc::Pose2d ¤tPose, const PathPlannerTrajectoryState &targetState)=0 |
|
virtual void | reset (const frc::Pose2d ¤tPose, const frc::ChassisSpeeds ¤tSpeeds)=0 |
|
virtual units::meter_t | getPositionalError ()=0 |
|
virtual bool | isHolonomic ()=0 |
|
◆ 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
-
dt | Discretization timestep in seconds. |
maxVelocity | The 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 |
◆ calculateRobotRelativeSpeeds()
frc::ChassisSpeeds pathplanner::PPLTVController::calculateRobotRelativeSpeeds |
( |
const frc::Pose2d & |
currentPose, |
|
|
const PathPlannerTrajectoryState & |
targetState |
|
) |
| |
|
inlineoverridevirtual |
Calculates the next output of the path following controller
- Parameters
-
currentPose | The current robot pose |
targetState | The 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 |
◆ 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
-
currentPose | Current robot pose |
currentSpeeds | Current robot relative chassis speeds |
Implements pathplanner::PathFollowingController.
The documentation for this class was generated from the following file: