#include <GridMapRosConverter.hpp>
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, const std::vector< std::string > &layers, bool copyBasicLayers=true, bool copyAllNonBasicLayers=true) |
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) |
ROS interface for the Grid Map library.
Definition at line 35 of file GridMapRosConverter.hpp.
grid_map::GridMapRosConverter::GridMapRosConverter | ( | ) |
Default constructor.
Definition at line 30 of file GridMapRosConverter.cpp.
|
virtual |
Destructor.
Definition at line 34 of file GridMapRosConverter.cpp.
|
static |
Adds a color layer with data from an image.
[in] | image | the image to be added. |
[in] | layer | the layer that is filled with the image. |
[out] | gridMap | the grid map to be populated. |
Definition at line 379 of file GridMapRosConverter.cpp.
|
static |
Adds a layer with data from image.
[in] | image | the image to be added. If it is a color image (bgr or bgra encoding), it will be transformed in a grayscale image. |
[in] | layer | the layer that is filled with the image data. |
[out] | gridMap | the grid map to be populated. |
[in] |
Definition at line 345 of file GridMapRosConverter.cpp.
|
static |
Converts a ROS grid map message to a grid map object.
[in] | message | the grid map message. |
[in] | layers | the layers to be copied. |
[in] | copyBasicLayers | if true, basic layers are copied. |
[in] | copyAllNonBasicLayers | if true, all basic layers are copied, otherwise only that one specified in layers. |
[out] | gridMap | the grid map object to be initialized. |
Definition at line 38 of file GridMapRosConverter.cpp.
|
static |
Converts a ROS grid map message to a grid map object.
[in] | message | the grid map message. |
[out] | gridMap | the grid map object to be initialized. |
Definition at line 77 of file GridMapRosConverter.cpp.
|
static |
Converts an occupancy grid message to a layer of a grid map.
[in] | occupancyGrid | the occupancy grid to be converted. |
[in] | layer | the layer to which the occupancy grid will be converted. |
[out] | gridMap | the grid map to be populated. |
Definition at line 225 of file GridMapRosConverter.cpp.
|
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!
[in] | image | the image. |
[in] | resolution | the desired resolution of the grid map [m/cell]. |
[out] | gridMap | the grid map to be initialized. |
[in] |
Definition at line 332 of file GridMapRosConverter.cpp.
|
static |
Loads a GridMap from a ROS bag.
[in] | pathToBag | the path to the ROS bag file. |
[in] | topic | the topic name of the grid map in the ROS bag. |
[out] | gridMap | the grid map object to be initialized. |
Definition at line 482 of file GridMapRosConverter.cpp.
|
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.
[in] | gridMap | the grid map object to be saved in the ROS bag. |
[in] | pathToBag | the path to the ROS bag file. |
[in] | topic | the name of the topic in the ROS bag. |
Definition at line 462 of file GridMapRosConverter.cpp.
|
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.
[in] | grid | map to be added. |
[in] | layer | the layer that is converted to the image. |
[in] | encoding | the desired encoding of the image. |
[out] | cvImage | the to be populated. |
Definition at line 426 of file GridMapRosConverter.cpp.
|
static |
Creates a cv image from a grid map layer.
[in] | grid | map to be added. |
[in] | layer | the layer that is converted to the image. |
[in] | encoding | the desired encoding of the image. |
[in] | lowerValue | the value of the layer corresponding to black image pixels. |
[in] | upperValue | the value of the layer corresponding to white image pixels. |
[out] | cvImage | to be populated. |
Definition at line 434 of file GridMapRosConverter.cpp.
|
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.
[in] | gridMap | the grid map object. |
[in] | layer | the layer that is transformed as grid cells. |
[in] | lowerThreshold | the lower threshold. |
[in] | upperThreshold | the upper threshold. |
[out] | gridCells | the message to be populated. |
Definition at line 309 of file GridMapRosConverter.cpp.
|
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.
[in] | grid | map to be added. |
[in] | layer | the layer that is converted to the image. |
[in] | encoding | the desired encoding of the image. |
[out] | image | the message to be populated. |
Definition at line 407 of file GridMapRosConverter.cpp.
|
static |
Creates an image message from a grid map layer.
[in] | grid | map to be added. |
[in] | layer | the layer that is converted to the image. |
[in] | encoding | the desired encoding of the image. |
[in] | lowerValue | the value of the layer corresponding to black image pixels. |
[in] | upperValue | the value of the layer corresponding to white image pixels. |
[out] | image | the message to be populated. |
Definition at line 416 of file GridMapRosConverter.cpp.
|
static |
Converts all layers of a grid map object to a ROS grid map message.
[in] | gridMap | the grid map object. |
[out] | message | the grid map message to be populated. |
Definition at line 82 of file GridMapRosConverter.cpp.
|
static |
Converts requested layers of a grid map object to a ROS grid map message.
[in] | gridMap | the grid map object. |
[in] | layers | the layers to be added to the message. |
[out] | message | the grid map message to be populated. |
Definition at line 87 of file GridMapRosConverter.cpp.
|
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.
[in] | gridMap | the grid map object. |
[in] | layer | the layer that is transformed to the occupancy cell data. |
[in] | dataMin | the minimum value of the grid map data (used to normalize the cell data in [min, max]). |
[in] | dataMax | the maximum value of the grid map data (used to normalize the cell data in [min, max]). |
[out] | occupancyGrid | the message to be populated. |
Definition at line 271 of file GridMapRosConverter.cpp.
|
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.
[in] | gridMap | the grid map object. |
[in] | pointLayer | the type that is transformed to points. |
[out] | pointCloud | the message to be populated. |
Definition at line 117 of file GridMapRosConverter.cpp.
|
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
.
[in] | gridMap | the grid map object. |
[in] | layers | the layers that should be added as fields to the point cloud. Must include the pointLayer . |
[in] | pointLayer | the layer that is transformed to points. |
[out] | pointCloud | the message to be populated. |
Definition at line 124 of file GridMapRosConverter.cpp.