Class PathfindingCommand

java.lang.Object
edu.wpi.first.wpilibj2.command.Command
com.pathplanner.lib.commands.PathfindingCommand
All Implemented Interfaces:
Sendable

public class PathfindingCommand extends Command
Base pathfinding command
  • 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 to
      constraints - the path constraints to use while pathfinding
      poseSupplier - a supplier for the robot's current pose
      speedsSupplier - 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

      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
    • 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 trains
      constraints - the path constraints to use while pathfinding
      goalEndVel - The goal end velocity when reaching the target pose
      poseSupplier - a supplier for the robot's current pose
      speedsSupplier - 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

      controller - Path following controller that will be used to follow the path
      robotConfig - The robot configuration
      requirements - 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 trains
      constraints - the path constraints to use while pathfinding
      goalEndVel - The goal end velocity when reaching the target pose
      poseSupplier - a supplier for the robot's current pose
      speedsSupplier - 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

      controller - Path following controller that will be used to follow the path
      robotConfig - The robot configuration
      requirements - 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 trains
      constraints - the path constraints to use while pathfinding
      poseSupplier - a supplier for the robot's current pose
      speedsSupplier - 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

      controller - Path following controller that will be used to follow the path
      robotConfig - The robot configuration
      requirements - the subsystems required by this command
  • Method Details

    • initialize

      public void initialize()
      Overrides:
      initialize in class Command
    • execute

      public void execute()
      Overrides:
      execute in class Command
    • isFinished

      public boolean isFinished()
      Overrides:
      isFinished in class Command
    • end

      public void end(boolean interrupted)
      Overrides:
      end in class Command
    • warmupCommand

      public static Command warmupCommand()
      Create a command to warmup the pathfinder and pathfinding command
      Returns:
      Pathfinding warmup command