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
00033
00034 #ifndef GRIDMAP2D_GRIDMAP2D_H_
00035 #define GRIDMAP2D_GRIDMAP2D_H_
00036
00037 #include <nav_msgs/OccupancyGrid.h>
00038
00039 #include <opencv2/core/core.hpp>
00040 #include <opencv2/imgproc/imgproc.hpp>
00041
00042
00043
00044 namespace vigir_gridmap_2d
00045 {
00051 class GridMap2D
00052 {
00053 public:
00054 GridMap2D();
00055 GridMap2D(const nav_msgs::OccupancyGridConstPtr& gridMap);
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 {
00073 return worldDist(cv::Point(x1, y1), cv::Point(x2, y2));
00074 }
00075
00076 inline double worldDist(const cv::Point& p1, const cv::Point& p2)
00077 {
00078 return GridMap2D::pointDist(p1, p2) * m_mapInfo.resolution;
00079 }
00080
00082 static inline double pointDist(const cv::Point& p1, const cv::Point& p2)
00083 {
00084 return sqrt(pointDist2(p1, p2));
00085 }
00086
00088 static inline double pointDist2(const cv::Point& p1, const cv::Point& p2)
00089 {
00090 return (p1.x - p2.x)*(p1.x - p2.x) + (p1.y - p2.y)*(p1.y - p2.y);
00091 }
00092
00094 float distanceMapAt(double wx, double wy) const;
00095
00097 float distanceMapAtCell(unsigned int mx, unsigned int my) const;
00098
00100 uchar binaryMapAt(double wx, double wy) const;
00101
00103 uchar binaryMapAtCell(unsigned int mx, unsigned int my) const;
00104
00107 bool isOccupiedAt(double wx, double wy) const;
00108
00110 bool isOccupiedAtCell(unsigned int mx, unsigned int my) const;
00111
00113 void setMap(const nav_msgs::OccupancyGridConstPtr& gridMap);
00114
00116 void setMap(const cv::Mat& binaryMap);
00117
00118 inline const nav_msgs::MapMetaData& getInfo() const { return m_mapInfo; }
00119 inline float getResolution() const { return m_mapInfo.resolution; }
00121 inline const std::string getFrameID() const { return m_frameId; }
00123 const cv::Mat& distanceMap() const { return m_distMap; }
00125 const cv::Mat& binaryMap() const { return m_binaryMap; }
00127 inline const CvSize size() const { return m_binaryMap.size(); }
00128
00129 protected:
00130 cv::Mat m_binaryMap;
00131 cv::Mat m_distMap;
00132 nav_msgs::MapMetaData m_mapInfo;
00133 std::string m_frameId;
00134 };
00135
00136 typedef boost::shared_ptr< GridMap2D> GridMap2DPtr;
00137 }
00138
00139 #endif