public class PurePursuitTracker
extends java.lang.Object
| Constructor and Description | 
|---|
| PurePursuitTracker(PoseEstimator poseEstimator,
                  DriveBase driveBase,
                  MustangSensors sensors)Makes a Pure Pursuit Tracker that is not reversed | 
| PurePursuitTracker(PoseEstimator poseEstimator,
                  DriveBase driveBase,
                  MustangSensors sensors,
                  boolean isReversed) | 
| Modifier and Type | Method and Description | 
|---|---|
| Path | getPath() | 
| boolean | isDone()Tells PurePursuitAction when we are done, indicated by the closest point being the last point of the path | 
| void | reset() | 
| void | setPath(Path path,
       double lookaheadDistance)Sets the path to be tracked | 
| DrivePower | update(Vector currPose,
      double currLeftVel,
      double currRightVel,
      double heading)Updates the tracker and returns left and right velocities | 
public PurePursuitTracker(PoseEstimator poseEstimator, DriveBase driveBase, MustangSensors sensors, boolean isReversed)
public PurePursuitTracker(PoseEstimator poseEstimator, DriveBase driveBase, MustangSensors sensors)
public void setPath(Path path, double lookaheadDistance)
path - path to be trackedlookaheadDistance - lookahead distance (ideally between 15-24 inches)public Path getPath()
public void reset()
public DrivePower update(Vector currPose, double currLeftVel, double currRightVel, double heading)
currPose - current position of robotcurrLeftVel - current left velocity of robotcurrRightVel - current right velocity of robotheading - current angle of robotpublic boolean isDone()