Program Listing for File GridMapRosConverter.hpp
↰ Return to documentation for file (include/grid_map_ros/GridMapRosConverter.hpp
)
/*
* GridMapRosConverter.hpp
*
* Created on: Jul 14, 2014
* Author: Péter Fankhauser
* Institute: ETH Zurich, ANYbotics
*/
#ifndef GRID_MAP_ROS__GRIDMAPROSCONVERTER_HPP_
#define GRID_MAP_ROS__GRIDMAPROSCONVERTER_HPP_
#include <grid_map_core/grid_map_core.hpp>
#include <grid_map_msgs/msg/grid_map.hpp>
// Eigen
#include <Eigen/Core>
// ROS
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/image_encodings.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/grid_cells.hpp>
#include <nav2_msgs/msg/costmap.hpp>
#include <cv_bridge/cv_bridge.hpp>
// STL
#include <vector>
#include <unordered_map>
#include <string>
#include <memory>
namespace grid_map
{
class GridMapRosConverter
{
public:
GridMapRosConverter();
virtual ~GridMapRosConverter();
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);
static bool fromMessage(const grid_map_msgs::msg::GridMap & message, grid_map::GridMap & gridMap);
static std::unique_ptr<grid_map_msgs::msg::GridMap> toMessage(
const grid_map::GridMap & gridMap);
static std::unique_ptr<grid_map_msgs::msg::GridMap> toMessage(
const grid_map::GridMap & gridMap, const std::vector<std::string> & layers);
static void toPointCloud(
const grid_map::GridMap & gridMap,
const std::string & pointLayer,
sensor_msgs::msg::PointCloud2 & pointCloud);
static void toPointCloud(
const grid_map::GridMap & gridMap,
const std::vector<std::string> & layers,
const std::string & pointLayer,
sensor_msgs::msg::PointCloud2 & pointCloud);
static bool fromOccupancyGrid(
const nav_msgs::msg::OccupancyGrid & occupancyGrid,
const std::string & layer, grid_map::GridMap & gridMap);
static void toOccupancyGrid(
const grid_map::GridMap & gridMap, const std::string & layer,
float dataMin, float dataMax, nav_msgs::msg::OccupancyGrid & occupancyGrid);
static bool fromCostmap(
const nav2_msgs::msg::Costmap & costmap,
const std::string & layer, grid_map::GridMap & gridMap);
static void toCostmap(
const grid_map::GridMap & gridMap, const std::string & layer,
float dataMin, float dataMax, nav2_msgs::msg::Costmap & costmap);
static void toGridCells(
const grid_map::GridMap & gridMap, const std::string & layer,
float lowerThreshold, float upperThreshold,
nav_msgs::msg::GridCells & gridCells);
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());
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);
static bool addColorLayerFromImage(
const sensor_msgs::msg::Image & image, const std::string & layer,
grid_map::GridMap & gridMap);
static bool toImage(
const grid_map::GridMap & gridMap, const std::string & layer,
const std::string encoding, sensor_msgs::msg::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::msg::Image & image);
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 bool saveToBag(
const grid_map::GridMap & gridMap, const std::string & pathToBag,
const std::string & topic);
static bool loadFromBag(
const std::string & pathToBag, const std::string & topic,
grid_map::GridMap & gridMap);
};
} // namespace grid_map
#endif // GRID_MAP_ROS__GRIDMAPROSCONVERTER_HPP_