|
Robot Core Documentation
|
Static Public Member Functions | |
| static Pose2d | getStaringPoseFromAutoFile (String autoName) |
| static List< PathPlannerPath > | getPathGroupFromAutoFile (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< Subsystem > | m_requirements = new HashSet<>() |
A command that loads and runs an autonomous routine built using PathPlanner.
| com.pathplanner.lib.commands.PathPlannerAuto.PathPlannerAuto | ( | String | autoName | ) |
Constructs a new PathPlannerAuto command.
| autoName | the name of the autonomous routine to load and run |
| RuntimeException | if AutoBuilder is not configured before attempting to load the autonomous routine |
| 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.
| interrupted | whether the command was interrupted/canceled |
Reimplemented from edu.wpi.first.wpilibj2.command.Command.
| 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.
|
static |
Get a list of every path in the given auto (depth first)
| autoName | Name of the auto to get the path group from |
|
static |
Get the starting pose from the given auto file
| autoName | Name of the auto to get the pose from |
| 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.
| autoJson | the JSON object representing the updated autonomous routine |
| 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.
| 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.
Reimplemented from edu.wpi.first.wpilibj2.command.Command.