Public Member Functions | Static Public Member Functions
grid_map::GridMapRosConverter Class Reference

#include <GridMapRosConverter.hpp>

List of all members.

Public Member Functions

 GridMapRosConverter ()
virtual ~GridMapRosConverter ()

Static Public Member Functions

static bool addColorLayerFromImage (const sensor_msgs::Image &image, const std::string &layer, grid_map::GridMap &gridMap)
static bool addLayerFromImage (const sensor_msgs::Image &image, const std::string &layer, grid_map::GridMap &gridMap, const float lowerValue=0.0, const float upperValue=1.0, const double alphaThreshold=0.5)
static bool fromMessage (const grid_map_msgs::GridMap &message, grid_map::GridMap &gridMap)
static bool fromOccupancyGrid (const nav_msgs::OccupancyGrid &occupancyGrid, const std::string &layer, grid_map::GridMap &gridMap)
static bool initializeFromImage (const sensor_msgs::Image &image, const double resolution, grid_map::GridMap &gridMap, const grid_map::Position &position=grid_map::Position::Zero())
static bool loadFromBag (const std::string &pathToBag, const std::string &topic, grid_map::GridMap &gridMap)
static bool saveToBag (const grid_map::GridMap &gridMap, const std::string &pathToBag, const std::string &topic)
static bool toCvImage (const grid_map::GridMap &gridMap, const std::string &layer, const std::string encoding, cv_bridge::CvImage &cvImage)
static bool toCvImage (const grid_map::GridMap &gridMap, const std::string &layer, const std::string encoding, const float lowerValue, const float upperValue, cv_bridge::CvImage &cvImage)
static void toGridCells (const grid_map::GridMap &gridMap, const std::string &layer, float lowerThreshold, float upperThreshold, nav_msgs::GridCells &gridCells)
static bool toImage (const grid_map::GridMap &gridMap, const std::string &layer, const std::string encoding, sensor_msgs::Image &image)
static bool toImage (const grid_map::GridMap &gridMap, const std::string &layer, const std::string encoding, const float lowerValue, const float upperValue, sensor_msgs::Image &image)
static void toMessage (const grid_map::GridMap &gridMap, grid_map_msgs::GridMap &message)
static void toMessage (const grid_map::GridMap &gridMap, const std::vector< std::string > &layers, grid_map_msgs::GridMap &message)
static void toOccupancyGrid (const grid_map::GridMap &gridMap, const std::string &layer, float dataMin, float dataMax, nav_msgs::OccupancyGrid &occupancyGrid)
static void toPointCloud (const grid_map::GridMap &gridMap, const std::string &pointLayer, sensor_msgs::PointCloud2 &pointCloud)
static void toPointCloud (const grid_map::GridMap &gridMap, const std::vector< std::string > &layers, const std::string &pointLayer, sensor_msgs::PointCloud2 &pointCloud)

Detailed Description

ROS interface for the Grid Map library.

Definition at line 35 of file GridMapRosConverter.hpp.


Constructor & Destructor Documentation

Default constructor.

Definition at line 30 of file GridMapRosConverter.cpp.

Destructor.

Definition at line 34 of file GridMapRosConverter.cpp.


Member Function Documentation

bool grid_map::GridMapRosConverter::addColorLayerFromImage ( const sensor_msgs::Image &  image,
const std::string &  layer,
grid_map::GridMap gridMap 
) [static]

Adds a color layer with data from an image.

Parameters:
[in]imagethe image to be added.
[in]layerthe layer that is filled with the image.
[out]gridMapthe grid map to be populated.
Returns:
true if successful, false otherwise.

Definition at line 359 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::addLayerFromImage ( const sensor_msgs::Image &  image,
const std::string &  layer,
grid_map::GridMap gridMap,
const float  lowerValue = 0.0,
const float  upperValue = 1.0,
const double  alphaThreshold = 0.5 
) [static]

Adds a layer with data from image.

Parameters:
[in]imagethe image to be added. If it is a color image (bgr or bgra encoding), it will be transformed in a grayscale image.
[in]layerthe layer that is filled with the image data.
[out]gridMapthe grid map to be populated.
[in]optional)lowerValue value of the layer corresponding to black image pixels.
[in]optional)upperValue value of the layer corresponding to white image pixels.
[in]optional)alphaThreshold the threshold ([0.0, 1.0]) for the alpha value at which cells in the grid map are marked as empty.
Returns:
true if successful, false otherwise.

Definition at line 325 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::fromMessage ( const grid_map_msgs::GridMap &  message,
grid_map::GridMap gridMap 
) [static]

Converts a ROS grid map message to a grid map object.

Parameters:
[in]messagethe grid map message.
[out]gridMapthe grid map object to be initialized.
Returns:
true if successful, false otherwise.

Definition at line 38 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::fromOccupancyGrid ( const nav_msgs::OccupancyGrid &  occupancyGrid,
const std::string &  layer,
grid_map::GridMap gridMap 
) [static]

Converts an occupancy grid message to a layer of a grid map.

Parameters:
[in]occupancyGridthe occupancy grid to be converted.
[in]layerthe layer to which the occupancy grid will be converted.
[out]gridMapthe grid map to be populated.
Returns:
true if successful.

Definition at line 205 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::initializeFromImage ( const sensor_msgs::Image &  image,
const double  resolution,
grid_map::GridMap gridMap,
const grid_map::Position position = grid_map::Position::Zero() 
) [static]

Initializes the geometry of a grid map from an image messages. This changes the geometry of the map and deletes all contents of the layers!

Parameters:
[in]imagethe image.
[in]resolutionthe desired resolution of the grid map [m/cell].
[out]gridMapthe grid map to be initialized.
[in]optional)position the position of the grid map.
Returns:
true if successful, false otherwise.

Definition at line 312 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::loadFromBag ( const std::string &  pathToBag,
const std::string &  topic,
grid_map::GridMap gridMap 
) [static]

Loads a GridMap from a ROS bag.

Parameters:
[in]pathToBagthe path to the ROS bag file.
[in]topicthe topic name of the grid map in the ROS bag.
[out]gridMapthe grid map object to be initialized.
Returns:
true if successful, false otherwise.

Definition at line 461 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::saveToBag ( const grid_map::GridMap gridMap,
const std::string &  pathToBag,
const std::string &  topic 
) [static]

Saves a grid map into a ROS bag. The timestamp of the grid map is used as time for storing the message in the ROS bag. The time value 0.0 is not a valid bag time and will be replaced by the current time.

Parameters:
[in]gridMapthe grid map object to be saved in the ROS bag.
[in]pathToBagthe path to the ROS bag file.
[in]topicthe name of the topic in the ROS bag.
Returns:
true if successful, false otherwise.

Definition at line 442 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::toCvImage ( const grid_map::GridMap gridMap,
const std::string &  layer,
const std::string  encoding,
cv_bridge::CvImage &  cvImage 
) [static]

Creates a cv image from a grid map layer. This conversion sets the corresponding black and white pixel value to the min. and max. data of the layer data.

Parameters:
[in]gridmap to be added.
[in]layerthe layer that is converted to the image.
[in]encodingthe desired encoding of the image.
[out]cvImagethe to be populated.
Returns:
true if successful, false otherwise.

Definition at line 406 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::toCvImage ( const grid_map::GridMap gridMap,
const std::string &  layer,
const std::string  encoding,
const float  lowerValue,
const float  upperValue,
cv_bridge::CvImage &  cvImage 
) [static]

Creates a cv image from a grid map layer.

Parameters:
[in]gridmap to be added.
[in]layerthe layer that is converted to the image.
[in]encodingthe desired encoding of the image.
[in]lowerValuethe value of the layer corresponding to black image pixels.
[in]upperValuethe value of the layer corresponding to white image pixels.
[out]cvImageto be populated.
Returns:
true if successful, false otherwise.

Definition at line 414 of file GridMapRosConverter.cpp.

void grid_map::GridMapRosConverter::toGridCells ( const grid_map::GridMap gridMap,
const std::string &  layer,
float  lowerThreshold,
float  upperThreshold,
nav_msgs::GridCells &  gridCells 
) [static]

Converts a grid map object to a ROS GridCells message. Set the layer to be transformed as grid cells with `layer`, all other layers will be neglected. Values that are between the lower and upper threshold are converted to grid cells, other data is neglected.

Parameters:
[in]gridMapthe grid map object.
[in]layerthe layer that is transformed as grid cells.
[in]lowerThresholdthe lower threshold.
[in]upperThresholdthe upper threshold.
[out]gridCellsthe message to be populated.

Definition at line 289 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::toImage ( const grid_map::GridMap gridMap,
const std::string &  layer,
const std::string  encoding,
sensor_msgs::Image &  image 
) [static]

Creates an image message from a grid map layer. This conversion sets the corresponding black and white pixel value to the min. and max. data of the layer data.

Parameters:
[in]gridmap to be added.
[in]layerthe layer that is converted to the image.
[in]encodingthe desired encoding of the image.
[out]imagethe message to be populated.
Returns:
true if successful, false otherwise.

Definition at line 387 of file GridMapRosConverter.cpp.

bool grid_map::GridMapRosConverter::toImage ( const grid_map::GridMap gridMap,
const std::string &  layer,
const std::string  encoding,
const float  lowerValue,
const float  upperValue,
sensor_msgs::Image &  image 
) [static]

Creates an image message from a grid map layer.

Parameters:
[in]gridmap to be added.
[in]layerthe layer that is converted to the image.
[in]encodingthe desired encoding of the image.
[in]lowerValuethe value of the layer corresponding to black image pixels.
[in]upperValuethe value of the layer corresponding to white image pixels.
[out]imagethe message to be populated.
Returns:
true if successful, false otherwise.

Definition at line 396 of file GridMapRosConverter.cpp.

void grid_map::GridMapRosConverter::toMessage ( const grid_map::GridMap gridMap,
grid_map_msgs::GridMap &  message 
) [static]

Converts all layers of a grid map object to a ROS grid map message.

Parameters:
[in]gridMapthe grid map object.
[out]messagethe grid map message to be populated.

Definition at line 62 of file GridMapRosConverter.cpp.

void grid_map::GridMapRosConverter::toMessage ( const grid_map::GridMap gridMap,
const std::vector< std::string > &  layers,
grid_map_msgs::GridMap &  message 
) [static]

Converts requested layers of a grid map object to a ROS grid map message.

Parameters:
[in]gridMapthe grid map object.
[in]layersthe layers to be added to the message.
[out]messagethe grid map message to be populated.

Definition at line 67 of file GridMapRosConverter.cpp.

void grid_map::GridMapRosConverter::toOccupancyGrid ( const grid_map::GridMap gridMap,
const std::string &  layer,
float  dataMin,
float  dataMax,
nav_msgs::OccupancyGrid &  occupancyGrid 
) [static]

Converts a grid map object to a ROS OccupancyGrid message. Set the layer to be transformed as the cell data of the occupancy grid with `layer`, all other layers will be neglected.

Parameters:
[in]gridMapthe grid map object.
[in]layerthe layer that is transformed to the occupancy cell data.
[in]dataMinthe minimum value of the grid map data (used to normalize the cell data in [min, max]).
[in]dataMaxthe maximum value of the grid map data (used to normalize the cell data in [min, max]).
[out]occupancyGridthe message to be populated.

Definition at line 251 of file GridMapRosConverter.cpp.

void grid_map::GridMapRosConverter::toPointCloud ( const grid_map::GridMap gridMap,
const std::string &  pointLayer,
sensor_msgs::PointCloud2 &  pointCloud 
) [static]

Converts a grid map object to a ROS PointCloud2 message. Set the layer to be transformed as the points of the point cloud with `pointLayer`, all other types will be added as additional fields.

Parameters:
[in]gridMapthe grid map object.
[in]pointLayerthe type that is transformed to points.
[out]pointCloudthe message to be populated.

Definition at line 97 of file GridMapRosConverter.cpp.

void grid_map::GridMapRosConverter::toPointCloud ( const grid_map::GridMap gridMap,
const std::vector< std::string > &  layers,
const std::string &  pointLayer,
sensor_msgs::PointCloud2 &  pointCloud 
) [static]

Converts a grid map object to a ROS PointCloud2 message. Set the layer to be transformed as the points of the point cloud with `pointLayer` and all other types to be added as additional layers with `layers`.

Parameters:
[in]gridMapthe grid map object.
[in]layersthe layers that should be added as fields to the point cloud. Must include the `pointLayer`.
[in]pointLayerthe layer that is transformed to points.
[out]pointCloudthe message to be populated.

Definition at line 104 of file GridMapRosConverter.cpp.


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


grid_map_ros
Author(s): Péter Fankhauser
autogenerated on Mon Oct 9 2017 03:09:29