$search
#include <PolyOps.h>
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, WayPointNode waypt) |
void | AddLanePolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, ElementID id) |
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, WayPointNode waypt) |
void | AddReverseLanePolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, ElementID id) |
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) |
void | CollectPolys (const std::vector< poly > &from_polys, std::vector< poly > &to_polys, unsigned start, unsigned end) |
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, MapXY pt) |
int | getClosestNonTransPoly (const std::vector< poly > &polys, float x, float y) |
MapXY | GetClosestPointToLine (MapXY A, MapXY B, MapXY P, bool segmentClamp) |
int | getClosestPoly (const std::vector< poly > &polys, const MapPose &pose) |
int | getClosestPoly (const std::vector< poly > &polys, MapXY pt) |
int | getClosestPoly (const std::vector< poly > &polys, float x, float y) |
int | getContainingPoly (const std::vector< poly > &polys, const MapPose &pose) |
int | getContainingPoly (const std::vector< poly > &polys, const MapXY &pt) |
int | getContainingPoly (const std::vector< poly > &polys, float x, float y) |
poly_id_t | getContainingPolyID (const std::vector< poly > &polys, const MapXY &pt) |
poly_id_t | getContainingPolyID (const std::vector< poly > &polys, float x, float y) |
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< MapXY > | getPointsFromPolys (const std::vector< poly > &polys) |
MapXY | getPolyEdgeMidpoint (const poly &p) |
int | getPolyIndex (const std::vector< poly > &polys, const poly &curPoly) |
std::set< ElementID > | getPolyLaneIds (const std::vector< poly > &polys) |
void | GetPolys (const art_msgs::ArtLanes &lanes, poly_list_t &polyList) |
std::vector< poly > | getPolysBetweenPoints (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< MapXY > | getRoadPerimeterPoints (const std::vector< poly > &polys, const ElementID way0) |
std::vector< MapXY > | getRoadPerimeterPoints (const std::vector< poly > &polys, const ElementID way0, const ElementID way1) |
float | getShortestDistToPoly (MapXY pt, const poly &p) |
float | getShortestDistToPoly (float x, float y, 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, WayPointNode waypt) |
bool | LanePoly (const poly &curPoly, ElementID id) |
bool | left_of_poly (const poly &this_poly, const poly &cur_poly) |
bool | match_waypt_poly (const poly &curPoly, ElementID way) |
bool | match_waypt_poly (const poly &curPoly, ElementID way0, ElementID way1) |
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 (const Polar &polar, const MapPose &origin, const poly &p) |
bool | pointInPoly (const MapXY &pt, const poly &p) |
bool | pointInPoly (float x, float y, const poly &p) |
bool | pointInPoly_ratio (const MapXY &pt, const poly &p, float ratio) |
bool | pointInPoly_ratio (float x, float y, const poly &p, float ratio) |
bool | pointNearPoly (const MapXY &pt, const poly &poly, double epsilon) |
bool | pointNearPoly (double x, double y, 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, MapXY > | specialDistanceAlongLane (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) |
Polygon operations.
Definition at line 141 of file PolyOps.h.
PolyOps::PolyOps | ( | ) |
Definition at line 33 of file PolyOps.cc.
PolyOps::~PolyOps | ( | ) |
Definition at line 38 of file PolyOps.cc.
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, | |||
WayPointNode | waypt | |||
) |
Definition at line 533 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::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, | |||
WayPointNode | waypt | |||
) |
Definition at line 571 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::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 | |||
) |
Definition at line 586 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.
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.
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.
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::getContainingPoly | ( | const std::vector< poly > & | polys, | |
float | x, | |||
float | y | |||
) |
Get containing polygon
polys | vector of polygons to consider | |
x,y | MapXY coordinates of desired point |
Definition at line 85 of file PolyOps.cc.
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.
Definition at line 383 of file PolyOps.cc.
Definition at line 269 of file PolyOps.cc.
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.
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.
Definition at line 1198 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.
std::vector< MapXY > PolyOps::getRoadPerimeterPoints | ( | const std::vector< poly > & | polys, | |
const ElementID | way0, | |||
const ElementID | way1 | |||
) |
Definition at line 1356 of file PolyOps.cc.
float PolyOps::getShortestDistToPoly | ( | float | x, | |
float | y, | |||
const poly & | p | |||
) |
Definition at line 131 of file PolyOps.cc.
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.
pose | current vehicle pose (2D map coordinates) | |
polygons | list of polygons | |
distance | looks ahead a certain amount so that we don't turn sharply to reach a nearby waypoint. | |
min_heading | angle to accept polygon as valid |
Definition at line 646 of file PolyOps.cc.
poly_list_t PolyOps::getTransitionPolys | ( | const poly_list_t & | polys | ) |
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, | |
WayPointNode | waypt | |||
) |
Definition at line 611 of file PolyOps.cc.
Definition at line 617 of file PolyOps.cc.
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::MatchTransitionPoly | ( | const poly & | curPoly, | |
const WayPointNode & | way0, | |||
const WayPointNode & | way1 | |||
) |
Definition at line 627 of file PolyOps.cc.
Definition at line 902 of file PolyOps.cc.
bool PolyOps::pointInHull | ( | float | x, | |
float | y, | |||
const poly & | p | |||
) | [inline] |
bool PolyOps::pointInPoly | ( | float | x, | |
float | y, | |||
const poly & | p | |||
) | [inline] |
bool PolyOps::pointInPoly_ratio | ( | float | x, | |
float | y, | |||
const poly & | p, | |||
float | ratio | |||
) |
Definition at line 44 of file PolyOps.cc.
bool PolyOps::pointNearPoly | ( | double | x, | |
double | y, | |||
const poly & | poly, | |||
double | epsilon | |||
) | [inline] |
bool PolyOps::pointOnEdges | ( | float | x, | |
float | y, | |||
const poly & | p | |||
) | [inline] |
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.
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.