map_saver.hpp
Go to the documentation of this file.
1 /*
2  * map_saver
3  * Copyright (c) 2019, Samsung Research America
4  *
5  * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
6  * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
7  * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
8  * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
9  *
10  * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
11  * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
12  * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
13  * CONDITIONS.
14  *
15  */
16 
17 /* Author: Steven Macenski */
18 
19 #ifndef SLAM_TOOLBOX_MAP_SAVER_H_
20 #define SLAM_TOOLBOX_MAP_SAVER_H_
21 
22 #include <string>
23 #include "ros/ros.h"
25 
26 namespace map_saver
27 {
28 
29 // a service to save a map with a given name as requested
30 class MapSaver
31 {
32 public:
33  MapSaver(ros::NodeHandle& nh, const std::string& service_name);
34 
35 protected:
36  bool saveMapCallback(slam_toolbox_msgs::SaveMap::Request& req,
37  slam_toolbox_msgs::SaveMap::Response& resp);
38  void mapCallback(const nav_msgs::OccupancyGrid& msg);
39 
40 private:
44  std::string service_name_, map_name_;
46 };
47 
48 } // end namespace
49 
50 #endif //SLAM_TOOLBOX_MAP_SAVER_H_
std::string service_name_
Definition: map_saver.hpp:44
ros::Subscriber sub_
Definition: map_saver.hpp:43
MapSaver(ros::NodeHandle &nh, const std::string &service_name)
Definition: map_saver.cpp:25
std::string map_name_
Definition: map_saver.hpp:44
void mapCallback(const nav_msgs::OccupancyGrid &msg)
Definition: map_saver.cpp:34
ros::ServiceServer server_
Definition: map_saver.hpp:42
bool saveMapCallback(slam_toolbox_msgs::SaveMap::Request &req, slam_toolbox_msgs::SaveMap::Response &resp)
Definition: map_saver.cpp:41
ros::NodeHandle nh_
Definition: map_saver.hpp:41


slam_toolbox
Author(s): Steve Macenski
autogenerated on Mon Feb 28 2022 23:46:49