Class PathPlannerAuto

java.lang.Object
edu.wpi.first.wpilibj2.command.Command
com.pathplanner.lib.commands.PathPlannerAuto
All Implemented Interfaces:
Sendable

public class PathPlannerAuto extends Command
A command that loads and runs an autonomous routine built using PathPlanner.
  • Field Details

    • currentPathName

      public static String currentPathName
      The currently running path name. Used to handle activePath triggers
  • Constructor Details

    • PathPlannerAuto

      public PathPlannerAuto(String autoName)
      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

      public PathPlannerAuto(Command autoCommand, Pose2d startingPose)
      Create a PathPlannerAuto from a custom command
      Parameters:
      autoCommand - The command this auto should run
      startingPose - The starting pose of the auto. Only used for the getStartingPose method
    • PathPlannerAuto

      public PathPlannerAuto(Command autoCommand)
      Create a PathPlannerAuto from a custom command
      Parameters:
      autoCommand - The command this auto should run
  • Method Details

    • getStartingPose

      public Pose2d 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

      public Trigger isRunning()
      Create a trigger that is high when this auto is running, and low when it is not running
      Returns:
      isRunning trigger
    • setCurrentTrajectory

      public static void setCurrentTrajectory(PathPlannerTrajectory trajectory)
      Used by path following commands to inform autos of what trajectory is currently being followed
      Parameters:
      trajectory - The current trajectory being followed
    • timeElapsed

      public Trigger timeElapsed(double time)
      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

      public Trigger timeElapsed(edu.wpi.first.units.measure.Time time)
      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

      public Trigger timeRange(double startTime, double endTime)
      Trigger that is high when within a range of time since the start of this auto
      Parameters:
      startTime - The starting time of the range
      endTime - 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 range
      endTime - The ending time of the range
      Returns:
      timeRange trigger
    • event

      public Trigger event(String eventName)
      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

      public Trigger beforeEvent(String eventName, double timeSeconds)
      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 name
      timeSeconds - The amount of time before the event this trigger should activate, in seconds
      Returns:
      beforeEvent trigger
    • beforeEvent

      public Trigger 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. The trigger will go low after passing the given event.
      Parameters:
      eventName - The event name
      time - The amount of time before the event this trigger should activate
      Returns:
      beforeEvent trigger
    • distanceFromEvent

      public Trigger 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 event
      Parameters:
      eventName - The event name
      distanceMeters - The distance from the event that will activate this trigger, in meters
      Returns:
      distanceFromEvent trigger
    • distanceFromEvent

      public Trigger distanceFromEvent(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 event
      Parameters:
      eventName - The event name
      distance - The distance from the event that will activate this trigger
      Returns:
      distanceFromEvent trigger
    • distanceFromEventEnd

      public Trigger distanceFromEventEnd(String eventName, double distanceMeters)
      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 name
      distanceMeters - 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 name
      distance - The distance from the event that will activate this trigger
      Returns:
      distanceFromEventEnd trigger
    • pointTowardsZone

      public Trigger pointTowardsZone(String zoneName)
      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

      public Trigger activePath(String pathName)
      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

      public Trigger nearFieldPosition(Translation2d fieldPosition, double toleranceMeters)
      Create a trigger that is high when near a given field position. This field position is not automatically flipped
      Parameters:
      fieldPosition - The target field position
      toleranceMeters - 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 position
      tolerance - 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 alliance
      toleranceMeters - 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 alliance
      tolerance - The position tolerance. The trigger will be high when within this distance from the target position
      Returns:
      nearFieldPositionAutoFlipped trigger
    • inFieldArea

      public Trigger inFieldArea(Translation2d boundingBoxMin, Translation2d boundingBoxMax)
      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

      public Trigger condition(BooleanSupplier 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 class Command
    • execute

      public void execute()
      Overrides:
      execute in class Command
    • isFinished

      public boolean isFinished()
      Overrides:
      isFinished in class Command
    • end

      public void end(boolean interrupted)
      Overrides:
      end in class Command
    • 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 read
      org.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