Package com.pathplanner.lib.commands
Class FollowPathCommand
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
com.pathplanner.lib.commands.FollowPathCommand
- All Implemented Interfaces:
Sendable
Base command for following a path
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.Command
Command.InterruptionBehavior
-
Constructor Summary
ConstructorDescriptionFollowPathCommand
(PathPlannerPath path, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, BooleanSupplier shouldFlipPath, Subsystem... requirements) Construct a base path following command -
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
-
FollowPathCommand
public FollowPathCommand(PathPlannerPath path, Supplier<Pose2d> poseSupplier, Supplier<ChassisSpeeds> speedsSupplier, BiConsumer<ChassisSpeeds, DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, BooleanSupplier shouldFlipPath, Subsystem... requirements) Construct a base path following command- Parameters:
path
- The path to followposeSupplier
- Function that supplies the current field-relative pose of the robotspeedsSupplier
- Function that supplies the current robot-relative chassis 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 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
-
-
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 on-the-fly generation, replanning, and the path following command- Returns:
- Path following warmup command
-