Robot Core Documentation
Loading...
Searching...
No Matches
com.pathplanner.lib.commands.PathfindingCommand Class Reference
Inheritance diagram for com.pathplanner.lib.commands.PathfindingCommand:
edu.wpi.first.wpilibj2.command.Command edu.wpi.first.util.sendable.Sendable com.pathplanner.lib.commands.PathfindHolonomic com.pathplanner.lib.commands.PathfindLTV com.pathplanner.lib.commands.PathfindRamsete

Public Member Functions

 PathfindingCommand (PathPlannerPath targetPath, PathConstraints constraints, Supplier< Pose2d > poseSupplier, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > outputRobotRelative, PathFollowingController controller, double rotationDelayDistance, ReplanningConfig replanningConfig, BooleanSupplier shouldFlipPath, Subsystem... requirements)
 
 PathfindingCommand (Pose2d targetPose, PathConstraints constraints, double goalEndVel, Supplier< Pose2d > poseSupplier, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > outputRobotRelative, PathFollowingController controller, double rotationDelayDistance, ReplanningConfig replanningConfig, Subsystem... requirements)
 
void initialize ()
 
void execute ()
 
boolean isFinished ()
 
void end (boolean interrupted)
 
- Public Member Functions inherited from edu.wpi.first.wpilibj2.command.Command
Set< SubsystemgetRequirements ()
 
final void addRequirements (Subsystem... requirements)
 
String getName ()
 
void setName (String name)
 
String getSubsystem ()
 
void setSubsystem (String subsystem)
 
ParallelRaceGroup withTimeout (double seconds)
 
ParallelRaceGroup until (BooleanSupplier condition)
 
ParallelRaceGroup onlyWhile (BooleanSupplier condition)
 
SequentialCommandGroup beforeStarting (Runnable toRun, Subsystem... requirements)
 
SequentialCommandGroup beforeStarting (Command before)
 
SequentialCommandGroup andThen (Runnable toRun, Subsystem... requirements)
 
SequentialCommandGroup andThen (Command... next)
 
ParallelDeadlineGroup deadlineWith (Command... parallel)
 
ParallelCommandGroup alongWith (Command... parallel)
 
ParallelRaceGroup raceWith (Command... parallel)
 
RepeatCommand repeatedly ()
 
ProxyCommand asProxy ()
 
ConditionalCommand unless (BooleanSupplier condition)
 
ConditionalCommand onlyIf (BooleanSupplier condition)
 
WrapperCommand ignoringDisable (boolean doesRunWhenDisabled)
 
WrapperCommand withInterruptBehavior (InterruptionBehavior interruptBehavior)
 
WrapperCommand finallyDo (BooleanConsumer end)
 
WrapperCommand finallyDo (Runnable end)
 
WrapperCommand handleInterrupt (Runnable handler)
 
void schedule ()
 
void cancel ()
 
boolean isScheduled ()
 
boolean hasRequirement (Subsystem requirement)
 
InterruptionBehavior getInterruptionBehavior ()
 
boolean runsWhenDisabled ()
 
WrapperCommand withName (String name)
 
void initSendable (SendableBuilder builder)
 
- Public Member Functions inherited from edu.wpi.first.util.sendable.Sendable

Additional Inherited Members

- Protected Member Functions inherited from edu.wpi.first.wpilibj2.command.Command
 Command ()
 
- Protected Attributes inherited from edu.wpi.first.wpilibj2.command.Command
Set< Subsystemm_requirements = new HashSet<>()
 

Detailed Description

Base pathfinding command

Constructor & Destructor Documentation

◆ PathfindingCommand() [1/2]

com.pathplanner.lib.commands.PathfindingCommand.PathfindingCommand ( PathPlannerPath targetPath,
PathConstraints constraints,
Supplier< Pose2d > poseSupplier,
Supplier< ChassisSpeeds > speedsSupplier,
Consumer< ChassisSpeeds > outputRobotRelative,
PathFollowingController controller,
double rotationDelayDistance,
ReplanningConfig replanningConfig,
BooleanSupplier shouldFlipPath,
Subsystem... 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
outputRobotRelativea consumer for the output speeds (robot relative)
controllerPath following controller that will be used to follow the path
rotationDelayDistanceHow far the robot should travel before attempting to rotate to the final rotation
replanningConfigPath replanning 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]

com.pathplanner.lib.commands.PathfindingCommand.PathfindingCommand ( Pose2d targetPose,
PathConstraints constraints,
double goalEndVel,
Supplier< Pose2d > poseSupplier,
Supplier< ChassisSpeeds > speedsSupplier,
Consumer< ChassisSpeeds > outputRobotRelative,
PathFollowingController controller,
double rotationDelayDistance,
ReplanningConfig replanningConfig,
Subsystem... 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
outputRobotRelativea consumer for the output speeds (robot relative)
controllerPath following controller that will be used to follow the path
rotationDelayDistanceHow far the robot should travel before attempting to rotate to the final rotation
replanningConfigPath replanning configuration
requirementsthe subsystems required by this command

Member Function Documentation

◆ end()

void com.pathplanner.lib.commands.PathfindingCommand.end ( boolean interrupted)

The action to take when the command ends. Called when either the command finishes normally, or when it interrupted/canceled.

Do not schedule commands here that share requirements with this command. Use andThen(Command...) instead.

Parameters
interruptedwhether the command was interrupted/canceled

Reimplemented from edu.wpi.first.wpilibj2.command.Command.

◆ execute()

void com.pathplanner.lib.commands.PathfindingCommand.execute ( )

The main body of a command. Called repeatedly while the command is scheduled.

Reimplemented from edu.wpi.first.wpilibj2.command.Command.

◆ initialize()

void com.pathplanner.lib.commands.PathfindingCommand.initialize ( )

The initial subroutine of a command. Called once when the command is initially scheduled.

Reimplemented from edu.wpi.first.wpilibj2.command.Command.

◆ isFinished()

boolean com.pathplanner.lib.commands.PathfindingCommand.isFinished ( )

Whether the command has finished. Once a command finishes, the scheduler will call its end() method and un-schedule it.

Returns
whether the command has finished.

Reimplemented from edu.wpi.first.wpilibj2.command.Command.


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