21 #include "nav2_map_server/map_mode.hpp"
22 #include "nav2_map_server/map_saver.hpp"
24 #include "rclcpp/rclcpp.hpp"
26 using namespace nav2_map_server;
28 const char * USAGE_STRING{
30 " map_saver_cli [arguments] [--ros-args ROS remapping args]\n"
36 " --occ <threshold_occupied>\n"
37 " --free <threshold_free>\n"
38 " --fmt <image_format>\n"
39 " --mode trinary(default)/scale/raw\n"
41 "NOTE: --ros-args should be passed at the end of command line"};
46 COMMAND_MAP_FILE_NAME,
48 COMMAND_OCCUPIED_THRESH,
56 COMMAND_TYPE command_type;
69 ARGUMENTS_STATUS parse_arguments(
70 const rclcpp::Logger & logger,
int argc,
char ** argv,
74 {
"-t", COMMAND_MAP_TOPIC},
75 {
"-f", COMMAND_MAP_FILE_NAME},
76 {
"--occ", COMMAND_OCCUPIED_THRESH},
77 {
"--free", COMMAND_FREE_THRESH},
78 {
"--mode", COMMAND_MODE},
79 {
"--fmt", COMMAND_IMAGE_FORMAT},
82 std::vector<std::string> arguments(argv + 1, argv + argc);
83 std::vector<rclcpp::Parameter> params_from_args;
86 size_t cmd_size =
sizeof(commands) /
sizeof(commands[0]);
88 for (
auto it = arguments.begin(); it != arguments.end(); it++) {
89 if (*it ==
"-h" || *it ==
"--help") {
90 std::cout << USAGE_STRING << std::endl;
93 if (*it ==
"--ros-args") {
96 for (i = 0; i < cmd_size; i++) {
97 if (commands[i].cmd == *it) {
98 if ((it + 1) == arguments.end()) {
99 RCLCPP_ERROR(logger,
"Wrong argument: %s should be followed by a value.", it->c_str());
100 return ARGUMENTS_INVALID;
103 switch (commands[i].command_type) {
104 case COMMAND_MAP_TOPIC:
107 case COMMAND_MAP_FILE_NAME:
108 save_parameters.map_file_name = *it;
110 case COMMAND_FREE_THRESH:
111 save_parameters.free_thresh = atof(it->c_str());
113 case COMMAND_OCCUPIED_THRESH:
114 save_parameters.occupied_thresh = atof(it->c_str());
116 case COMMAND_IMAGE_FORMAT:
117 save_parameters.image_format = *it;
121 save_parameters.mode = map_mode_from_string(*it);
122 }
catch (std::invalid_argument &) {
123 save_parameters.mode = MapMode::Trinary;
126 "Map mode parameter not recognized: %s, using default value (trinary)",
135 RCLCPP_ERROR(logger,
"Wrong argument: %s", it->c_str());
136 return ARGUMENTS_INVALID;
140 return ARGUMENTS_VALID;
143 int main(
int argc,
char ** argv)
146 rclcpp::init(argc, argv);
147 auto logger = rclcpp::get_logger(
"map_saver_cli");
151 std::string map_topic =
"map";
152 switch (parse_arguments(logger, argc, argv, map_topic, save_parameters)) {
153 case ARGUMENTS_INVALID:
159 case ARGUMENTS_VALID:
166 auto map_saver = std::make_shared<nav2_map_server::MapSaver>();
167 map_saver->on_configure(rclcpp_lifecycle::State());
168 if (map_saver->saveMapTopicToFile(map_topic, save_parameters)) {
173 }
catch (std::exception & e) {
174 RCLCPP_ERROR(logger,
"Unexpected problem appear: %s", e.what());