GridMap2D.h
Go to the documentation of this file.
1 /*
2  * A simple 2D gridmap structure
3  *
4  * Copyright 2011 Armin Hornung, University of Freiburg
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the University of Freiburg nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
31 
32 #ifndef GRIDMAP2D_GRIDMAP2D_H_
33 #define GRIDMAP2D_GRIDMAP2D_H_
34 
35 #include <opencv2/core/core.hpp>
36 #include <opencv2/imgproc/imgproc.hpp>
37 #include <nav_msgs/OccupancyGrid.h>
38 
39 
40 
41 
42 
43 namespace gridmap_2d{
49 class GridMap2D {
50 public:
51  GridMap2D();
53  GridMap2D(const nav_msgs::OccupancyGridConstPtr& grid_map, bool unknown_as_obstacle = false);
55  GridMap2D(const GridMap2D& other);
56  virtual ~GridMap2D();
57 
58  void mapToWorld(unsigned int mx, unsigned int my, double& wx, double& wy) const;
59  bool worldToMap(double wx, double wy, unsigned int& mx, unsigned int& my) const;
60  void worldToMapNoBounds(double wx, double wy, unsigned int& mx, unsigned int& my) const;
61 
63  bool inMapBounds(double wx, double wy) const;
64 
68  void inflateMap(double inflationRaduis);
69 
71  inline double worldDist(unsigned x1, unsigned y1, unsigned x2, unsigned y2){
72  return worldDist(cv::Point(x1, y1), cv::Point(x2, y2));
73  }
74 
75  inline double worldDist(const cv::Point& p1, const cv::Point& p2){
76  return GridMap2D::pointDist(p1, p2) * m_mapInfo.resolution;
77  }
78 
80  static inline double pointDist(const cv::Point& p1, const cv::Point& p2){
81  return sqrt(pointDist2(p1, p2));
82  }
83 
85  static inline double pointDist2(const cv::Point& p1, const cv::Point& p2){
86  return (p1.x - p2.x)*(p1.x - p2.x) + (p1.y - p2.y)*(p1.y - p2.y);
87  }
88 
90  float distanceMapAt(double wx, double wy) const;
91 
93  float distanceMapAtCell(unsigned int mx, unsigned int my) const;
94 
96  uchar binaryMapAt(double wx, double wy) const;
97 
99  uchar binaryMapAtCell(unsigned int mx, unsigned int my) const;
100 
102  uchar& binaryMapAtCell(unsigned int mx, unsigned int my);
103 
106  bool isOccupiedAt(double wx, double wy) const;
107 
109  bool isOccupiedAtCell(unsigned int mx, unsigned int my) const;
110 
112  void setMap(const nav_msgs::OccupancyGridConstPtr& grid_map, bool unknown_as_obstacle = false);
113 
115  nav_msgs::OccupancyGrid toOccupancyGridMsg() const;
116 
118  void setMap(const cv::Mat& binary_map);
119 
121  void updateDistanceMap();
122 
123  inline const nav_msgs::MapMetaData& getInfo() const {return m_mapInfo;}
124  inline float getResolution() const {return m_mapInfo.resolution; }
126  inline const std::string getFrameID() const {return m_frameId;}
128  const cv::Mat& distanceMap() const {return m_distMap;}
130  const cv::Mat& binaryMap() const {return m_binaryMap;}
132  inline const CvSize size() const {return m_binaryMap.size();}
133 
134  const static uchar FREE = 255;
135  const static uchar OCCUPIED = 0;
136 
137 protected:
138  cv::Mat m_binaryMap;
139  cv::Mat m_distMap;
140  nav_msgs::MapMetaData m_mapInfo;
141  std::string m_frameId;
142 
143 };
144 
147 }
148 
149 #endif /* GRIDMAP2D_H_ */
static const uchar OCCUPIED
char value for "free": 0
Definition: GridMap2D.h:135
float getResolution() const
Definition: GridMap2D.h:124
nav_msgs::OccupancyGrid toOccupancyGridMsg() const
Converts back into a ROS nav_msgs::OccupancyGrid msg.
Definition: GridMap2D.cpp:100
const nav_msgs::MapMetaData & getInfo() const
Definition: GridMap2D.h:123
bool isOccupiedAt(double wx, double wy) const
Definition: GridMap2D.cpp:213
void worldToMapNoBounds(double wx, double wy, unsigned int &mx, unsigned int &my) const
Definition: GridMap2D.cpp:152
boost::shared_ptr< const GridMap2D > GridMap2DConstPtr
Definition: GridMap2D.h:146
void setMap(const nav_msgs::OccupancyGridConstPtr &grid_map, bool unknown_as_obstacle=false)
Initialize map from a ROS OccupancyGrid message.
Definition: GridMap2D.cpp:67
cv::Mat m_distMap
distance map (in meter)
Definition: GridMap2D.h:139
static double pointDist(const cv::Point &p1, const cv::Point &p2)
Euclidean distance between two points:
Definition: GridMap2D.h:80
static const uchar FREE
char value for "free": 255
Definition: GridMap2D.h:134
boost::shared_ptr< GridMap2D > GridMap2DPtr
Definition: GridMap2D.h:145
const std::string getFrameID() const
returns the tf frame ID of the map (usually "/map")
Definition: GridMap2D.h:126
void updateDistanceMap()
Recalculate the internal distance map. Required after manual changes to the grid map data...
Definition: GridMap2D.cpp:61
float distanceMapAtCell(unsigned int mx, unsigned int my) const
Returns distance (in m) at map cell <mx, my> in m; -1 if out of bounds!
Definition: GridMap2D.cpp:194
const CvSize size() const
Definition: GridMap2D.h:132
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Definition: GridMap2D.cpp:157
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Definition: GridMap2D.cpp:145
std::string m_frameId
"map" frame where ROS OccupancyGrid originated from
Definition: GridMap2D.h:141
uchar binaryMapAt(double wx, double wy) const
Returns map value at world coordinates <wx, wy>; out of bounds will be returned as 0! ...
Definition: GridMap2D.cpp:185
uchar binaryMapAtCell(unsigned int mx, unsigned int my) const
Returns map value at map cell <mx, my>; out of bounds will be returned as 0!
Definition: GridMap2D.cpp:199
float distanceMapAt(double wx, double wy) const
Returns distance (in m) at world coordinates <wx,wy> in m; -1 if out of bounds!
Definition: GridMap2D.cpp:175
const cv::Mat & distanceMap() const
Definition: GridMap2D.h:128
nav_msgs::MapMetaData m_mapInfo
Definition: GridMap2D.h:140
void inflateMap(double inflationRaduis)
Definition: GridMap2D.cpp:136
Stores a nav_msgs::OccupancyGrid in a convenient opencv cv::Mat as binary map (free: 255...
Definition: GridMap2D.h:49
const cv::Mat & binaryMap() const
Definition: GridMap2D.h:130
bool inMapBounds(double wx, double wy) const
check if a coordinate is covered by the map extent (same as worldToMap)
Definition: GridMap2D.cpp:170
double worldDist(unsigned x1, unsigned y1, unsigned x2, unsigned y2)
Distance (in m) between two map coordinates (indices)
Definition: GridMap2D.h:71
double worldDist(const cv::Point &p1, const cv::Point &p2)
Definition: GridMap2D.h:75
cv::Mat m_binaryMap
binary occupancy map. 255: free, 0 occupied.
Definition: GridMap2D.h:138
bool isOccupiedAtCell(unsigned int mx, unsigned int my) const
Definition: GridMap2D.cpp:208
static double pointDist2(const cv::Point &p1, const cv::Point &p2)
Squared distance between two points:
Definition: GridMap2D.h:85


gridmap_2d
Author(s): Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:21