SMACC2
Loading...
Searching...
No Matches
cb_save_slam_map.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#include <angles/angles.h>
22#include <chrono>
23#include <geometry_msgs/msg/twist.hpp>
24#include <memory>
25#include <nav2_msgs/srv/save_map.hpp>
28#include <slam_toolbox/srv/save_map.hpp>
31#include <std_msgs/msg/string.hpp>
32
33namespace cl_nav2z
34{
35using namespace std::chrono_literals;
36
37CbSaveSlamMap::CbSaveSlamMap() : CbServiceCall("/map_saver/save_map", getRequest())
38{
39 // : CbServiceCall("/slam_toolbox/save_map",
40 // getRequest()) {
41
42 // map_name.data = "saved_map";
43 // auto request = getRequest(map_name);
44 // RCLCPP_INFO_STREAM(getLogger(), "Save Slam Map builded");
45}
46
47// void onEntry() override {}
48
50
51std::shared_ptr<nav2_msgs::srv::SaveMap::Request> CbSaveSlamMap::getRequest(
52 /*slam_toolbox::srv::SaveMap_Request_<std::allocator<void> >::_name_type saved_map_name*/)
53{
54 nav2_msgs::srv::SaveMap_Request map_save;
55 std_msgs::msg::String map_name;
56
57 // // map_name.data = "saved_map";
58 // map_save.map_topic = "map";
59 // map_save.map_url = "${workspacesFolder}/maps/saved_map";
60 // map_save.image_format = "png";
61 // map_save.occupied_thresh = 0.65;
62 // map_save.free_thresh = 0.25;
63 // map_save.map_mode = "trinary";
64
65 // // auto request = std::make_shared<slam_toolbox::srv::SaveMap::Request>();
66 // // // request->name = saved_map_name;
67 // // request->name = map_name;
68 // // return request;
69 // auto request = std::make_shared<nav2_msgs::srv::SaveMap::Request>(map_save);
70
71 auto request = std::make_shared<nav2_msgs::srv::SaveMap::Request>();
72 request->map_topic = "map";
73 request->map_url = "/tmp/saved_map";
74 request->image_format = "png";
75 request->occupied_thresh = 0.65;
76 request->free_thresh = 0.25;
77 request->map_mode = "trinary";
78
79 return request;
80}
81} // namespace cl_nav2z
82
83// slam_toolbox::srv::SaveMap_Request_<std::allocator<void> >::_name_type
84
85// std_msgs::msg::String_<std::allocator<void> >
std::shared_ptr< nav2_msgs::srv::SaveMap::Request > getRequest()