Class GridMapRosConverter

Class Documentation

class GridMapRosConverter

ROS interface for the Grid Map library.

Public Functions

GridMapRosConverter()

Default constructor.

virtual ~GridMapRosConverter()

Destructor.

Public Static Functions

static bool fromMessage(const grid_map_msgs::msg::GridMap &message, grid_map::GridMap &gridMap, const std::vector<std::string> &layers, bool copyBasicLayers = true, bool copyAllNonBasicLayers = true)

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

Parameters:
  • message[in] the grid map message.

  • layers[in] the layers to be copied.

  • copyBasicLayers[in] if true, basic layers are copied.

  • copyAllNonBasicLayers[in] if true, all basic layers are copied, otherwise only that one specified in layers.

  • gridMap[out] the grid map object to be initialized.

Returns:

true if successful, false otherwise.

static bool fromMessage(const grid_map_msgs::msg::GridMap &message, grid_map::GridMap &gridMap)

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

Parameters:
  • message[in] the grid map message.

  • gridMap[out] the grid map object to be initialized.

Returns:

true if successful, false otherwise.

static std::unique_ptr<grid_map_msgs::msg::GridMap> toMessage(const grid_map::GridMap &gridMap)

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

Parameters:
  • gridMap[in] the grid map object.

  • message[out] the grid map message to be populated.

static std::unique_ptr<grid_map_msgs::msg::GridMap> toMessage(const grid_map::GridMap &gridMap, const std::vector<std::string> &layers)

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

Parameters:
  • gridMap[in] the grid map object.

  • layers[in] the layers to be added to the message.

  • message[out] the grid map message to be populated.

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

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:
  • gridMap[in] the grid map object.

  • pointLayer[in] the type that is transformed to points.

  • pointCloud[out] the message to be populated.

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

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:
  • gridMap[in] the grid map object.

  • layers[in] the layers that should be added as fields to the point cloud. Must include the pointLayer.

  • pointLayer[in] the layer that is transformed to points.

  • pointCloud[out] the message to be populated.

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

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

Parameters:
  • occupancyGrid[in] the occupancy grid to be converted.

  • layer[in] the layer to which the occupancy grid will be converted.

  • gridMap[out] the grid map to be populated.

Returns:

true if successful.

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

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:
  • gridMap[in] the grid map object.

  • layer[in] the layer that is transformed to the occupancy cell data.

  • dataMin[in] the minimum value of the grid map data (used to normalize the cell data in [min, max]).

  • dataMax[in] the maximum value of the grid map data (used to normalize the cell data in [min, max]).

  • occupancyGrid[out] the message to be populated.

static bool fromCostmap(const nav2_msgs::msg::Costmap &costmap, const std::string &layer, grid_map::GridMap &gridMap)

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

Parameters:
  • Costmap[in] the occupancy grid to be converted.

  • layer[in] the layer to which the costmap will be converted.

  • gridMap[out] the grid map to be populated.

Returns:

true if successful.

static void toCostmap(const grid_map::GridMap &gridMap, const std::string &layer, float dataMin, float dataMax, nav2_msgs::msg::Costmap &costmap)

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

Parameters:
  • gridMap[in] the grid map object.

  • layer[in] the layer that is transformed to the occupancy cell data.

  • dataMin[in] the minimum value of the grid map data (used to normalize the cell data in [min, max]).

  • dataMax[in] the maximum value of the grid map data (used to normalize the cell data in [min, max]).

  • Costmap[out] the message to be populated.

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

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:
  • gridMap[in] the grid map object.

  • layer[in] the layer that is transformed as grid cells.

  • lowerThreshold[in] the lower threshold.

  • upperThreshold[in] the upper threshold.

  • gridCells[out] the message to be populated.

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

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:
  • image[in] the image.

  • resolution[in] the desired resolution of the grid map [m/cell].

  • gridMap[out] the grid map to be initialized.

Param :

static bool addLayerFromImage(const sensor_msgs::msg::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)

Adds a layer with data from image.

Parameters:
  • image[in] the image to be added. If it is a color image (bgr or bgra encoding), it will be transformed in a grayscale image.

  • layer[in] the layer that is filled with the image data.

  • gridMap[out] the grid map to be populated.

Param :

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

Adds a color layer with data from an image.

Parameters:
  • image[in] the image to be added.

  • layer[in] the layer that is filled with the image.

  • gridMap[out] the grid map to be populated.

Returns:

true if successful, false otherwise.

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

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:
  • grid[in] map to be added.

  • layer[in] the layer that is converted to the image.

  • encoding[in] the desired encoding of the image.

  • image[out] the message to be populated.

Returns:

true if successful, false otherwise.

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

Creates an image message from a grid map layer.

Parameters:
  • grid[in] map to be added.

  • layer[in] the layer that is converted to the image.

  • encoding[in] the desired encoding of the image.

  • lowerValue[in] the value of the layer corresponding to black image pixels.

  • upperValue[in] the value of the layer corresponding to white image pixels.

  • image[out] the message to be populated.

Returns:

true if successful, false otherwise.

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

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:
  • grid[in] map to be added.

  • layer[in] the layer that is converted to the image.

  • encoding[in] the desired encoding of the image.

  • cvImage[out] the to be populated.

Returns:

true if successful, false otherwise.

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)

Creates a cv image from a grid map layer.

Parameters:
  • grid[in] map to be added.

  • layer[in] the layer that is converted to the image.

  • encoding[in] the desired encoding of the image.

  • lowerValue[in] the value of the layer corresponding to black image pixels.

  • upperValue[in] the value of the layer corresponding to white image pixels.

  • cvImage[out] to be populated.

Returns:

true if successful, false otherwise.

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

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:
  • gridMap[in] the grid map object to be saved in the ROS bag.

  • pathToBag[in] the path to the ROS bag file.

  • topic[in] the name of the topic in the ROS bag.

Returns:

true if successful, false otherwise.

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

Loads a GridMap from a ROS bag.

Parameters:
  • pathToBag[in] the path to the ROS bag file.

  • topic[in] the topic name of the grid map in the ROS bag.

  • gridMap[out] the grid map object to be initialized.

Returns:

true if successful, false otherwise.