|
template<typename Point > |
static void | convertPointToPolygon (const Point &point, geometry_msgs::Polygon &polygon) |
| Convert a generi point type to a geometry_msgs::Polygon. More...
|
|
void | addPoint (double x, double y) |
| helper function for adding a point to the lookup data structures More...
|
|
void | convexHull (std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon) |
| Compute the convex hull for a single cluster (monotone chain algorithm) More...
|
|
void | convexHull2 (std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon) |
| Compute the convex hull for a single cluster. More...
|
|
template<typename P1 , typename P2 , typename P3 > |
long double | cross (const P1 &O, const P2 &A, const P3 &B) |
| 2D Cross product of two vectors defined by two points and a common origin More...
|
|
void | dbScan (std::vector< std::vector< KeyPoint > > &clusters) |
| DBSCAN algorithm for clustering. More...
|
|
int | neighborCellsToIndex (int cx, int cy) |
| offset [meters] in y for the lookup grid More...
|
|
void | pointToNeighborCells (const KeyPoint &kp, int &cx, int &cy) |
| compute the cell indices of a keypoint More...
|
|
void | regionQuery (int curr_index, std::vector< int > &neighbor_indices) |
| Helper function for dbScan to search for neighboring points. More...
|
|
void | simplifyPolygon (geometry_msgs::Polygon &polygon) |
| Simplify a polygon by removing points. More...
|
|
void | updatePolygonContainer (PolygonContainerPtr polygons) |
| Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside this class) More...
|
|
| BaseCostmapToPolygons () |
| Protected constructor that should be called by subclasses. More...
|
|
void | spinThread () |
| Blocking method that checks for new timer events (active if startWorker() is called with spin_thread enabled) More...
|
|
void | workerCallback (const ros::TimerEvent &) |
| The callback of the worker that performs the actual work (updating the costmap and converting it to polygons) More...
|
|
std::vector< std::vector< int > > | neighbor_lookup_ |
|
int | neighbor_size_x_ |
| array of cells for neighbor lookup More...
|
|
int | neighbor_size_y_ |
| size of the neighbour lookup in x (number of cells) More...
|
|
std::vector< KeyPoint > | occupied_cells_ |
| List of occupied cells in the current map (updated by updateCostmap2D()) More...
|
|
double | offset_x_ |
| size of the neighbour lookup in y (number of cells) More...
|
|
double | offset_y_ |
| offset [meters] in x for the lookup grid More...
|
|
Parameters | parameter_ |
|
Parameters | parameter_buffered_ |
|
boost::mutex | parameter_mutex_ |
| Mutex that keeps track about the ownership of the shared polygon instance. More...
|
|
Definition at line 19 of file costmap_polygons.cpp.