Class PathfinderBuilder

java.lang.Object
me.nabdev.pathfinding.PathfinderBuilder

public class PathfinderBuilder extends Object
Builder class for Pathfinder
  • Constructor Details

    • PathfinderBuilder

      public PathfinderBuilder(FieldLoader.Field field)
      Creates a new PathfinderBuilder with the given FieldLoader.Field
      Parameters:
      field - The FieldLoader.Field to use
    • PathfinderBuilder

      public PathfinderBuilder(String field)
      Creates a new PathfinderBuilder with the given field json map. Recommended to store this in the deploy directory and use Filesystem.getDeployDirectory() to get the path so it works on the rio and in sim.
      Parameters:
      field - The full path to the field json map to use
  • Method Details

    • setPointSpacing

      public PathfinderBuilder setPointSpacing(double pointSpacing)
      Sets the point spacing (space between injected points on straightaways when generating paths)
      Parameters:
      pointSpacing - The point spacing, default 0.25 (meters)
      Returns:
      The builder
    • setCornerPointSpacing

      public PathfinderBuilder setCornerPointSpacing(double cornerPointSpacing)
      Sets the corner point spacing (space between points on curves when generating paths)
      Parameters:
      cornerPointSpacing - The corner point spacing, default 0.08
      Returns:
      The builder
    • setCornerDist

      public PathfinderBuilder setCornerDist(double cornerDist)
      Sets the corner distance (how far back along the straightaway to dedicate to making corners)
      Parameters:
      cornerDist - The corner distance, default 0.6 (meters)
      Returns:
      The builder
    • setRobotWidth

      public PathfinderBuilder setRobotWidth(double robotWidth)
      Sets the robot width in meters (used to calculate the clearance)
      Parameters:
      robotWidth - The clearance, default 0.7 (meters)
      Returns:
      The builder
    • setRobotLength

      public PathfinderBuilder setRobotLength(double robotLength)
      Sets the robot length in meters (used to calculate the clearance)
      Parameters:
      robotLength - The clearance, default 0.7 (meters)
      Returns:
      The builder
    • setCornerSplitPercent

      public PathfinderBuilder setCornerSplitPercent(double cornerSplitPercent)
      Sets the corner split percent (how far each bezier curve should move towards the other point if the distance is too short to allow both corners the full corner distance)
      Parameters:
      cornerSplitPercent - The corner split percent, default 0.45 (max 0.5)
      Returns:
      The builder
    • setInjectPoints

      public PathfinderBuilder setInjectPoints(boolean injectPoints)
      Sets whether or not to inject points (add points in the middle of straightaways, useful for certain path following algorithms)
      Parameters:
      injectPoints - Whether or not to inject points, default false
      Returns:
      The builder
    • setNormalizeCorners

      public PathfinderBuilder setNormalizeCorners(boolean normalizeCorners)
      Sets whether or not to normalize corners (make sure that corner points are spaced evenly). Disabling this can greatly help path generation with a higher corner dist and can remove weird artifacts between corners, but will cause issues with certain path following algorithms.
      Parameters:
      normalizeCorners - Whether or not to normalize corners, default true
      Returns:
      The builder
    • setSearchAlgorithmType

      public PathfinderBuilder setSearchAlgorithmType(SearchAlgorithm.SearchAlgorithmType searchAlgorithmType)
      Sets the search algorithm type to use
      Parameters:
      searchAlgorithmType - The search algorithm type, default ASTAR
      Returns:
      The builder
    • setCornerCuttingType

      public PathfinderBuilder setCornerCuttingType(FieldLoader.CornerCutting cornerCutting)
      Sets the corner cutting type to use (See FieldLoader.CornerCutting for more info)
      Parameters:
      cornerCutting - The corner cutting type, default LINE
      Returns:
      The builder
    • setProfiling

      public PathfinderBuilder setProfiling(boolean profiling)
      Sets whether or not to profile the pathfinder (Output path gen time to smartdashboard)
      Parameters:
      profiling - Whether or not to profile the pathfinder, default false
      Returns:
      The builder
    • setEndgameTime

      public PathfinderBuilder setEndgameTime(double endgameTime)
      Sets the endgame time (time in seconds when the robot should start to consider endgame obstacles). Note that this uses DriverStation.getMatchTime(), so it is not perfectly accurate, and does not work properly when teleop/auto is manually enabled from the driver station (practice mode works fine) It is recommended to set this to 0 when testing in teleop.
      Parameters:
      endgameTime - The endgame time, default 25 (seconds)
      Returns:
      The builder
    • build

      public Pathfinder build()
      Builds the Pathfinder
      Returns:
      The Pathfinder