GridmapToImageDemo.cpp
Go to the documentation of this file.
1 /*
2  * GridMapToImageDemo.cpp
3  *
4  * Created on: October 19, 2020
5  * Author: Magnus Gärtner
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
10 
12 #include <opencv2/imgcodecs.hpp>
13 
14 namespace grid_map_demos {
15 
17  : nodeHandle_(nodeHandle)
18 {
21  ROS_ERROR("Subscribed to %s", nodeHandle_.resolveName(gridMapTopic_).c_str());
22 }
23 
25 
27 {
28  nodeHandle_.param("grid_map_topic", gridMapTopic_, std::string("/grid_map"));
29  nodeHandle_.param("file", filePath_, std::string("~/.ros/grid_map.png"));
30 }
31 
32 void GridMapToImageDemo::gridMapCallback(const grid_map_msgs::GridMap& msg)
33 {
34  ROS_INFO("Saving map received from: %s to file %s.", nodeHandle_.resolveName(gridMapTopic_).c_str(), filePath_.c_str());
36  cv_bridge::CvImage image;
37  grid_map::GridMapRosConverter::fromMessage(msg, map, {"elevation"});
39  bool success = cv::imwrite(filePath_.c_str(),image.image, {cv::IMWRITE_PNG_STRATEGY_DEFAULT});
40  ROS_INFO("Success writing image: %s", success?"true":"false");
41  ros::shutdown();
42 }
43 
44 } /* namespace */
void readParameters()
Reads and verifies the ROS parameters.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber gridMapSubscriber_
GridMap subscriber.
std::string gridMapTopic_
Name of the grid map topic.
std::string filePath_
Path where to store the image.
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)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::NodeHandle & nodeHandle_
ROS nodehandle.
#define ROS_INFO(...)
std::string resolveName(const std::string &name, bool remap=true) const
void gridMapCallback(const grid_map_msgs::GridMap &msg)
The callback receiving the grid map. It will convert the elevation layer into a png image and save it...
ROSCPP_DECL void shutdown()
static bool toCvImage(const grid_map::GridMap &gridMap, const std::string &layer, const std::string encoding, cv_bridge::CvImage &cvImage)
#define ROS_ERROR(...)
GridMapToImageDemo(ros::NodeHandle &nodeHandle)


grid_map_demos
Author(s): Péter Fankhauser
autogenerated on Wed Jul 5 2023 02:24:01