Public Member Functions | Private Member Functions
PolyOps Class Reference

#include <PolyOps.h>

List of all members.

Public Member Functions

void add_polys_for_waypts (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, ElementID from_id, ElementID to_id)
void AddLanePolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, ElementID id)
void AddLanePolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, WayPointNode waypt)
void AddLanePolysEither (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, WayPointNode waypt, int direction)
void AddReverseLanePolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, ElementID id)
void AddReverseLanePolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, WayPointNode waypt)
void AddTransitionPolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, WayPointNode way0, WayPointNode way1)
float avgLengthOfPolySides (const poly &p)
MapXY centerpoint (const poly &p)
void CollectPolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, unsigned start, unsigned end)
void CollectPolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, unsigned start)
float distanceAlongLane (const std::vector< poly > &polygons, const MapXY &from, const MapXY &to)
int get_waypoint_index (const std::vector< poly > &polys, const ElementID &waypoint)
int getClosestNonTransPoly (const std::vector< poly > &polys, float x, float y)
int getClosestNonTransPoly (const std::vector< poly > &polys, MapXY pt)
MapXY GetClosestPointToLine (MapXY A, MapXY B, MapXY P, bool segmentClamp)
int getClosestPoly (const std::vector< poly > &polys, float x, float y)
int getClosestPoly (const std::vector< poly > &polys, MapXY pt)
int getClosestPoly (const std::vector< poly > &polys, const MapPose &pose)
int getContainingPoly (const std::vector< poly > &polys, float x, float y)
int getContainingPoly (const std::vector< poly > &polys, const MapXY &pt)
int getContainingPoly (const std::vector< poly > &polys, const MapPose &pose)
poly_id_t getContainingPolyID (const std::vector< poly > &polys, float x, float y)
poly_id_t getContainingPolyID (const std::vector< poly > &polys, const MapXY &pt)
void getLaneDir (const std::vector< poly > &polys, std::vector< poly > &to_polys, const int relative, const int direction, const MapPose &pose)
void GetLanes (poly_list_t &polyList, art_msgs::ArtLanes &lanes)
float getLength (const poly &p)
std::vector< MapXYgetPointsFromPolys (const std::vector< poly > &polys)
MapXY getPolyEdgeMidpoint (const poly &p)
int getPolyIndex (const std::vector< poly > &polys, const poly &curPoly)
std::set< ElementIDgetPolyLaneIds (const std::vector< poly > &polys)
void GetPolys (const art_msgs::ArtLanes &lanes, poly_list_t &polyList)
std::vector< polygetPolysBetweenPoints (const std::vector< poly > &polys, float x1, float y1, float x2, float y2)
void getPolysBetweenWayPts (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, ElementID from_id, ElementID to_id)
int getPolyWayPt (const std::vector< poly > &polys, const ElementID &waypoint)
void getRemainingPolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, const MapXY &point)
ElementID getReverseLane (const std::vector< poly > &polys, const MapPose &pose)
std::vector< MapXYgetRoadPerimeterPoints (const std::vector< poly > &polys, const ElementID way0, const ElementID way1)
std::vector< MapXYgetRoadPerimeterPoints (const std::vector< poly > &polys, const ElementID way0)
float getShortestDistToPoly (float x, float y, const poly &p)
float getShortestDistToPoly (MapXY pt, const poly &p)
int getStartingPoly (const MapPose &pose, const std::vector< poly > &polygons, float distance, float min_heading)
poly_list_t getTransitionPolys (const poly_list_t &polys)
int index_of_downstream_poly (const std::vector< poly > &polygons, int start_index, float distance)
bool isValidPoly (const poly &p)
bool LanePoly (const poly &curPoly, ElementID id)
bool LanePoly (const poly &curPoly, WayPointNode waypt)
bool left_of_poly (const poly &this_poly, const poly &cur_poly)
bool match_waypt_poly (const poly &curPoly, ElementID way0, ElementID way1)
bool match_waypt_poly (const poly &curPoly, ElementID way)
bool MatchTransitionPoly (const poly &curPoly, const WayPointNode &way0, const WayPointNode &way1)
MapXY midpoint (const MapXY &p1, const MapXY &p2)
bool pointInHull (float x, float y, const poly &p)
bool pointInPoly (float x, float y, const poly &p)
bool pointInPoly (const MapXY &pt, const poly &p)
bool pointInPoly (const Polar &polar, const MapPose &origin, const poly &p)
bool pointInPoly_ratio (float x, float y, const poly &p, float ratio)
bool pointInPoly_ratio (const MapXY &pt, const poly &p, float ratio)
bool pointNearPoly (double x, double y, const poly &poly, double epsilon)
bool pointNearPoly (const MapXY &pt, const poly &poly, double epsilon)
bool pointOnEdges (float x, float y, const poly &p)
bool pointOnSegment (float x, float y, MapXY p1, MapXY p2)
float PolyHeading (const poly &curPoly)
 PolyOps ()
void printPolygons (const poly_list_t &polys)
bool same_direction (const poly &p1, const poly &p2, float angle)
float shortestDistToLineSegment (float x, float y, float line_x1, float line_y1, float line_x2, float line_y2)
std::pair< float, MapXYspecialDistanceAlongLane (const std::vector< poly > &polygons, const MapXY &from, const MapXY &to)
 ~PolyOps ()

Private Member Functions

float distance (float x1, float y1, float x2, float y2)
float length_between_polygons (const std::vector< poly > &polygons, int index1=-1, int index2=-1)

Detailed Description

Polygon operations.

Todo:
This class has no state. It should be replaced by a collection of functions in an appropriate namespace.

Definition at line 141 of file PolyOps.h.


Constructor & Destructor Documentation

Definition at line 33 of file PolyOps.cc.

Definition at line 38 of file PolyOps.cc.


Member Function Documentation

void PolyOps::add_polys_for_waypts ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
ElementID  from_id,
ElementID  to_id 
)

Definition at line 469 of file PolyOps.cc.

void PolyOps::AddLanePolys ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
ElementID  id 
)

Definition at line 519 of file PolyOps.cc.

void PolyOps::AddLanePolys ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
WayPointNode  waypt 
)

Definition at line 533 of file PolyOps.cc.

void PolyOps::AddLanePolysEither ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
WayPointNode  waypt,
int  direction 
)

Definition at line 541 of file PolyOps.cc.

void PolyOps::AddReverseLanePolys ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
ElementID  id 
)

Definition at line 553 of file PolyOps.cc.

void PolyOps::AddReverseLanePolys ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
WayPointNode  waypt 
)

Definition at line 571 of file PolyOps.cc.

void PolyOps::AddTransitionPolys ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
WayPointNode  way0,
WayPointNode  way1 
)

Definition at line 504 of file PolyOps.cc.

float PolyOps::avgLengthOfPolySides ( const poly p)

Definition at line 908 of file PolyOps.cc.

Definition at line 277 of file PolyOps.cc.

void PolyOps::CollectPolys ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
unsigned  start,
unsigned  end 
)

Definition at line 578 of file PolyOps.cc.

void PolyOps::CollectPolys ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
unsigned  start 
)

Definition at line 586 of file PolyOps.cc.

float PolyOps::distance ( float  x1,
float  y1,
float  x2,
float  y2 
) [private]

Definition at line 395 of file PolyOps.cc.

float PolyOps::distanceAlongLane ( const std::vector< poly > &  polygons,
const MapXY from,
const MapXY to 
)

Definition at line 800 of file PolyOps.cc.

int PolyOps::get_waypoint_index ( const std::vector< poly > &  polys,
const ElementID waypoint 
)

Definition at line 442 of file PolyOps.cc.

int PolyOps::getClosestNonTransPoly ( const std::vector< poly > &  polys,
float  x,
float  y 
)

Definition at line 202 of file PolyOps.cc.

int PolyOps::getClosestNonTransPoly ( const std::vector< poly > &  polys,
MapXY  pt 
) [inline]

Definition at line 466 of file PolyOps.h.

MapXY PolyOps::GetClosestPointToLine ( MapXY  A,
MapXY  B,
MapXY  P,
bool  segmentClamp 
)

Definition at line 1290 of file PolyOps.cc.

int PolyOps::getClosestPoly ( const std::vector< poly > &  polys,
float  x,
float  y 
)

Definition at line 163 of file PolyOps.cc.

int PolyOps::getClosestPoly ( const std::vector< poly > &  polys,
MapXY  pt 
) [inline]

Definition at line 442 of file PolyOps.h.

int PolyOps::getClosestPoly ( const std::vector< poly > &  polys,
const MapPose pose 
) [inline]

Definition at line 446 of file PolyOps.h.

int PolyOps::getContainingPoly ( const std::vector< poly > &  polys,
float  x,
float  y 
)

Get containing polygon

Parameters:
polysvector of polygons to consider
x,yMapXY coordinates of desired point
Returns:
index of polygon containing location (x, y) in polys -1 if no such polygon is found

Definition at line 85 of file PolyOps.cc.

int PolyOps::getContainingPoly ( const std::vector< poly > &  polys,
const MapXY pt 
) [inline]

Definition at line 362 of file PolyOps.h.

int PolyOps::getContainingPoly ( const std::vector< poly > &  polys,
const MapPose pose 
) [inline]

Definition at line 367 of file PolyOps.h.

poly_id_t PolyOps::getContainingPolyID ( const std::vector< poly > &  polys,
float  x,
float  y 
) [inline]

Definition at line 374 of file PolyOps.h.

poly_id_t PolyOps::getContainingPolyID ( const std::vector< poly > &  polys,
const MapXY pt 
) [inline]

Definition at line 383 of file PolyOps.h.

void PolyOps::getLaneDir ( const std::vector< poly > &  polys,
std::vector< poly > &  to_polys,
const int  relative,
const int  direction,
const MapPose pose 
)

Definition at line 1100 of file PolyOps.cc.

void PolyOps::GetLanes ( poly_list_t polyList,
art_msgs::ArtLanes lanes 
)

Definition at line 602 of file PolyOps.cc.

float PolyOps::getLength ( const poly p)

Definition at line 282 of file PolyOps.cc.

std::vector< MapXY > PolyOps::getPointsFromPolys ( const std::vector< poly > &  polys)

Definition at line 383 of file PolyOps.cc.

Definition at line 269 of file PolyOps.cc.

int PolyOps::getPolyIndex ( const std::vector< poly > &  polys,
const poly curPoly 
) [inline]

Definition at line 403 of file PolyOps.h.

std::set< ElementID > PolyOps::getPolyLaneIds ( const std::vector< poly > &  polys)

Definition at line 918 of file PolyOps.cc.

void PolyOps::GetPolys ( const art_msgs::ArtLanes lanes,
poly_list_t polyList 
)

Definition at line 594 of file PolyOps.cc.

std::vector< poly > PolyOps::getPolysBetweenPoints ( const std::vector< poly > &  polys,
float  x1,
float  y1,
float  x2,
float  y2 
)

Definition at line 292 of file PolyOps.cc.

void PolyOps::getPolysBetweenWayPts ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
ElementID  from_id,
ElementID  to_id 
)

Definition at line 1315 of file PolyOps.cc.

int PolyOps::getPolyWayPt ( const std::vector< poly > &  polys,
const ElementID waypoint 
)

Definition at line 454 of file PolyOps.cc.

void PolyOps::getRemainingPolys ( const std::vector< poly > &  from_polys,
std::vector< poly > &  to_polys,
const MapXY point 
)

Definition at line 349 of file PolyOps.cc.

ElementID PolyOps::getReverseLane ( const std::vector< poly > &  polys,
const MapPose pose 
)

Definition at line 1198 of file PolyOps.cc.

std::vector< MapXY > PolyOps::getRoadPerimeterPoints ( const std::vector< poly > &  polys,
const ElementID  way0,
const ElementID  way1 
)

Definition at line 1356 of file PolyOps.cc.

std::vector< MapXY > PolyOps::getRoadPerimeterPoints ( const std::vector< poly > &  polys,
const ElementID  way0 
)

Definition at line 1435 of file PolyOps.cc.

float PolyOps::getShortestDistToPoly ( float  x,
float  y,
const poly p 
)

Definition at line 131 of file PolyOps.cc.

float PolyOps::getShortestDistToPoly ( MapXY  pt,
const poly p 
) [inline]

Definition at line 429 of file PolyOps.h.

int PolyOps::getStartingPoly ( const MapPose pose,
const std::vector< poly > &  polygons,
float  distance,
float  min_heading 
)

Get closest polygon in front of robot's current pose

Useful when starting off road.

Parameters:
posecurrent vehicle pose (2D map coordinates)
polygonslist of polygons
distancelooks ahead a certain amount so that we don't turn sharply to reach a nearby waypoint.
min_headingangle to accept polygon as valid
Returns:
index in polygons of closest polygon within min_heading and distance.

Definition at line 646 of file PolyOps.cc.

Definition at line 1242 of file PolyOps.cc.

int PolyOps::index_of_downstream_poly ( const std::vector< poly > &  polygons,
int  start_index,
float  distance 
)

Definition at line 881 of file PolyOps.cc.

bool PolyOps::isValidPoly ( const poly p)

Definition at line 1270 of file PolyOps.cc.

bool PolyOps::LanePoly ( const poly curPoly,
ElementID  id 
)

Definition at line 617 of file PolyOps.cc.

bool PolyOps::LanePoly ( const poly curPoly,
WayPointNode  waypt 
)

Definition at line 611 of file PolyOps.cc.

bool PolyOps::left_of_poly ( const poly this_poly,
const poly cur_poly 
) [inline]

Definition at line 661 of file PolyOps.h.

float PolyOps::length_between_polygons ( const std::vector< poly > &  polygons,
int  index1 = -1,
int  index2 = -1 
) [private]

Definition at line 771 of file PolyOps.cc.

bool PolyOps::match_waypt_poly ( const poly curPoly,
ElementID  way0,
ElementID  way1 
) [inline]

Definition at line 206 of file PolyOps.h.

bool PolyOps::match_waypt_poly ( const poly curPoly,
ElementID  way 
) [inline]

Definition at line 213 of file PolyOps.h.

bool PolyOps::MatchTransitionPoly ( const poly curPoly,
const WayPointNode way0,
const WayPointNode way1 
)

Definition at line 627 of file PolyOps.cc.

MapXY PolyOps::midpoint ( const MapXY p1,
const MapXY p2 
)

Definition at line 902 of file PolyOps.cc.

bool PolyOps::pointInHull ( float  x,
float  y,
const poly p 
) [inline]

Definition at line 228 of file PolyOps.h.

bool PolyOps::pointInPoly ( float  x,
float  y,
const poly p 
) [inline]

Definition at line 281 of file PolyOps.h.

bool PolyOps::pointInPoly ( const MapXY pt,
const poly p 
) [inline]

Definition at line 313 of file PolyOps.h.

bool PolyOps::pointInPoly ( const Polar polar,
const MapPose origin,
const poly p 
) [inline]

Definition at line 318 of file PolyOps.h.

bool PolyOps::pointInPoly_ratio ( float  x,
float  y,
const poly p,
float  ratio 
)

Definition at line 44 of file PolyOps.cc.

bool PolyOps::pointInPoly_ratio ( const MapXY pt,
const poly p,
float  ratio 
) [inline]

Definition at line 329 of file PolyOps.h.

bool PolyOps::pointNearPoly ( double  x,
double  y,
const poly poly,
double  epsilon 
) [inline]

Definition at line 340 of file PolyOps.h.

bool PolyOps::pointNearPoly ( const MapXY pt,
const poly poly,
double  epsilon 
) [inline]

Definition at line 344 of file PolyOps.h.

bool PolyOps::pointOnEdges ( float  x,
float  y,
const poly p 
) [inline]

Definition at line 273 of file PolyOps.h.

bool PolyOps::pointOnSegment ( float  x,
float  y,
MapXY  p1,
MapXY  p2 
) [inline]

Definition at line 244 of file PolyOps.h.

float PolyOps::PolyHeading ( const poly curPoly)

Definition at line 636 of file PolyOps.cc.

void PolyOps::printPolygons ( const poly_list_t polys)

Definition at line 1228 of file PolyOps.cc.

bool PolyOps::same_direction ( const poly p1,
const poly p2,
float  angle 
) [inline]

Definition at line 672 of file PolyOps.h.

float PolyOps::shortestDistToLineSegment ( float  x,
float  y,
float  line_x1,
float  line_y1,
float  line_x2,
float  line_y2 
)

Definition at line 400 of file PolyOps.cc.

std::pair< float, MapXY > PolyOps::specialDistanceAlongLane ( const std::vector< poly > &  polygons,
const MapXY from,
const MapXY to 
)

Definition at line 811 of file PolyOps.cc.


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


art_map
Author(s): David Li, Patrick Beeson, Bartley Gillen, Tarun Nimmagadda, Mickey Ristroph, Michael Quinlan, Jack O'Quin
autogenerated on Fri Jan 3 2014 11:08:34