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

Public Member Functions

 PathPlannerAuto (String autoName)
 
void hotReload (JSONObject autoJson)
 
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

Static Public Member Functions

static Pose2d getStaringPoseFromAutoFile (String autoName)
 
static List< PathPlannerPathgetPathGroupFromAutoFile (String autoName)
 

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 that loads and runs an autonomous routine built using PathPlanner.

Constructor & Destructor Documentation

◆ PathPlannerAuto()

com.pathplanner.lib.commands.PathPlannerAuto.PathPlannerAuto ( String autoName)

Constructs a new PathPlannerAuto command.

Parameters
autoNamethe name of the autonomous routine to load and run
Exceptions
RuntimeExceptionif AutoBuilder is not configured before attempting to load the autonomous routine

Member Function Documentation

◆ end()

void com.pathplanner.lib.commands.PathPlannerAuto.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.PathPlannerAuto.execute ( )

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

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

◆ getPathGroupFromAutoFile()

static List< PathPlannerPath > com.pathplanner.lib.commands.PathPlannerAuto.getPathGroupFromAutoFile ( String autoName)
static

Get a list of every path in the given auto (depth first)

Parameters
autoNameName of the auto to get the path group from
Returns
List of paths in the auto

◆ getStaringPoseFromAutoFile()

static Pose2d com.pathplanner.lib.commands.PathPlannerAuto.getStaringPoseFromAutoFile ( String autoName)
static

Get the starting pose from the given auto file

Parameters
autoNameName of the auto to get the pose from
Returns
Starting pose from the given auto

◆ hotReload()

void com.pathplanner.lib.commands.PathPlannerAuto.hotReload ( JSONObject autoJson)

Reloads the autonomous routine with the given JSON object and updates the requirements of this command.

Parameters
autoJsonthe JSON object representing the updated autonomous routine

◆ initialize()

void com.pathplanner.lib.commands.PathPlannerAuto.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.PathPlannerAuto.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: