Public Member Functions | Public Attributes | Private Attributes
Path Class Reference

class to manage the waypoints and magnets of the current path More...

List of all members.

Public Member Functions

ReturnValue AddMagnet (MagnetStruct magnet)
 Adds a new magnet.
ReturnValue AddMagnet (vector< MagnetStruct > po)
 Adds a vector of magnets.
ReturnValue AddWaypoint (Waypoint point)
 Adds a new waypoint.
ReturnValue AddWaypoint (vector< Waypoint > po)
 Adds a vector of waypoints.
ReturnValue BackMagnet (MagnetStruct *mg)
 Returns the back magnet.
ReturnValue BackWaypoint (Waypoint *wp)
 Returns the last waypoint.
void Clear ()
 Clears the waypoints and magnets.
double DistForSpeed (double target_speed)
double dot2 (Waypoint w, Waypoint v)
 Cross product.
ReturnValue GetCurrentMagnet (MagnetStruct *mg)
 Gets the current magnet.
int GetCurrentMagnetIndex ()
 Gets the current MagnetStruct in the path.
ReturnValue GetCurrentWaypoint (Waypoint *wp)
 Gets the current waypoint.
int GetCurrentWaypointIndex ()
 Gets the current Waypoint in the path.
ReturnValue GetLastMagnet (MagnetStruct *mg)
 Gets the last magnet.
ReturnValue GetNextMagnet (MagnetStruct *mg)
 Returns the next magnet.
ReturnValue GetNextWaypoint (Waypoint *wp)
 Returns the next waypoint.
ReturnValue GetPreviousMagnet (MagnetStruct *mg)
 Gets the previous magnet.
ReturnValue GetWaypoint (int index, Waypoint *wp)
 Gets selected waypoint.
void NextMagnet ()
 Increase magnet's number.
void NextWaypoint ()
 Increase waypoint's number.
int NumOfMagnets ()
 Returns the number of magnets.
int NumOfWaypoints ()
 Returns the number of waypoints.
Pathoperator+= (const Path &a)
 Overloaded operator +=.
ReturnValue Optimize (double distance)
 Path ()
 public constructor
Waypoint PosOnQuadraticBezier (Waypoint cp0, Waypoint cp1, Waypoint cp2, float t)
void Print ()
 Prints all the waypoints.
ReturnValue SetCurrentMagnet (int index)
 Sets the current magnet to index.
ReturnValue SetCurrentWaypoint (int index)
 Sets the current Waypoint to index.
unsigned int Size ()
 Returns the size of the vector points.
 ~Path ()
 Destructor.

Public Attributes

int iCurrentMagnet
 Current magnet.
int iCurrentWaypoint
 Current waypoint.

Private Attributes

bool bOptimized
 Flag to control the optimization.
pthread_mutex_t mutexPath
 Mutex to control the access.
vector< MagnetStructvMagnets
 Vector to store all the magnets.
vector< WaypointvPoints
 Vector to store all the Waypoints.

Detailed Description

class to manage the waypoints and magnets of the current path

Definition at line 89 of file purepursuit_planner.cpp.


Constructor & Destructor Documentation

Path::Path ( ) [inline]

public constructor

Definition at line 109 of file purepursuit_planner.cpp.

Path::~Path ( ) [inline]

Destructor.

Definition at line 116 of file purepursuit_planner.cpp.


Member Function Documentation

Adds a new magnet.

Definition at line 156 of file purepursuit_planner.cpp.

ReturnValue Path::AddMagnet ( vector< MagnetStruct po) [inline]

Adds a vector of magnets.

Definition at line 168 of file purepursuit_planner.cpp.

ReturnValue Path::AddWaypoint ( Waypoint  point) [inline]

Adds a new waypoint.

Definition at line 121 of file purepursuit_planner.cpp.

ReturnValue Path::AddWaypoint ( vector< Waypoint po) [inline]

Adds a vector of waypoints.

Definition at line 144 of file purepursuit_planner.cpp.

Returns the back magnet.

Definition at line 301 of file purepursuit_planner.cpp.

Returns the last waypoint.

Definition at line 212 of file purepursuit_planner.cpp.

void Path::Clear ( ) [inline]

Clears the waypoints and magnets.

Definition at line 180 of file purepursuit_planner.cpp.

double Path::DistForSpeed ( double  target_speed) [inline]

Function that calculate the distance to deccelerate from target speed

Parameters:
target_speedas double, speed on m/s
Returns:
distance on meters

Definition at line 419 of file purepursuit_planner.cpp.

double Path::dot2 ( Waypoint  w,
Waypoint  v 
) [inline]

Cross product.

Definition at line 394 of file purepursuit_planner.cpp.

Gets the current magnet.

Definition at line 315 of file purepursuit_planner.cpp.

int Path::GetCurrentMagnetIndex ( ) [inline]

Gets the current MagnetStruct in the path.

Definition at line 343 of file purepursuit_planner.cpp.

Gets the current waypoint.

Definition at line 226 of file purepursuit_planner.cpp.

Gets the current Waypoint in the path.

Definition at line 254 of file purepursuit_planner.cpp.

Gets the last magnet.

Definition at line 368 of file purepursuit_planner.cpp.

Returns the next magnet.

Definition at line 285 of file purepursuit_planner.cpp.

Returns the next waypoint.

Definition at line 196 of file purepursuit_planner.cpp.

Gets the previous magnet.

Definition at line 329 of file purepursuit_planner.cpp.

ReturnValue Path::GetWaypoint ( int  index,
Waypoint wp 
) [inline]

Gets selected waypoint.

Definition at line 240 of file purepursuit_planner.cpp.

void Path::NextMagnet ( ) [inline]

Increase magnet's number.

Definition at line 361 of file purepursuit_planner.cpp.

void Path::NextWaypoint ( ) [inline]

Increase waypoint's number.

Definition at line 273 of file purepursuit_planner.cpp.

int Path::NumOfMagnets ( ) [inline]

Returns the number of magnets.

Definition at line 382 of file purepursuit_planner.cpp.

int Path::NumOfWaypoints ( ) [inline]

Returns the number of waypoints.

Definition at line 280 of file purepursuit_planner.cpp.

Path& Path::operator+= ( const Path a) [inline]

Overloaded operator +=.

Definition at line 387 of file purepursuit_planner.cpp.

ReturnValue Path::Optimize ( double  distance) [inline]

Modifies and adds new waypoints to the route for improving the path

Parameters:
distanceas double, used for the calculation of the new points
Returns:
ERROR if Size is lower than 3, distance <= 0 or the waypoints has already been optimized
OK

Definition at line 433 of file purepursuit_planner.cpp.

Waypoint Path::PosOnQuadraticBezier ( Waypoint  cp0,
Waypoint  cp1,
Waypoint  cp2,
float  t 
) [inline]

Obtains the points for a quadratic Bezier's curve

Parameters:
cp0as player_pose2d_t, control point 0
cp1as player_pose2d_t, control point 1
cp2as player_pose2d_t, control point 2
tas float, [0 ... 1]
Returns:
Point over the curve

Definition at line 404 of file purepursuit_planner.cpp.

void Path::Print ( ) [inline]

Prints all the waypoints.

Definition at line 662 of file purepursuit_planner.cpp.

ReturnValue Path::SetCurrentMagnet ( int  index) [inline]

Sets the current magnet to index.

Definition at line 348 of file purepursuit_planner.cpp.

ReturnValue Path::SetCurrentWaypoint ( int  index) [inline]

Sets the current Waypoint to index.

Definition at line 259 of file purepursuit_planner.cpp.

unsigned int Path::Size ( ) [inline]

Returns the size of the vector points.

Definition at line 191 of file purepursuit_planner.cpp.


Member Data Documentation

bool Path::bOptimized [private]

Flag to control the optimization.

Definition at line 104 of file purepursuit_planner.cpp.

Current magnet.

Definition at line 94 of file purepursuit_planner.cpp.

Current waypoint.

Definition at line 92 of file purepursuit_planner.cpp.

pthread_mutex_t Path::mutexPath [private]

Mutex to control the access.

Definition at line 98 of file purepursuit_planner.cpp.

vector<MagnetStruct> Path::vMagnets [private]

Vector to store all the magnets.

Definition at line 102 of file purepursuit_planner.cpp.

vector<Waypoint> Path::vPoints [private]

Vector to store all the Waypoints.

Definition at line 100 of file purepursuit_planner.cpp.


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


purepursuit_planner
Author(s): Román Navarro
autogenerated on Thu Aug 27 2015 12:08:42