Class PurePursuitCommand

All Implemented Interfaces:
Sendable, IPropertySupport
Direct Known Subclasses:
ConfigurablePurePursuitCommand

public abstract class PurePursuitCommand extends BaseCommand
  • Field Details

  • Constructor Details

    • PurePursuitCommand

      public PurePursuitCommand(HeadingModule.HeadingModuleFactory headingModuleFactory, BasePoseSubsystem pose, BaseDriveSubsystem drive, PropertyFactory propMan)
      An implementation of Pure Pursuit for FRC. We got the basic idea from here: http://www8.cs.umu.se/kurser/TDBD17/VT06/utdelat/Assignment%20Papers/Path%20Tracking%20for%20a%20Miniature%20Robot.pdf Fundamentally, you can add field points to this command (x,y, and rotation) and the robot will attempt to reach all those points with a smooth path. This works for any drive base, but presumably, holonomic robots can solve this problem more effectively. You will see references to rabbits, or "chasing the rabbit". This is alluding to how greyhoud races use mechanical rabbits, which is designed to always stay ahead of them, regardless of their speed. This is similiar to how, as the robot uses pure pursuit, it is always chasing a point it can never reach.
      Parameters:
      headingModuleFactory - HeadingModuleFactory
      pose - BasePoseSubsystem
      drive - BaseDriveSubsystem
      propMan - PropertyManager
  • Method Details

    • setPIDs

      public void setPIDs(HeadingModule headingModule, PIDManager positionalPid)
      By default, the PurePursuitCommand uses the HeadingModule and PositionalPid from the DriveSubsystem. However, if you want to change the PIDs used on the fly, you can here.
      Parameters:
      headingModule - Used for rotation
      positionalPid - Used for translation
    • setPIDsToDefault

      public void setPIDsToDefault()
    • setDotProductDrivingEnabled

      public void setDotProductDrivingEnabled(boolean enabled)
    • getOriginalPoints

      protected abstract List<RabbitPoint> getOriginalPoints()
    • getPursuitMode

      protected abstract PurePursuitCommand.PointLoadingMode getPursuitMode()
    • getPlannedPointsToVisit

      public List<RabbitPoint> getPlannedPointsToVisit()
      If you want to see where this command is heading in the future (for visualization purposes, perhaps) you can get that information here.
      Returns:
      List of points to visit
    • initialize

      public void initialize()
      Overrides:
      initialize in class BaseCommand
    • execute

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

      public PurePursuitCommand.RabbitChaseInfo evaluateCurrentPoint(FieldPose robotPose)
    • evaluateCurrentPoint

      public PurePursuitCommand.RabbitChaseInfo evaluateCurrentPoint()
      This is the core method that looks at the point list, figures out which point to be heading towards, and doing the math on how to get there.
      Returns:
      Information about what the robot would like to do in order to reach its points.
    • end

      public void end(boolean interrupted)
      Overrides:
      end in class BaseCommand
    • isFinished

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

      public double getMotionBudget()