12 #include <opencv2/imgcodecs.hpp> 17 : nodeHandle_(nodeHandle)
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");
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())
std::string resolveName(const std::string &name, bool remap=true) const
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)
ros::NodeHandle & nodeHandle_
ROS nodehandle.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
virtual ~GridMapToImageDemo()
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)
GridMapToImageDemo(ros::NodeHandle &nodeHandle)