RobotCore
Robot Core Documentation
Classes | Public Member Functions | List of all members
robotCore.PurePursuit Class Reference

The PurePursuit class provides path following using the Pure Pursuit algorithm. More...

Classes

interface  SetSpeed
 SetSpeed defines the interface used by PurPursuit to set the speed of the motors. The speed should be set in feet/second. More...
 

Public Member Functions

 PurePursuit (Navigator navigator, SetSpeed setSpeed, int rate)
 
void loadPath (Path path, boolean isReversed, boolean isExtended, boolean setPosition)
 
void enableLogging (String logPath)
 
void disableLogging ()
 
void startPath ()
 
boolean isFinished ()
 
void stopFollow ()
 

Detailed Description

The PurePursuit class provides path following using the Pure Pursuit algorithm.

        This algorithm is described here: https://www.ri.cmu.edu/pub_files/pub3/coulter_r_craig_1992_1/coulter_r_craig_1992_1.pdf
        It takes as input paths generated by the Pathfinder class. There are a number
        of adjustable parameters that can be set when creating the paths that will
        control the behavior of the Pure Pursuit. See the Pathfinder class for details.

Constructor & Destructor Documentation

◆ PurePursuit()

robotCore.PurePursuit.PurePursuit ( Navigator  navigator,
SetSpeed  setSpeed,
int  rate 
)
Parameters
navigator- Specifies the Navigator class to be use to obtain the robot's position.
setSpeed- Specifies the callback function used to set the robot's speed. This function should accept the speed in feet/second.
rate- Specifies the time between updates in milliseconds

Member Function Documentation

◆ disableLogging()

void robotCore.PurePursuit.disableLogging ( )

Disables logging of the robots motion.

◆ enableLogging()

void robotCore.PurePursuit.enableLogging ( String  logPath)

Enables logging of the robots motion along the path to the robot's local file system.

Parameters
logPath- Specifies the path directory into which the logs are stored

◆ isFinished()

boolean robotCore.PurePursuit.isFinished ( )
Returns
Returns true if the path is complete

◆ loadPath()

void robotCore.PurePursuit.loadPath ( Path  path,
boolean  isReversed,
boolean  isExtended,
boolean  setPosition 
)

Loads the current path

Parameters
path- Specifies the path to follow.
isReversed- If true, the robot backs along the path.
isExtended- If true, the path is extended beyond the end, tangent to the ending angle, for the purpose of tracking (the robot will still stop when the original end is reached.)
setPosition- If true, set the starting position and angle based on the first point of the path.

◆ startPath()

void robotCore.PurePursuit.startPath ( )

Start following the currently loaded path. While the path is being followed, PurePursuit must have exclusive access to the drive motors.

◆ stopFollow()

void robotCore.PurePursuit.stopFollow ( )

Stop following the path.


The documentation for this class was generated from the following file: