Package com.pathplanner.lib.commands
Class PathfindingCommand
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
com.pathplanner.lib.commands.PathfindingCommand
- All Implemented Interfaces:
Sendable
Base pathfinding command
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.Command
Command.InterruptionBehavior
-
Constructor Summary
ConstructorDescriptionPathfindingCommand
(PathPlannerPath targetPath, PathConstraints constraints, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, BooleanSupplier shouldFlipPath, Subsystem... requirements) Constructs a new base pathfinding command that will generate a path towards the given path.PathfindingCommand
(Pose2d targetPose, PathConstraints constraints, double goalEndVel, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, Subsystem... requirements) Constructs a new base pathfinding command that will generate a path towards the given pose.PathfindingCommand
(Pose2d targetPose, PathConstraints constraints, edu.wpi.first.units.measure.LinearVelocity goalEndVel, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, Subsystem... requirements) Constructs a new base pathfinding command that will generate a path towards the given pose.PathfindingCommand
(Pose2d targetPose, PathConstraints constraints, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, Subsystem... requirements) Constructs a new base pathfinding command that will generate a path towards the given pose. -
Method Summary
Methods inherited from class edu.wpi.first.wpilibj2.command.Command
addRequirements, addRequirements, alongWith, andThen, andThen, asProxy, beforeStarting, beforeStarting, cancel, deadlineFor, deadlineWith, finallyDo, finallyDo, getInterruptionBehavior, getName, getRequirements, getSubsystem, handleInterrupt, hasRequirement, ignoringDisable, initSendable, isScheduled, onlyIf, onlyWhile, raceWith, repeatedly, runsWhenDisabled, schedule, setName, setSubsystem, unless, until, withInterruptBehavior, withName, withTimeout, withTimeout
-
Constructor Details
-
PathfindingCommand
public PathfindingCommand(PathPlannerPath targetPath, PathConstraints constraints, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, BooleanSupplier shouldFlipPath, Subsystem... requirements) Constructs a new base pathfinding command that will generate a path towards the given path.- Parameters:
targetPath
- the path to pathfind toconstraints
- the path constraints to use while pathfindingposeSupplier
- a supplier for the robot's current posespeedsSupplier
- a supplier for the robot's current robot relative speedsoutput
- 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
controller
- Path following controller that will be used to follow the pathrobotConfig
- The robot configurationshouldFlipPath
- 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
-
PathfindingCommand
public PathfindingCommand(Pose2d targetPose, PathConstraints constraints, double goalEndVel, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, Subsystem... requirements) Constructs a new base pathfinding command that will generate a path towards the given pose.- Parameters:
targetPose
- the pose to pathfind to, the rotation component is only relevant for holonomic drive trainsconstraints
- the path constraints to use while pathfindinggoalEndVel
- The goal end velocity when reaching the target poseposeSupplier
- a supplier for the robot's current posespeedsSupplier
- a supplier for the robot's current robot relative speedsoutput
- 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
controller
- Path following controller that will be used to follow the pathrobotConfig
- The robot configurationrequirements
- the subsystems required by this command
-
PathfindingCommand
public PathfindingCommand(Pose2d targetPose, PathConstraints constraints, edu.wpi.first.units.measure.LinearVelocity goalEndVel, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, Subsystem... requirements) Constructs a new base pathfinding command that will generate a path towards the given pose.- Parameters:
targetPose
- the pose to pathfind to, the rotation component is only relevant for holonomic drive trainsconstraints
- the path constraints to use while pathfindinggoalEndVel
- The goal end velocity when reaching the target poseposeSupplier
- a supplier for the robot's current posespeedsSupplier
- a supplier for the robot's current robot relative speedsoutput
- 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
controller
- Path following controller that will be used to follow the pathrobotConfig
- The robot configurationrequirements
- the subsystems required by this command
-
PathfindingCommand
public PathfindingCommand(Pose2d targetPose, PathConstraints constraints, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, Subsystem... requirements) Constructs a new base pathfinding command that will generate a path towards the given pose.- Parameters:
targetPose
- the pose to pathfind to, the rotation component is only relevant for holonomic drive trainsconstraints
- the path constraints to use while pathfindingposeSupplier
- a supplier for the robot's current posespeedsSupplier
- a supplier for the robot's current robot relative speedsoutput
- 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
controller
- Path following controller that will be used to follow the pathrobotConfig
- The robot configurationrequirements
- the subsystems required by this command
-
-
Method Details
-
initialize
public void initialize()- Overrides:
initialize
in classCommand
-
execute
public void execute() -
isFinished
public boolean isFinished()- Overrides:
isFinished
in classCommand
-
end
public void end(boolean interrupted) -
warmupCommand
Create a command to warmup the pathfinder and pathfinding command- Returns:
- Pathfinding warmup command
-