32 #ifndef GRIDMAP2D_GRIDMAP2D_H_ 33 #define GRIDMAP2D_GRIDMAP2D_H_ 35 #include <opencv2/core/core.hpp> 36 #include <opencv2/imgproc/imgproc.hpp> 37 #include <nav_msgs/OccupancyGrid.h> 53 GridMap2D(
const nav_msgs::OccupancyGridConstPtr& grid_map,
bool unknown_as_obstacle =
false);
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){
72 return worldDist(cv::Point(x1, y1), cv::Point(x2, y2));
75 inline double worldDist(
const cv::Point& p1,
const cv::Point& p2){
80 static inline double pointDist(
const cv::Point& p1,
const cv::Point& p2){
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);
112 void setMap(
const nav_msgs::OccupancyGridConstPtr& grid_map,
bool unknown_as_obstacle =
false);
118 void setMap(
const cv::Mat& binary_map);
static const uchar OCCUPIED
char value for "free": 0
float getResolution() const
nav_msgs::OccupancyGrid toOccupancyGridMsg() const
Converts back into a ROS nav_msgs::OccupancyGrid msg.
const nav_msgs::MapMetaData & getInfo() const
bool isOccupiedAt(double wx, double wy) const
void worldToMapNoBounds(double wx, double wy, unsigned int &mx, unsigned int &my) const
boost::shared_ptr< const GridMap2D > GridMap2DConstPtr
void setMap(const nav_msgs::OccupancyGridConstPtr &grid_map, bool unknown_as_obstacle=false)
Initialize map from a ROS OccupancyGrid message.
cv::Mat m_distMap
distance map (in meter)
static double pointDist(const cv::Point &p1, const cv::Point &p2)
Euclidean distance between two points:
static const uchar FREE
char value for "free": 255
boost::shared_ptr< GridMap2D > GridMap2DPtr
const std::string getFrameID() const
returns the tf frame ID of the map (usually "/map")
void updateDistanceMap()
Recalculate the internal distance map. Required after manual changes to the grid map data...
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!
const CvSize size() const
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
std::string m_frameId
"map" frame where ROS OccupancyGrid originated from
uchar binaryMapAt(double wx, double wy) const
Returns map value at world coordinates <wx, wy>; out of bounds will be returned as 0! ...
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!
float distanceMapAt(double wx, double wy) const
Returns distance (in m) at world coordinates <wx,wy> in m; -1 if out of bounds!
const cv::Mat & distanceMap() const
nav_msgs::MapMetaData m_mapInfo
void inflateMap(double inflationRaduis)
Stores a nav_msgs::OccupancyGrid in a convenient opencv cv::Mat as binary map (free: 255...
const cv::Mat & binaryMap() const
bool inMapBounds(double wx, double wy) const
check if a coordinate is covered by the map extent (same as worldToMap)
double worldDist(unsigned x1, unsigned y1, unsigned x2, unsigned y2)
Distance (in m) between two map coordinates (indices)
double worldDist(const cv::Point &p1, const cv::Point &p2)
cv::Mat m_binaryMap
binary occupancy map. 255: free, 0 occupied.
bool isOccupiedAtCell(unsigned int mx, unsigned int my) const
static double pointDist2(const cv::Point &p1, const cv::Point &p2)
Squared distance between two points: