grid_map_2d.h
Go to the documentation of this file.
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/vigir_gridmap_2d/include/vigir_gridmap_2d/GridMap2D.h $
00002 // SVN $Id: GridMap2D.h 3276 2012-09-27 12:39:16Z hornunga@informatik.uni-freiburg.de $
00003 
00004 /*
00005  * A simple 2D gridmap structure
00006  *
00007  * Copyright 2011 Armin Hornung, University of Freiburg
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions are met:
00011  *
00012  *     * Redistributions of source code must retain the above copyright
00013  *       notice, this list of conditions and the following disclaimer.
00014  *     * Redistributions in binary form must reproduce the above copyright
00015  *       notice, this list of conditions and the following disclaimer in the
00016  *       documentation and/or other materials provided with the distribution.
00017  *     * Neither the name of the University of Freiburg nor the names of its
00018  *       contributors may be used to endorse or promote products derived from
00019  *       this software without specific prior written permission.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00023  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00024  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00025  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00026  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00027  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00028  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00029  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00030  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  * POSSIBILITY OF SUCH DAMAGE.
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 /* GRIDMAP2D_H_ */


vigir_footstep_planning_default_plugins
Author(s): Alexander Stumpf
autogenerated on Thu Jun 6 2019 18:38:06