Package com.pathplanner.lib.commands
Class PathPlannerAuto
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
com.pathplanner.lib.commands.PathPlannerAuto
- All Implemented Interfaces:
Sendable
A command that loads and runs an autonomous routine built using PathPlanner.
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.Command
Command.InterruptionBehavior
-
Field Summary
-
Constructor Summary
ConstructorDescriptionPathPlannerAuto
(Command autoCommand) Create a PathPlannerAuto from a custom commandPathPlannerAuto
(Command autoCommand, Pose2d startingPose) Create a PathPlannerAuto from a custom commandPathPlannerAuto
(String autoName) Constructs a new PathPlannerAuto command. -
Method Summary
Modifier and TypeMethodDescriptionactivePath
(String pathName) Create a trigger that is high when a certain path is being followedbeforeEvent
(String eventName, double timeSeconds) Create a trigger that will be activated a given time before an event is reached.beforeEvent
(String eventName, edu.wpi.first.units.measure.Time time) Create a trigger that will be activated a given time before an event is reached.condition
(BooleanSupplier condition) Create a trigger with a custom condition.distanceFromEvent
(String eventName, double distanceMeters) Create a trigger that will be activated when the robot is within a given distance from the start of an eventdistanceFromEvent
(String eventName, edu.wpi.first.units.measure.Distance distance) Create a trigger that will be activated when the robot is within a given distance from the start of an eventdistanceFromEventEnd
(String eventName, double distanceMeters) Create a trigger that will be activated when the robot is within a given distance from the end of an eventdistanceFromEventEnd
(String eventName, edu.wpi.first.units.measure.Distance distance) Create a trigger that will be activated when the robot is within a given distance from the end of an eventvoid
end
(boolean interrupted) Create an EventTrigger that will be polled by this auto instead of globally across all path following commandsvoid
execute()
static List<PathPlannerPath>
getPathGroupFromAutoFile
(String autoName) Get a list of every path in the given auto (depth first)Get the starting pose of this auto, relative to a blue alliance origin.void
hotReload
(org.json.simple.JSONObject autoJson) Reloads the autonomous routine with the given JSON object and updates the requirements of this command.inFieldArea
(Translation2d boundingBoxMin, Translation2d boundingBoxMax) Create a trigger that will be high when the robot is within a given area on the field.inFieldAreaAutoFlipped
(Translation2d blueBoundingBoxMin, Translation2d blueBoundingBoxMax) Create a trigger that will be high when the robot is within a given area on the field.void
boolean
Create a trigger that is high when this auto is running, and low when it is not runningnearFieldPosition
(Translation2d fieldPosition, double toleranceMeters) Create a trigger that is high when near a given field position.nearFieldPosition
(Translation2d fieldPosition, edu.wpi.first.units.measure.Distance tolerance) Create a trigger that is high when near a given field position.nearFieldPositionAutoFlipped
(Translation2d blueFieldPosition, double toleranceMeters) Create a trigger that is high when near a given field position.nearFieldPositionAutoFlipped
(Translation2d blueFieldPosition, edu.wpi.first.units.measure.Distance tolerance) Create a trigger that is high when near a given field position.pointTowardsZone
(String zoneName) Create a PointTowardsZoneTrigger that will be polled by this auto instead of globally across all path following commandsstatic void
setCurrentTrajectory
(PathPlannerTrajectory trajectory) Used by path following commands to inform autos of what trajectory is currently being followedtimeElapsed
(double time) Trigger that is high when the given time has elapsedtimeElapsed
(edu.wpi.first.units.measure.Time time) Trigger that is high when the given time has elapsedtimeRange
(double startTime, double endTime) Trigger that is high when within a range of time since the start of this autotimeRange
(edu.wpi.first.units.measure.Time startTime, edu.wpi.first.units.measure.Time endTime) Trigger that is high when within a range of time since the start of this autoMethods inherited from class edu.wpi.first.wpilibj2.command.Command
addRequirements, addRequirements, alongWith, andThen, andThen, asProxy, beforeStarting, beforeStarting, cancel, deadlineFor, deadlineWith, finallyDo, finallyDo, getInterruptionBehavior, getName, getRequirements, getSubsystem, handleInterrupt, hasRequirement, ignoringDisable, initSendable, isScheduled, onlyIf, onlyWhile, raceWith, repeatedly, runsWhenDisabled, schedule, setName, setSubsystem, unless, until, withInterruptBehavior, withName, withTimeout, withTimeout
-
Field Details
-
currentPathName
The currently running path name. Used to handle activePath triggers
-
-
Constructor Details
-
PathPlannerAuto
Constructs a new PathPlannerAuto command.- Parameters:
autoName
- the name of the autonomous routine to load and run- Throws:
AutoBuilderException
- if AutoBuilder is not configured before attempting to load the autonomous routine
-
PathPlannerAuto
Create a PathPlannerAuto from a custom command- Parameters:
autoCommand
- The command this auto should runstartingPose
- The starting pose of the auto. Only used for the getStartingPose method
-
PathPlannerAuto
Create a PathPlannerAuto from a custom command- Parameters:
autoCommand
- The command this auto should run
-
-
Method Details
-
getStartingPose
Get the starting pose of this auto, relative to a blue alliance origin. If there are no paths in this auto, the starting pose will be null.- Returns:
- The blue alliance starting pose
-
isRunning
Create a trigger that is high when this auto is running, and low when it is not running- Returns:
- isRunning trigger
-
setCurrentTrajectory
Used by path following commands to inform autos of what trajectory is currently being followed- Parameters:
trajectory
- The current trajectory being followed
-
timeElapsed
Trigger that is high when the given time has elapsed- Parameters:
time
- The amount of time this auto should run before the trigger is activated- Returns:
- timeElapsed trigger
-
timeElapsed
Trigger that is high when the given time has elapsed- Parameters:
time
- The amount of time this auto should run before the trigger is activated- Returns:
- timeElapsed trigger
-
timeRange
Trigger that is high when within a range of time since the start of this auto- Parameters:
startTime
- The starting time of the rangeendTime
- The ending time of the range- Returns:
- timeRange trigger
-
timeRange
public Trigger timeRange(edu.wpi.first.units.measure.Time startTime, edu.wpi.first.units.measure.Time endTime) Trigger that is high when within a range of time since the start of this auto- Parameters:
startTime
- The starting time of the rangeendTime
- The ending time of the range- Returns:
- timeRange trigger
-
event
Create an EventTrigger that will be polled by this auto instead of globally across all path following commands- Parameters:
eventName
- The event name that controls this trigger- Returns:
- EventTrigger for this auto
-
beforeEvent
Create a trigger that will be activated a given time before an event is reached. The trigger will go low after passing the given event.- Parameters:
eventName
- The event nametimeSeconds
- The amount of time before the event this trigger should activate, in seconds- Returns:
- beforeEvent trigger
-
beforeEvent
Create a trigger that will be activated a given time before an event is reached. The trigger will go low after passing the given event.- Parameters:
eventName
- The event nametime
- The amount of time before the event this trigger should activate- Returns:
- beforeEvent trigger
-
distanceFromEvent
Create a trigger that will be activated when the robot is within a given distance from the start of an event- Parameters:
eventName
- The event namedistanceMeters
- The distance from the event that will activate this trigger, in meters- Returns:
- distanceFromEvent trigger
-
distanceFromEvent
Create a trigger that will be activated when the robot is within a given distance from the start of an event- Parameters:
eventName
- The event namedistance
- The distance from the event that will activate this trigger- Returns:
- distanceFromEvent trigger
-
distanceFromEventEnd
Create a trigger that will be activated when the robot is within a given distance from the end of an event- Parameters:
eventName
- The event namedistanceMeters
- The distance from the event that will activate this trigger, in meters- Returns:
- distanceFromEventEnd trigger
-
distanceFromEventEnd
public Trigger distanceFromEventEnd(String eventName, edu.wpi.first.units.measure.Distance distance) Create a trigger that will be activated when the robot is within a given distance from the end of an event- Parameters:
eventName
- The event namedistance
- The distance from the event that will activate this trigger- Returns:
- distanceFromEventEnd trigger
-
pointTowardsZone
Create a PointTowardsZoneTrigger that will be polled by this auto instead of globally across all path following commands- Parameters:
zoneName
- The point towards zone name that controls this trigger- Returns:
- PointTowardsZoneTrigger for this auto
-
activePath
Create a trigger that is high when a certain path is being followed- Parameters:
pathName
- The name of the path to check for- Returns:
- activePath trigger
-
nearFieldPosition
Create a trigger that is high when near a given field position. This field position is not automatically flipped- Parameters:
fieldPosition
- The target field positiontoleranceMeters
- The position tolerance, in meters. The trigger will be high when within this distance from the target position- Returns:
- nearFieldPosition trigger
-
nearFieldPosition
public Trigger nearFieldPosition(Translation2d fieldPosition, edu.wpi.first.units.measure.Distance tolerance) Create a trigger that is high when near a given field position. This field position is not automatically flipped- Parameters:
fieldPosition
- The target field positiontolerance
- The position tolerance. The trigger will be high when within this distance from the target position- Returns:
- nearFieldPosition trigger
-
nearFieldPositionAutoFlipped
public Trigger nearFieldPositionAutoFlipped(Translation2d blueFieldPosition, double toleranceMeters) Create a trigger that is high when near a given field position. This field position will be automatically flipped- Parameters:
blueFieldPosition
- The target field position if on the blue alliancetoleranceMeters
- The position tolerance, in meters. The trigger will be high when within this distance from the target position- Returns:
- nearFieldPositionAutoFlipped trigger
-
nearFieldPositionAutoFlipped
public Trigger nearFieldPositionAutoFlipped(Translation2d blueFieldPosition, edu.wpi.first.units.measure.Distance tolerance) Create a trigger that is high when near a given field position. This field position will be automatically flipped- Parameters:
blueFieldPosition
- The target field position if on the blue alliancetolerance
- The position tolerance. The trigger will be high when within this distance from the target position- Returns:
- nearFieldPositionAutoFlipped trigger
-
inFieldArea
Create a trigger that will be high when the robot is within a given area on the field. These positions will not be automatically flipped- Parameters:
boundingBoxMin
- The minimum position of the bounding box for the target field area. The X and Y coordinates of this position should be less than the max position.boundingBoxMax
- The maximum position of the bounding box for the target field area. The X and Y coordinates of this position should be greater than the min position.- Returns:
- inFieldArea trigger
-
inFieldAreaAutoFlipped
public Trigger inFieldAreaAutoFlipped(Translation2d blueBoundingBoxMin, Translation2d blueBoundingBoxMax) Create a trigger that will be high when the robot is within a given area on the field. These positions will be automatically flipped- Parameters:
blueBoundingBoxMin
- The minimum position of the bounding box for the target field area if on the blue alliance. The X and Y coordinates of this position should be less than the max position.blueBoundingBoxMax
- The maximum position of the bounding box for the target field area if on the blue alliance. The X and Y coordinates of this position should be greater than the min position.- Returns:
- inFieldAreaAutoFlipped trigger
-
condition
Create a trigger with a custom condition. This will be polled by this auto's event loop so that its condition is only polled when this auto is running.- Parameters:
condition
- The condition represented by this trigger- Returns:
- Custom condition trigger
-
initialize
public void initialize()- Overrides:
initialize
in classCommand
-
execute
public void execute() -
isFinished
public boolean isFinished()- Overrides:
isFinished
in classCommand
-
end
public void end(boolean interrupted) -
getPathGroupFromAutoFile
public static List<PathPlannerPath> getPathGroupFromAutoFile(String autoName) throws IOException, org.json.simple.parser.ParseException Get a list of every path in the given auto (depth first)- Parameters:
autoName
- Name of the auto to get the path group from- Returns:
- List of paths in the auto
- Throws:
IOException
- if attempting to load a file that does not exist or cannot be readorg.json.simple.parser.ParseException
- If JSON within file cannot be parsed
-
hotReload
public void hotReload(org.json.simple.JSONObject autoJson) Reloads the autonomous routine with the given JSON object and updates the requirements of this command.- Parameters:
autoJson
- the JSON object representing the updated autonomous routine
-