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

Public Member Functions

 PathfindThenFollowPathHolonomic (PathPlannerPath goalPath, PathConstraints pathfindingConstraints, Supplier< Pose2d > poseSupplier, Supplier< ChassisSpeeds > currentRobotRelativeSpeeds, Consumer< ChassisSpeeds > robotRelativeOutput, HolonomicPathFollowerConfig config, double rotationDelayDistance, BooleanSupplier shouldFlipPath, Subsystem... requirements)
 
 PathfindThenFollowPathHolonomic (PathPlannerPath goalPath, PathConstraints pathfindingConstraints, Supplier< Pose2d > poseSupplier, Supplier< ChassisSpeeds > currentRobotRelativeSpeeds, Consumer< ChassisSpeeds > robotRelativeOutput, HolonomicPathFollowerConfig config, BooleanSupplier shouldFlipPath, Subsystem... requirements)
 
- Public Member Functions inherited from edu.wpi.first.wpilibj2.command.SequentialCommandGroup
 SequentialCommandGroup (Command... commands)
 
final void addCommands (Command... commands)
 
final void initialize ()
 
final void execute ()
 
final void end (boolean interrupted)
 
final boolean isFinished ()
 
boolean runsWhenDisabled ()
 
InterruptionBehavior getInterruptionBehavior ()
 
void initSendable (SendableBuilder builder)
 
- 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)
 
WrapperCommand withName (String name)
 
- 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

A command group that first pathfinds to a goal path and then follows the goal path.

Constructor & Destructor Documentation

◆ PathfindThenFollowPathHolonomic() [1/2]

com.pathplanner.lib.commands.PathfindThenFollowPathHolonomic.PathfindThenFollowPathHolonomic ( PathPlannerPath goalPath,
PathConstraints pathfindingConstraints,
Supplier< Pose2d > poseSupplier,
Supplier< ChassisSpeeds > currentRobotRelativeSpeeds,
Consumer< ChassisSpeeds > robotRelativeOutput,
HolonomicPathFollowerConfig config,
double rotationDelayDistance,
BooleanSupplier shouldFlipPath,
Subsystem... requirements )

Constructs a new PathfindThenFollowPathHolonomic command group.

Parameters
goalPaththe goal path to follow
pathfindingConstraintsthe path constraints for pathfinding
poseSuppliera supplier for the robot's current pose
currentRobotRelativeSpeedsa supplier for the robot's current robot relative speeds
robotRelativeOutputa consumer for the output speeds (robot relative)
configcom.pathplanner.lib.util.HolonomicPathFollowerConfig for configuring the path following commands
rotationDelayDistanceDistance to delay the target rotation of the robot. This will cause the robot to hold its current rotation until it reaches the given distance along the path.
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 (drive subsystem)

◆ PathfindThenFollowPathHolonomic() [2/2]

com.pathplanner.lib.commands.PathfindThenFollowPathHolonomic.PathfindThenFollowPathHolonomic ( PathPlannerPath goalPath,
PathConstraints pathfindingConstraints,
Supplier< Pose2d > poseSupplier,
Supplier< ChassisSpeeds > currentRobotRelativeSpeeds,
Consumer< ChassisSpeeds > robotRelativeOutput,
HolonomicPathFollowerConfig config,
BooleanSupplier shouldFlipPath,
Subsystem... requirements )

Constructs a new PathfindThenFollowPathHolonomic command group.

Parameters
goalPaththe goal path to follow
pathfindingConstraintsthe path constraints for pathfinding
poseSuppliera supplier for the robot's current pose
currentRobotRelativeSpeedsa supplier for the robot's current robot relative speeds
robotRelativeOutputa consumer for the output speeds (robot relative)
configcom.pathplanner.lib.util.HolonomicPathFollowerConfig for configuring the path following commands
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 (drive subsystem)

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