Stores a nav_msgs::OccupancyGrid in a convenient opencv cv::Mat as binary map (free: 255, occupied: 0) and as distance map (distance to closest obstacle in meter). More...
#include <GridMap2D.h>
Public Member Functions | |
const cv::Mat & | binaryMap () const |
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! | |
const cv::Mat & | distanceMap () const |
float | distanceMapAt (double wx, double wy) const |
Returns distance (in m) at world coordinates <wx,wy> in m; -1 if out of bounds! | |
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 std::string | getFrameID () const |
returns the tf frame ID of the map (usually "/map") | |
const nav_msgs::MapMetaData & | getInfo () const |
float | getResolution () const |
GridMap2D () | |
GridMap2D (const nav_msgs::OccupancyGridConstPtr &gridMap) | |
void | inflateMap (double inflationRaduis) |
bool | inMapBounds (double wx, double wy) const |
check if a coordinate is covered by the map extent (same as worldToMap) | |
bool | isOccupiedAt (double wx, double wy) const |
bool | isOccupiedAtCell (unsigned int mx, unsigned int my) const |
void | mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const |
void | setMap (const nav_msgs::OccupancyGridConstPtr &gridMap) |
Initialize map from a ROS OccupancyGrid message. | |
void | setMap (const cv::Mat &binaryMap) |
Initialize from an existing cv::Map. mapInfo (in particular resultion) remains the same! | |
const CvSize | size () const |
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) |
bool | worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const |
void | worldToMapNoBounds (double wx, double wy, unsigned int &mx, unsigned int &my) const |
virtual | ~GridMap2D () |
Static Public Member Functions | |
static double | pointDist (const cv::Point &p1, const cv::Point &p2) |
Euclidean distance between two points: | |
static double | pointDist2 (const cv::Point &p1, const cv::Point &p2) |
Squared distance between two points: | |
Protected Attributes | |
cv::Mat | m_binaryMap |
binary occupancy map. 255: free, 0 occupied. | |
cv::Mat | m_distMap |
distance map (in meter) | |
std::string | m_frameId |
"map" frame where ROS OccupancyGrid originated from | |
nav_msgs::MapMetaData | m_mapInfo |
Stores a nav_msgs::OccupancyGrid in a convenient opencv cv::Mat as binary map (free: 255, occupied: 0) and as distance map (distance to closest obstacle in meter).
Definition at line 49 of file GridMap2D.h.
Definition at line 36 of file GridMap2D.cpp.
gridmap_2d::GridMap2D::GridMap2D | ( | const nav_msgs::OccupancyGridConstPtr & | gridMap | ) |
Definition at line 42 of file GridMap2D.cpp.
gridmap_2d::GridMap2D::~GridMap2D | ( | ) | [virtual] |
Definition at line 48 of file GridMap2D.cpp.
const cv::Mat& gridmap_2d::GridMap2D::binaryMap | ( | ) | const [inline] |
Definition at line 118 of file GridMap2D.h.
uchar gridmap_2d::GridMap2D::binaryMapAt | ( | double | wx, |
double | wy | ||
) | const |
Returns map value at world coordinates <wx, wy>; out of bounds will be returned as 0!
Definition at line 146 of file GridMap2D.cpp.
uchar gridmap_2d::GridMap2D::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 at line 161 of file GridMap2D.cpp.
const cv::Mat& gridmap_2d::GridMap2D::distanceMap | ( | ) | const [inline] |
Definition at line 116 of file GridMap2D.h.
float gridmap_2d::GridMap2D::distanceMapAt | ( | double | wx, |
double | wy | ||
) | const |
Returns distance (in m) at world coordinates <wx,wy> in m; -1 if out of bounds!
Definition at line 136 of file GridMap2D.cpp.
float gridmap_2d::GridMap2D::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 at line 156 of file GridMap2D.cpp.
const std::string gridmap_2d::GridMap2D::getFrameID | ( | ) | const [inline] |
returns the tf frame ID of the map (usually "/map")
Definition at line 114 of file GridMap2D.h.
const nav_msgs::MapMetaData& gridmap_2d::GridMap2D::getInfo | ( | ) | const [inline] |
Definition at line 111 of file GridMap2D.h.
float gridmap_2d::GridMap2D::getResolution | ( | ) | const [inline] |
Definition at line 112 of file GridMap2D.h.
void gridmap_2d::GridMap2D::inflateMap | ( | double | inflationRaduis | ) |
Inflate occupancy map by inflationRadius
Definition at line 97 of file GridMap2D.cpp.
bool gridmap_2d::GridMap2D::inMapBounds | ( | double | wx, |
double | wy | ||
) | const |
check if a coordinate is covered by the map extent (same as worldToMap)
Definition at line 131 of file GridMap2D.cpp.
bool gridmap_2d::GridMap2D::isOccupiedAt | ( | double | wx, |
double | wy | ||
) | const |
Definition at line 171 of file GridMap2D.cpp.
bool gridmap_2d::GridMap2D::isOccupiedAtCell | ( | unsigned int | mx, |
unsigned int | my | ||
) | const |
Definition at line 166 of file GridMap2D.cpp.
void gridmap_2d::GridMap2D::mapToWorld | ( | unsigned int | mx, |
unsigned int | my, | ||
double & | wx, | ||
double & | wy | ||
) | const |
Definition at line 106 of file GridMap2D.cpp.
static double gridmap_2d::GridMap2D::pointDist | ( | const cv::Point & | p1, |
const cv::Point & | p2 | ||
) | [inline, static] |
Euclidean distance between two points:
Definition at line 77 of file GridMap2D.h.
static double gridmap_2d::GridMap2D::pointDist2 | ( | const cv::Point & | p1, |
const cv::Point & | p2 | ||
) | [inline, static] |
Squared distance between two points:
Definition at line 82 of file GridMap2D.h.
void gridmap_2d::GridMap2D::setMap | ( | const nav_msgs::OccupancyGridConstPtr & | gridMap | ) |
Initialize map from a ROS OccupancyGrid message.
Definition at line 52 of file GridMap2D.cpp.
void gridmap_2d::GridMap2D::setMap | ( | const cv::Mat & | binaryMap | ) |
Initialize from an existing cv::Map. mapInfo (in particular resultion) remains the same!
Definition at line 85 of file GridMap2D.cpp.
const CvSize gridmap_2d::GridMap2D::size | ( | ) | const [inline] |
Definition at line 120 of file GridMap2D.h.
double gridmap_2d::GridMap2D::worldDist | ( | unsigned | x1, |
unsigned | y1, | ||
unsigned | x2, | ||
unsigned | y2 | ||
) | [inline] |
Distance (in m) between two map coordinates (indices)
Definition at line 68 of file GridMap2D.h.
double gridmap_2d::GridMap2D::worldDist | ( | const cv::Point & | p1, |
const cv::Point & | p2 | ||
) | [inline] |
Definition at line 72 of file GridMap2D.h.
bool gridmap_2d::GridMap2D::worldToMap | ( | double | wx, |
double | wy, | ||
unsigned int & | mx, | ||
unsigned int & | my | ||
) | const |
Definition at line 118 of file GridMap2D.cpp.
void gridmap_2d::GridMap2D::worldToMapNoBounds | ( | double | wx, |
double | wy, | ||
unsigned int & | mx, | ||
unsigned int & | my | ||
) | const |
Definition at line 113 of file GridMap2D.cpp.
cv::Mat gridmap_2d::GridMap2D::m_binaryMap [protected] |
binary occupancy map. 255: free, 0 occupied.
Definition at line 120 of file GridMap2D.h.
cv::Mat gridmap_2d::GridMap2D::m_distMap [protected] |
distance map (in meter)
Definition at line 125 of file GridMap2D.h.
std::string gridmap_2d::GridMap2D::m_frameId [protected] |
"map" frame where ROS OccupancyGrid originated from
Definition at line 127 of file GridMap2D.h.
nav_msgs::MapMetaData gridmap_2d::GridMap2D::m_mapInfo [protected] |
Definition at line 126 of file GridMap2D.h.