34 #ifndef GRIDMAP2D_GRIDMAP2D_H_ 35 #define GRIDMAP2D_GRIDMAP2D_H_ 37 #include <nav_msgs/OccupancyGrid.h> 39 #include <opencv2/core/core.hpp> 40 #include <opencv2/imgproc/imgproc.hpp> 55 GridMap2D(
const nav_msgs::OccupancyGridConstPtr& gridMap);
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;
71 inline double worldDist(
unsigned x1,
unsigned y1,
unsigned x2,
unsigned y2)
73 return worldDist(cv::Point(x1, y1), cv::Point(x2, y2));
76 inline double worldDist(
const cv::Point& p1,
const cv::Point& p2)
82 static inline double pointDist(
const cv::Point& p1,
const cv::Point& p2)
88 static inline double pointDist2(
const cv::Point& p1,
const cv::Point& p2)
90 return (p1.x - p2.x)*(p1.x - p2.x) + (p1.y - p2.y)*(p1.y - p2.y);
113 void setMap(
const nav_msgs::OccupancyGridConstPtr& gridMap);
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.
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
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
cv::Mat m_binaryMap
binary occupancy map. 255: free, 0 occupied.
std::string m_frameId
"map" frame where ROS OccupancyGrid originated from
const std::string getFrameID() const
returns the tf frame ID of the map (usually "/map")
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)
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:
float getResolution() const
const cv::Mat & distanceMap() const
const cv::Mat & binaryMap() const
Stores a nav_msgs::OccupancyGrid in a convenient opencv cv::Mat as binary map (free: 255...
double worldDist(unsigned x1, unsigned y1, unsigned x2, unsigned y2)
Distance (in m) between two map coordinates (indices)
const CvSize size() const
static double pointDist(const cv::Point &p1, const cv::Point &p2)
Euclidean distance between two points:
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
cv::Mat m_distMap
distance map (in meter)