◆ PathfindThenFollowPath()
pathplanner::PathfindThenFollowPath::PathfindThenFollowPath |
( |
std::shared_ptr< PathPlannerPath > |
goalPath, |
|
|
PathConstraints |
pathfindingConstraints, |
|
|
std::function< frc::Pose2d()> |
poseSupplier, |
|
|
std::function< frc::ChassisSpeeds()> |
currentRobotRelativeSpeeds, |
|
|
std::function< void(const frc::ChassisSpeeds &, const DriveFeedforwards &)> |
output, |
|
|
std::shared_ptr< PathFollowingController > |
controller, |
|
|
RobotConfig |
robotConfig, |
|
|
std::function< bool()> |
shouldFlipPath, |
|
|
frc2::Requirements |
requirements |
|
) |
| |
|
inline |
Constructs a new PathfindThenFollowPath command group.
- Parameters
-
goalPath | the goal path to follow |
pathfindingConstraints | the path constraints for pathfinding |
poseSupplier | a supplier for the robot's current pose |
currentRobotRelativeSpeeds | a supplier for the robot's current robot relative 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 target path be flipped to the other side of the field? This will maintain a global blue alliance origin. |
requirements | the subsystems required by this command (drive subsystem) |
The documentation for this class was generated from the following file: