00001
00002
00003
00004
00005
00006
00007
00008
00009 #pragma once
00010
00011 #include <grid_map_core/grid_map_core.hpp>
00012 #include <grid_map_msgs/GridMap.h>
00013
00014
00015 #include <vector>
00016 #include <unordered_map>
00017
00018
00019 #include <Eigen/Core>
00020
00021
00022 #include <ros/ros.h>
00023 #include <sensor_msgs/PointCloud2.h>
00024 #include <sensor_msgs/Image.h>
00025 #include <sensor_msgs/image_encodings.h>
00026 #include <nav_msgs/OccupancyGrid.h>
00027 #include <nav_msgs/GridCells.h>
00028 #include <cv_bridge/cv_bridge.h>
00029
00030 namespace grid_map {
00031
00035 class GridMapRosConverter
00036 {
00037 public:
00041 GridMapRosConverter();
00042
00046 virtual ~GridMapRosConverter();
00047
00054 static bool fromMessage(const grid_map_msgs::GridMap& message, grid_map::GridMap& gridMap);
00055
00061 static void toMessage(const grid_map::GridMap& gridMap, grid_map_msgs::GridMap& message);
00062
00069 static void toMessage(const grid_map::GridMap& gridMap, const std::vector<std::string>& layers,
00070 grid_map_msgs::GridMap& message);
00071
00080 static void toPointCloud(const grid_map::GridMap& gridMap,
00081 const std::string& pointLayer,
00082 sensor_msgs::PointCloud2& pointCloud);
00083
00093 static void toPointCloud(const grid_map::GridMap& gridMap,
00094 const std::vector<std::string>& layers,
00095 const std::string& pointLayer,
00096 sensor_msgs::PointCloud2& pointCloud);
00097
00105 static bool fromOccupancyGrid(const nav_msgs::OccupancyGrid& occupancyGrid,
00106 const std::string& layer, grid_map::GridMap& gridMap);
00107
00117 static void toOccupancyGrid(const grid_map::GridMap& gridMap, const std::string& layer,
00118 float dataMin, float dataMax, nav_msgs::OccupancyGrid& occupancyGrid);
00119
00130 static void toGridCells(const grid_map::GridMap& gridMap, const std::string& layer,
00131 float lowerThreshold, float upperThreshold,
00132 nav_msgs::GridCells& gridCells);
00133
00143 static bool initializeFromImage(const sensor_msgs::Image& image, const double resolution,
00144 grid_map::GridMap& gridMap,
00145 const grid_map::Position& position = grid_map::Position::Zero());
00146
00159 static bool addLayerFromImage(const sensor_msgs::Image& image, const std::string& layer,
00160 grid_map::GridMap& gridMap, const float lowerValue = 0.0,
00161 const float upperValue = 1.0, const double alphaThreshold = 0.5);
00162
00170 static bool addColorLayerFromImage(const sensor_msgs::Image& image, const std::string& layer,
00171 grid_map::GridMap& gridMap);
00172
00183 static bool toImage(const grid_map::GridMap& gridMap, const std::string& layer,
00184 const std::string encoding, sensor_msgs::Image& image);
00185
00196 static bool toImage(const grid_map::GridMap& gridMap, const std::string& layer,
00197 const std::string encoding, const float lowerValue, const float upperValue,
00198 sensor_msgs::Image& image);
00199
00210 static bool toCvImage(const grid_map::GridMap& gridMap, const std::string& layer,
00211 const std::string encoding, cv_bridge::CvImage& cvImage);
00212
00223 static bool toCvImage(const grid_map::GridMap& gridMap, const std::string& layer,
00224 const std::string encoding, const float lowerValue,
00225 const float upperValue, cv_bridge::CvImage& cvImage);
00226
00237 static bool saveToBag(const grid_map::GridMap& gridMap, const std::string& pathToBag,
00238 const std::string& topic);
00239
00247 static bool loadFromBag(const std::string& pathToBag, const std::string& topic,
00248 grid_map::GridMap& gridMap);
00249
00250 };
00251
00252 }