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

Public Member Functions

 PathfindingCommand (std::shared_ptr< PathPlannerPath > targetPath, PathConstraints constraints, 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)
 
 PathfindingCommand (frc::Pose2d targetPose, PathConstraints constraints, units::meters_per_second_t goalEndVel, 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, frc2::Requirements requirements)
 
void Initialize () override
 
void Execute () override
 
bool IsFinished () override
 
void End (bool interrupted) override
 

Constructor & Destructor Documentation

◆ PathfindingCommand() [1/2]

PathfindingCommand::PathfindingCommand ( std::shared_ptr< PathPlannerPath targetPath,
PathConstraints  constraints,
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 
)

Constructs a new base pathfinding command that will generate a path towards the given path.

Parameters
targetPaththe path to pathfind to
constraintsthe path constraints to use while pathfinding
poseSuppliera supplier for the robot's current pose
speedsSuppliera supplier for the robot's current robot relative speeds
outputOutput 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
controllerPath following controller that will be used to follow the path
robotConfigThe robot configuration
shouldFlipPathShould the target path be flipped to the other side of the field? This will maintain a global blue alliance origin.
requirementsthe subsystems required by this command

◆ PathfindingCommand() [2/2]

PathfindingCommand::PathfindingCommand ( frc::Pose2d  targetPose,
PathConstraints  constraints,
units::meters_per_second_t  goalEndVel,
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,
frc2::Requirements  requirements 
)

Constructs a new base pathfinding command that will generate a path towards the given pose.

Parameters
targetPosethe pose to pathfind to, the rotation component is only relevant for holonomic drive trains
constraintsthe path constraints to use while pathfinding
goalEndVelThe goal end velocity when reaching the target pose
poseSuppliera supplier for the robot's current pose
speedsSuppliera supplier for the robot's current robot relative speeds
outputOutput 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
controllerPath following controller that will be used to follow the path
robotConfigThe robot configuration
requirementsthe subsystems required by this command

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