|
Robot Core Documentation
|
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< 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) |
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< Subsystem > | m_requirements = new HashSet<>() |
Base pathfinding command
| 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.
| 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 |
| outputRobotRelative | a consumer for the output speeds (robot relative) |
| controller | Path following controller that will be used to follow the path |
| rotationDelayDistance | How far the robot should travel before attempting to rotate to the final rotation |
| replanningConfig | Path replanning 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 |
| 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.
| 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 |
| outputRobotRelative | a consumer for the output speeds (robot relative) |
| controller | Path following controller that will be used to follow the path |
| rotationDelayDistance | How far the robot should travel before attempting to rotate to the final rotation |
| replanningConfig | Path replanning configuration |
| requirements | the subsystems required by this command |
| 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.
| interrupted | whether the command was interrupted/canceled |
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
| 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.
| 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.
| 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.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.