|
| FollowPathCommand (std::shared_ptr< PathPlannerPath > path, std::function< frc::Pose2d()> poseSupplier, std::function< frc::ChassisSpeeds()> speedsSupplier, std::function< void(const frc::ChassisSpeeds &, const DriveFeedforwards &)> output, std::shared_ptr< PathFollowingController > controller, RobotConfig robotConfig, std::function< bool()> shouldFlipPath, frc2::Requirements requirements) |
|
void | Initialize () override |
|
void | Execute () override |
|
bool | IsFinished () override |
|
void | End (bool interrupted) override |
|
◆ FollowPathCommand()
FollowPathCommand::FollowPathCommand |
( |
std::shared_ptr< PathPlannerPath > |
path, |
|
|
std::function< frc::Pose2d()> |
poseSupplier, |
|
|
std::function< frc::ChassisSpeeds()> |
speedsSupplier, |
|
|
std::function< void(const frc::ChassisSpeeds &, const DriveFeedforwards &)> |
output, |
|
|
std::shared_ptr< PathFollowingController > |
controller, |
|
|
RobotConfig |
robotConfig, |
|
|
std::function< bool()> |
shouldFlipPath, |
|
|
frc2::Requirements |
requirements |
|
) |
| |
Construct a base path following command
- Parameters
-
path | The path to follow |
poseSupplier | Function that supplies the current field-relative pose of the robot |
speedsSupplier | Function that supplies the current robot-relative chassis speeds |
output | Output function that accepts robot-relative ChassisSpeeds and feedforwards for each drive motor. If using swerve, these feedforwards will be in FL, FR, BL, BR order. If using a differential drive, they will be in L, R order. |
NOTE: These feedforwards are assuming unoptimized module states. When you optimize your module states, you will need to reverse the feedforwards for modules that have been flipped
- Parameters
-
controller | Path following controller that will be used to follow the path |
robotConfig | The robot configuration |
shouldFlipPath | Should the path be flipped to the other side of the field? This will maintain a global blue alliance origin. |
requirements | Subsystems required by this command, usually just the drive subsystem |
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/commands/FollowPathCommand.h
- src/main/native/cpp/pathplanner/lib/commands/FollowPathCommand.cpp