Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Attributes | List of all members
gridmap_2d::GridMap2D Class Reference

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! 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...
 
uchar & binaryMapAtCell (unsigned int mx, unsigned int my)
 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 &grid_map, bool unknown_as_obstacle=false)
 Create from nav_msgs::OccupancyGrid. More...
 
 GridMap2D (const GridMap2D &other)
 Copy constructor, performs a deep copy of underlying data structures. More...
 
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 &grid_map, bool unknown_as_obstacle=false)
 Initialize map from a ROS OccupancyGrid message. More...
 
void setMap (const cv::Mat &binary_map)
 Initialize from an existing cv::Map. mapInfo (in particular resolution) remains the same! More...
 
const CvSize size () const
 
nav_msgs::OccupancyGrid toOccupancyGridMsg () const
 Converts back into a ROS nav_msgs::OccupancyGrid msg. More...
 
void updateDistanceMap ()
 Recalculate the internal distance map. Required after manual changes to the grid map data. More...
 
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...
 

Static Public Attributes

static const uchar FREE = 255
 char value for "free": 255 More...
 
static const uchar OCCUPIED = 0
 char value for "free": 0 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
 

Detailed Description

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.

Constructor & Destructor Documentation

gridmap_2d::GridMap2D::GridMap2D ( )

Definition at line 36 of file GridMap2D.cpp.

gridmap_2d::GridMap2D::GridMap2D ( const nav_msgs::OccupancyGridConstPtr &  grid_map,
bool  unknown_as_obstacle = false 
)

Create from nav_msgs::OccupancyGrid.

Definition at line 42 of file GridMap2D.cpp.

gridmap_2d::GridMap2D::GridMap2D ( const GridMap2D other)

Copy constructor, performs a deep copy of underlying data structures.

Definition at line 48 of file GridMap2D.cpp.

gridmap_2d::GridMap2D::~GridMap2D ( )
virtual

Definition at line 57 of file GridMap2D.cpp.

Member Function Documentation

const cv::Mat& gridmap_2d::GridMap2D::binaryMap ( ) const
inline
Returns
the cv::Mat binary image.

Definition at line 130 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 185 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 199 of file GridMap2D.cpp.

uchar & gridmap_2d::GridMap2D::binaryMapAtCell ( unsigned int  mx,
unsigned int  my 
)

Returns map value at map cell <mx, my>; out of bounds will be returned as 0!

Definition at line 203 of file GridMap2D.cpp.

const cv::Mat& gridmap_2d::GridMap2D::distanceMap ( ) const
inline
Returns
the cv::Mat distance image.

Definition at line 128 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 175 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 194 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 126 of file GridMap2D.h.

const nav_msgs::MapMetaData& gridmap_2d::GridMap2D::getInfo ( ) const
inline

Definition at line 123 of file GridMap2D.h.

float gridmap_2d::GridMap2D::getResolution ( ) const
inline

Definition at line 124 of file GridMap2D.h.

void gridmap_2d::GridMap2D::inflateMap ( double  inflationRaduis)

Inflate occupancy map by inflationRadius

Definition at line 136 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 170 of file GridMap2D.cpp.

bool gridmap_2d::GridMap2D::isOccupiedAt ( double  wx,
double  wy 
) const
Returns
true if map is occupied at world coordinate <wx, wy>. Out of bounds will be returned as occupied.

Definition at line 213 of file GridMap2D.cpp.

bool gridmap_2d::GridMap2D::isOccupiedAtCell ( unsigned int  mx,
unsigned int  my 
) const
Returns
true if map is occupied at cell <mx, my>

Definition at line 208 of file GridMap2D.cpp.

void gridmap_2d::GridMap2D::mapToWorld ( unsigned int  mx,
unsigned int  my,
double &  wx,
double &  wy 
) const

Definition at line 145 of file GridMap2D.cpp.

static double gridmap_2d::GridMap2D::pointDist ( const cv::Point &  p1,
const cv::Point &  p2 
)
inlinestatic

Euclidean distance between two points:

Definition at line 80 of file GridMap2D.h.

static double gridmap_2d::GridMap2D::pointDist2 ( const cv::Point &  p1,
const cv::Point &  p2 
)
inlinestatic

Squared distance between two points:

Definition at line 85 of file GridMap2D.h.

void gridmap_2d::GridMap2D::setMap ( const nav_msgs::OccupancyGridConstPtr &  grid_map,
bool  unknown_as_obstacle = false 
)

Initialize map from a ROS OccupancyGrid message.

Definition at line 67 of file GridMap2D.cpp.

void gridmap_2d::GridMap2D::setMap ( const cv::Mat &  binary_map)

Initialize from an existing cv::Map. mapInfo (in particular resolution) remains the same!

Definition at line 124 of file GridMap2D.cpp.

const CvSize gridmap_2d::GridMap2D::size ( ) const
inline
Returns
the size of the cv::Mat binary image. Note that x/y are swapped wrt. height/width

Definition at line 132 of file GridMap2D.h.

nav_msgs::OccupancyGrid gridmap_2d::GridMap2D::toOccupancyGridMsg ( ) const

Converts back into a ROS nav_msgs::OccupancyGrid msg.

Definition at line 100 of file GridMap2D.cpp.

void gridmap_2d::GridMap2D::updateDistanceMap ( )

Recalculate the internal distance map. Required after manual changes to the grid map data.

Definition at line 61 of file GridMap2D.cpp.

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 71 of file GridMap2D.h.

double gridmap_2d::GridMap2D::worldDist ( const cv::Point &  p1,
const cv::Point &  p2 
)
inline

Definition at line 75 of file GridMap2D.h.

bool gridmap_2d::GridMap2D::worldToMap ( double  wx,
double  wy,
unsigned int &  mx,
unsigned int &  my 
) const

Definition at line 157 of file GridMap2D.cpp.

void gridmap_2d::GridMap2D::worldToMapNoBounds ( double  wx,
double  wy,
unsigned int &  mx,
unsigned int &  my 
) const

Definition at line 152 of file GridMap2D.cpp.

Member Data Documentation

const uchar gridmap_2d::GridMap2D::FREE = 255
static

char value for "free": 255

Definition at line 134 of file GridMap2D.h.

cv::Mat gridmap_2d::GridMap2D::m_binaryMap
protected

binary occupancy map. 255: free, 0 occupied.

Definition at line 138 of file GridMap2D.h.

cv::Mat gridmap_2d::GridMap2D::m_distMap
protected

distance map (in meter)

Definition at line 139 of file GridMap2D.h.

std::string gridmap_2d::GridMap2D::m_frameId
protected

"map" frame where ROS OccupancyGrid originated from

Definition at line 141 of file GridMap2D.h.

nav_msgs::MapMetaData gridmap_2d::GridMap2D::m_mapInfo
protected

Definition at line 140 of file GridMap2D.h.

const uchar gridmap_2d::GridMap2D::OCCUPIED = 0
static

char value for "free": 0

Definition at line 135 of file GridMap2D.h.


The documentation for this class was generated from the following files:


gridmap_2d
Author(s): Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:21