Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef GRIDMAP2D_GRIDMAP2D_H_
00033 #define GRIDMAP2D_GRIDMAP2D_H_
00034
00035 #include <opencv2/core/core.hpp>
00036 #include <opencv2/imgproc/imgproc.hpp>
00037 #include <nav_msgs/OccupancyGrid.h>
00038
00039
00040
00041
00042
00043 namespace gridmap_2d{
00049 class GridMap2D {
00050 public:
00051 GridMap2D();
00053 GridMap2D(const nav_msgs::OccupancyGridConstPtr& grid_map, bool unknown_as_obstacle = false);
00055 GridMap2D(const GridMap2D& other);
00056 virtual ~GridMap2D();
00057
00058 void mapToWorld(unsigned int mx, unsigned int my, double& wx, double& wy) const;
00059 bool worldToMap(double wx, double wy, unsigned int& mx, unsigned int& my) const;
00060 void worldToMapNoBounds(double wx, double wy, unsigned int& mx, unsigned int& my) const;
00061
00063 bool inMapBounds(double wx, double wy) const;
00064
00068 void inflateMap(double inflationRaduis);
00069
00071 inline double worldDist(unsigned x1, unsigned y1, unsigned x2, unsigned y2){
00072 return worldDist(cv::Point(x1, y1), cv::Point(x2, y2));
00073 }
00074
00075 inline double worldDist(const cv::Point& p1, const cv::Point& p2){
00076 return GridMap2D::pointDist(p1, p2) * m_mapInfo.resolution;
00077 }
00078
00080 static inline double pointDist(const cv::Point& p1, const cv::Point& p2){
00081 return sqrt(pointDist2(p1, p2));
00082 }
00083
00085 static inline double pointDist2(const cv::Point& p1, const cv::Point& p2){
00086 return (p1.x - p2.x)*(p1.x - p2.x) + (p1.y - p2.y)*(p1.y - p2.y);
00087 }
00088
00090 float distanceMapAt(double wx, double wy) const;
00091
00093 float distanceMapAtCell(unsigned int mx, unsigned int my) const;
00094
00096 uchar binaryMapAt(double wx, double wy) const;
00097
00099 uchar binaryMapAtCell(unsigned int mx, unsigned int my) const;
00100
00102 uchar& binaryMapAtCell(unsigned int mx, unsigned int my);
00103
00106 bool isOccupiedAt(double wx, double wy) const;
00107
00109 bool isOccupiedAtCell(unsigned int mx, unsigned int my) const;
00110
00112 void setMap(const nav_msgs::OccupancyGridConstPtr& grid_map, bool unknown_as_obstacle = false);
00113
00115 nav_msgs::OccupancyGrid toOccupancyGridMsg() const;
00116
00118 void setMap(const cv::Mat& binary_map);
00119
00121 void updateDistanceMap();
00122
00123 inline const nav_msgs::MapMetaData& getInfo() const {return m_mapInfo;}
00124 inline float getResolution() const {return m_mapInfo.resolution; }
00126 inline const std::string getFrameID() const {return m_frameId;}
00128 const cv::Mat& distanceMap() const {return m_distMap;}
00130 const cv::Mat& binaryMap() const {return m_binaryMap;}
00132 inline const CvSize size() const {return m_binaryMap.size();}
00133
00134 const static uchar FREE = 255;
00135 const static uchar OCCUPIED = 0;
00136
00137 protected:
00138 cv::Mat m_binaryMap;
00139 cv::Mat m_distMap;
00140 nav_msgs::MapMetaData m_mapInfo;
00141 std::string m_frameId;
00142
00143 };
00144
00145 typedef boost::shared_ptr< GridMap2D> GridMap2DPtr;
00146 typedef boost::shared_ptr<const GridMap2D> GridMap2DConstPtr;
00147 }
00148
00149 #endif