26 : nh_(nh), map_name_(map_name), received_map_(false)
42 slam_toolbox_msgs::SaveMap::Request& req,
43 slam_toolbox_msgs::SaveMap::Response& resp)
48 ROS_WARN(
"Map Saver: Cannot save map, no map yet received on topic %s.",
53 const std::string name = req.name.data;
56 ROS_INFO(
"SlamToolbox: Saving map as %s.", name.c_str());
57 int rc = system((
"rosrun map_server map_saver -f " + name).c_str());
61 ROS_INFO(
"SlamToolbox: Saving map in current directory.");
62 int rc = system(
"rosrun map_server map_saver");
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
MapSaver(ros::NodeHandle &nh, const std::string &service_name)
void mapCallback(const nav_msgs::OccupancyGrid &msg)
ros::ServiceServer server_
bool saveMapCallback(slam_toolbox_msgs::SaveMap::Request &req, slam_toolbox_msgs::SaveMap::Response &resp)