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 <grid_map_2d.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! More... | |
| 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! More... | |
| 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! More... | |
| 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! More... | |
| const std::string | getFrameID () const |
| returns the tf frame ID of the map (usually "/map") More... | |
| 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) More... | |
| 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. More... | |
| void | setMap (const cv::Mat &binaryMap) |
| Initialize from an existing cv::Map. mapInfo (in particular resultion) remains the same! More... | |
| const CvSize | size () const |
| double | worldDist (unsigned x1, unsigned y1, unsigned x2, unsigned y2) |
| Distance (in m) between two map coordinates (indices) More... | |
| 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: More... | |
| static double | pointDist2 (const cv::Point &p1, const cv::Point &p2) |
| Squared distance between two points: More... | |
Protected Attributes | |
| cv::Mat | m_binaryMap |
| binary occupancy map. 255: free, 0 occupied. More... | |
| cv::Mat | m_distMap |
| distance map (in meter) More... | |
| std::string | m_frameId |
| "map" frame where ROS OccupancyGrid originated from More... | |
| 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 51 of file grid_map_2d.h.
| vigir_gridmap_2d::GridMap2D::GridMap2D | ( | ) |
Definition at line 41 of file grid_map_2d.cpp.
| vigir_gridmap_2d::GridMap2D::GridMap2D | ( | const nav_msgs::OccupancyGridConstPtr & | gridMap | ) |
Definition at line 47 of file grid_map_2d.cpp.
|
virtual |
Definition at line 52 of file grid_map_2d.cpp.
|
inline |
Definition at line 125 of file grid_map_2d.h.
| uchar vigir_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 155 of file grid_map_2d.cpp.
| uchar vigir_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 170 of file grid_map_2d.cpp.
|
inline |
Definition at line 123 of file grid_map_2d.h.
| float vigir_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 145 of file grid_map_2d.cpp.
| float vigir_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 165 of file grid_map_2d.cpp.
|
inline |
returns the tf frame ID of the map (usually "/map")
Definition at line 121 of file grid_map_2d.h.
|
inline |
Definition at line 118 of file grid_map_2d.h.
|
inline |
Definition at line 119 of file grid_map_2d.h.
| void vigir_gridmap_2d::GridMap2D::inflateMap | ( | double | inflationRaduis | ) |
Inflate occupancy map by inflationRadius
Definition at line 103 of file grid_map_2d.cpp.
| bool vigir_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 139 of file grid_map_2d.cpp.
| bool vigir_gridmap_2d::GridMap2D::isOccupiedAt | ( | double | wx, |
| double | wy | ||
| ) | const |
Definition at line 180 of file grid_map_2d.cpp.
| bool vigir_gridmap_2d::GridMap2D::isOccupiedAtCell | ( | unsigned int | mx, |
| unsigned int | my | ||
| ) | const |
Definition at line 175 of file grid_map_2d.cpp.
| void vigir_gridmap_2d::GridMap2D::mapToWorld | ( | unsigned int | mx, |
| unsigned int | my, | ||
| double & | wx, | ||
| double & | wy | ||
| ) | const |
Definition at line 113 of file grid_map_2d.cpp.
|
inlinestatic |
Euclidean distance between two points:
Definition at line 82 of file grid_map_2d.h.
|
inlinestatic |
Squared distance between two points:
Definition at line 88 of file grid_map_2d.h.
| void vigir_gridmap_2d::GridMap2D::setMap | ( | const nav_msgs::OccupancyGridConstPtr & | gridMap | ) |
Initialize map from a ROS OccupancyGrid message.
Definition at line 56 of file grid_map_2d.cpp.
| void vigir_gridmap_2d::GridMap2D::setMap | ( | const cv::Mat & | binaryMap | ) |
Initialize from an existing cv::Map. mapInfo (in particular resultion) remains the same!
Definition at line 90 of file grid_map_2d.cpp.
|
inline |
Definition at line 127 of file grid_map_2d.h.
|
inline |
Distance (in m) between two map coordinates (indices)
Definition at line 71 of file grid_map_2d.h.
|
inline |
Definition at line 76 of file grid_map_2d.h.
| bool vigir_gridmap_2d::GridMap2D::worldToMap | ( | double | wx, |
| double | wy, | ||
| unsigned int & | mx, | ||
| unsigned int & | my | ||
| ) | const |
Definition at line 125 of file grid_map_2d.cpp.
| void vigir_gridmap_2d::GridMap2D::worldToMapNoBounds | ( | double | wx, |
| double | wy, | ||
| unsigned int & | mx, | ||
| unsigned int & | my | ||
| ) | const |
Definition at line 119 of file grid_map_2d.cpp.
|
protected |
binary occupancy map. 255: free, 0 occupied.
Definition at line 130 of file grid_map_2d.h.
|
protected |
distance map (in meter)
Definition at line 131 of file grid_map_2d.h.
|
protected |
"map" frame where ROS OccupancyGrid originated from
Definition at line 133 of file grid_map_2d.h.
|
protected |
Definition at line 132 of file grid_map_2d.h.