Robot Core Documentation
|
Public Member Functions | |
FollowPathCommand (PathPlannerPath path, Supplier< Pose2d > poseSupplier, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > outputRobotRelative, PathFollowingController controller, ReplanningConfig replanningConfig, BooleanSupplier shouldFlipPath, Subsystem... requirements) | |
void | initialize () |
void | execute () |
boolean | isFinished () |
void | end (boolean interrupted) |
![]() | |
Set< Subsystem > | getRequirements () |
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) |
![]() |
Additional Inherited Members | |
![]() | |
Command () | |
![]() | |
Set< Subsystem > | m_requirements = new HashSet<>() |
Base command for following a path
com.pathplanner.lib.commands.FollowPathCommand.FollowPathCommand | ( | PathPlannerPath | path, |
Supplier< Pose2d > | poseSupplier, | ||
Supplier< ChassisSpeeds > | speedsSupplier, | ||
Consumer< ChassisSpeeds > | outputRobotRelative, | ||
PathFollowingController | controller, | ||
ReplanningConfig | replanningConfig, | ||
BooleanSupplier | shouldFlipPath, | ||
Subsystem... | requirements ) |
Construct a base path following command
path | The path to follow |
poseSupplier | Function that supplies the current field-relative pose of the robot |
speedsSupplier | Function that supplies the current robot-relative chassis speeds |
outputRobotRelative | Function that will apply the robot-relative output speeds of this command |
controller | Path following controller that will be used to follow the path |
replanningConfig | Path replanning configuration |
shouldFlipPath | 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 |
void com.pathplanner.lib.commands.FollowPathCommand.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.
interrupted | whether the command was interrupted/canceled |
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
void com.pathplanner.lib.commands.FollowPathCommand.execute | ( | ) |
The main body of a command. Called repeatedly while the command is scheduled.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
void com.pathplanner.lib.commands.FollowPathCommand.initialize | ( | ) |
The initial subroutine of a command. Called once when the command is initially scheduled.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
boolean com.pathplanner.lib.commands.FollowPathCommand.isFinished | ( | ) |
Whether the command has finished. Once a command finishes, the scheduler will call its end() method and un-schedule it.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.