grid_map_2d.h
Go to the documentation of this file.
1 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/vigir_gridmap_2d/include/vigir_gridmap_2d/GridMap2D.h $
2 // SVN $Id: GridMap2D.h 3276 2012-09-27 12:39:16Z hornunga@informatik.uni-freiburg.de $
3 
4 /*
5  * A simple 2D gridmap structure
6  *
7  * Copyright 2011 Armin Hornung, University of Freiburg
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above copyright
15  * notice, this list of conditions and the following disclaimer in the
16  * documentation and/or other materials provided with the distribution.
17  * * Neither the name of the University of Freiburg nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #ifndef GRIDMAP2D_GRIDMAP2D_H_
35 #define GRIDMAP2D_GRIDMAP2D_H_
36 
37 #include <nav_msgs/OccupancyGrid.h>
38 
39 #include <opencv2/core/core.hpp>
40 #include <opencv2/imgproc/imgproc.hpp>
41 
42 
43 
45 {
51 class GridMap2D
52 {
53 public:
54  GridMap2D();
55  GridMap2D(const nav_msgs::OccupancyGridConstPtr& gridMap);
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  {
73  return worldDist(cv::Point(x1, y1), cv::Point(x2, y2));
74  }
75 
76  inline double worldDist(const cv::Point& p1, const cv::Point& p2)
77  {
78  return GridMap2D::pointDist(p1, p2) * m_mapInfo.resolution;
79  }
80 
82  static inline double pointDist(const cv::Point& p1, const cv::Point& p2)
83  {
84  return sqrt(pointDist2(p1, p2));
85  }
86 
88  static inline double pointDist2(const cv::Point& p1, const cv::Point& p2)
89  {
90  return (p1.x - p2.x)*(p1.x - p2.x) + (p1.y - p2.y)*(p1.y - p2.y);
91  }
92 
94  float distanceMapAt(double wx, double wy) const;
95 
97  float distanceMapAtCell(unsigned int mx, unsigned int my) const;
98 
100  uchar binaryMapAt(double wx, double wy) const;
101 
103  uchar binaryMapAtCell(unsigned int mx, unsigned int my) const;
104 
107  bool isOccupiedAt(double wx, double wy) const;
108 
110  bool isOccupiedAtCell(unsigned int mx, unsigned int my) const;
111 
113  void setMap(const nav_msgs::OccupancyGridConstPtr& gridMap);
114 
116  void setMap(const cv::Mat& binaryMap);
117 
118  inline const nav_msgs::MapMetaData& getInfo() const { return m_mapInfo; }
119  inline float getResolution() const { return m_mapInfo.resolution; }
121  inline const std::string getFrameID() const { return m_frameId; }
123  const cv::Mat& distanceMap() const { return m_distMap; }
125  const cv::Mat& binaryMap() const { return m_binaryMap; }
127  inline const CvSize size() const { return m_binaryMap.size(); }
128 
129 protected:
130  cv::Mat m_binaryMap;
131  cv::Mat m_distMap;
132  nav_msgs::MapMetaData m_mapInfo;
133  std::string m_frameId;
134 };
135 
137 }
138 
139 #endif /* GRIDMAP2D_H_ */
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!
void setMap(const nav_msgs::OccupancyGridConstPtr &gridMap)
Initialize map from a ROS OccupancyGrid message.
Definition: grid_map_2d.cpp:56
bool inMapBounds(double wx, double wy) const
check if a coordinate is covered by the map extent (same as worldToMap)
void inflateMap(double inflationRaduis)
const nav_msgs::MapMetaData & getInfo() const
Definition: grid_map_2d.h:118
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!
boost::shared_ptr< GridMap2D > GridMap2DPtr
Definition: grid_map_2d.h:136
cv::Mat m_binaryMap
binary occupancy map. 255: free, 0 occupied.
Definition: grid_map_2d.h:130
std::string m_frameId
"map" frame where ROS OccupancyGrid originated from
Definition: grid_map_2d.h:133
const std::string getFrameID() const
returns the tf frame ID of the map (usually "/map")
Definition: grid_map_2d.h:121
void worldToMapNoBounds(double wx, double wy, unsigned int &mx, unsigned int &my) const
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
double worldDist(const cv::Point &p1, const cv::Point &p2)
Definition: grid_map_2d.h:76
uchar binaryMapAt(double wx, double wy) const
Returns map value at world coordinates <wx, wy>; out of bounds will be returned as 0! ...
float distanceMapAt(double wx, double wy) const
Returns distance (in m) at world coordinates <wx,wy> in m; -1 if out of bounds!
bool isOccupiedAt(double wx, double wy) const
static double pointDist2(const cv::Point &p1, const cv::Point &p2)
Squared distance between two points:
Definition: grid_map_2d.h:88
float getResolution() const
Definition: grid_map_2d.h:119
const cv::Mat & distanceMap() const
Definition: grid_map_2d.h:123
const cv::Mat & binaryMap() const
Definition: grid_map_2d.h:125
Stores a nav_msgs::OccupancyGrid in a convenient opencv cv::Mat as binary map (free: 255...
Definition: grid_map_2d.h:51
double worldDist(unsigned x1, unsigned y1, unsigned x2, unsigned y2)
Distance (in m) between two map coordinates (indices)
Definition: grid_map_2d.h:71
const CvSize size() const
Definition: grid_map_2d.h:127
static double pointDist(const cv::Point &p1, const cv::Point &p2)
Euclidean distance between two points:
Definition: grid_map_2d.h:82
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
bool isOccupiedAtCell(unsigned int mx, unsigned int my) const
nav_msgs::MapMetaData m_mapInfo
Definition: grid_map_2d.h:132
cv::Mat m_distMap
distance map (in meter)
Definition: grid_map_2d.h:131


vigir_footstep_planning_default_plugins
Author(s): Alexander Stumpf
autogenerated on Sun Nov 17 2019 03:30:01