voronoi_point.h
Go to the documentation of this file.
00001 
00039 #ifndef VORONOI_POINT_JI6FXE0K
00040 #define VORONOI_POINT_JI6FXE0K
00041 
00042 #include <vector>
00043 #include <nav_msgs/OccupancyGrid.h>
00044 #include <bwi_mapper/structures/point.h>
00045 
00046 namespace bwi_mapper {
00047 
00048   class VoronoiPoint : public Point2d {
00049 
00050     public:
00051       VoronoiPoint() : Point2d() {}
00052       VoronoiPoint(int x, int y) : Point2d(x, y) {}
00053       VoronoiPoint(const Point2d& pt) : Point2d(pt) {}
00054 
00055       std::vector<Point2d> basis_points;
00056 
00060       float basis_distance;
00061 
00065       float average_clearance; 
00066 
00070       float critical_clearance_diff;
00071 
00072        
00085       void addBasisCandidate(const Point2d& candidate, uint32_t threshold, 
00086           const nav_msgs::OccupancyGrid& map, bool use_naive);
00087 
00088   }; /* VoronoiPoint */
00089   
00090 } /* bwi_mapper */
00091 
00092 #endif /* end of include guard: VORONOI_POINT_JI6FXE0K */


bwi_mapper
Author(s): Piyush Khandelwal
autogenerated on Fri Aug 28 2015 10:14:35