Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
map_io.cpp
1 /* Copyright 2019 Rover Robotics
2  * Copyright 2010 Brian Gerkey
3  * Copyright (c) 2008, Willow Garage, Inc.
4  *
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * * Neither the name of the <ORGANIZATION> nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #include "nav2_map_server/map_io.hpp"
33 
34 #ifndef _WIN32
35 #include <libgen.h>
36 #endif
37 
38 #include <Eigen/Dense>
39 
40 #include <iostream>
41 #include <string>
42 #include <vector>
43 #include <fstream>
44 #include <stdexcept>
45 #include <cstdlib>
46 
47 #include "Magick++.h"
48 #include "nav2_util/geometry_utils.hpp"
49 
50 #include "yaml-cpp/yaml.h"
51 #include "tf2/LinearMath/Matrix3x3.h"
52 #include "tf2/LinearMath/Quaternion.h"
53 #include "nav2_util/occ_grid_values.hpp"
54 
55 #ifdef _WIN32
56 // https://github.com/rtv/Stage/blob/master/replace/dirname.c
57 static
58 char * dirname(char * path)
59 {
60  static const char dot[] = ".";
61  char * last_slash;
62 
63  if (path == NULL) {
64  return path;
65  }
66 
67  /* Replace all "\" with "/" */
68  char * c = path;
69  while (*c != '\0') {
70  if (*c == '\\') {*c = '/';}
71  ++c;
72  }
73 
74  /* Find last '/'. */
75  last_slash = path != NULL ? strrchr(path, '/') : NULL;
76 
77  if (last_slash != NULL && last_slash == path) {
78  /* The last slash is the first character in the string. We have to
79  return "/". */
80  ++last_slash;
81  } else if (last_slash != NULL && last_slash[1] == '\0') {
82  /* The '/' is the last character, we have to look further. */
83  last_slash = reinterpret_cast<char *>(memchr(path, last_slash - path, '/'));
84  }
85 
86  if (last_slash != NULL) {
87  /* Terminate the path. */
88  last_slash[0] = '\0';
89  } else {
90  /* This assignment is ill-designed but the XPG specs require to
91  return a string containing "." in any case no directory part is
92  found and so a static and constant string is required. */
93  path = reinterpret_cast<char *>(dot);
94  }
95 
96  return path;
97 }
98 #endif
99 
100 namespace nav2_map_server
101 {
102 using nav2_util::geometry_utils::orientationAroundZAxis;
103 
104 // === Map input part ===
105 
110 template<typename T>
111 T yaml_get_value(const YAML::Node & node, const std::string & key)
112 {
113  try {
114  return node[key].as<T>();
115  } catch (YAML::Exception & e) {
116  std::stringstream ss;
117  ss << "Failed to parse YAML tag '" << key << "' for reason: " << e.msg;
118  throw YAML::Exception(e.mark, ss.str());
119  }
120 }
121 
122 std::string get_home_dir()
123 {
124  if (const char * home_dir = std::getenv("HOME")) {
125  return std::string{home_dir};
126  }
127  return std::string{};
128 }
129 
130 std::string expand_user_home_dir_if_needed(
131  std::string yaml_filename,
132  std::string home_variable_value)
133 {
134  if (yaml_filename.size() < 2 || !(yaml_filename[0] == '~' && yaml_filename[1] == '/')) {
135  return yaml_filename;
136  }
137  if (home_variable_value.empty()) {
138  RCLCPP_INFO_STREAM(
139  rclcpp::get_logger(
140  "map_io"), "Map yaml file name starts with '~/' but no HOME variable set. \n"
141  << "[INFO] [map_io] User home dir will be not expanded \n");
142  return yaml_filename;
143  }
144  const std::string prefix{home_variable_value};
145  return yaml_filename.replace(0, 1, prefix);
146 }
147 
148 LoadParameters loadMapYaml(const std::string & yaml_filename)
149 {
150  YAML::Node doc = YAML::LoadFile(expand_user_home_dir_if_needed(yaml_filename, get_home_dir()));
151  LoadParameters load_parameters;
152 
153  auto image_file_name = yaml_get_value<std::string>(doc, "image");
154  if (image_file_name.empty()) {
155  throw YAML::Exception(doc["image"].Mark(), "The image tag was empty.");
156  }
157  if (image_file_name[0] != '/') {
158  // dirname takes a mutable char *, so we copy into a vector
159  std::vector<char> fname_copy(yaml_filename.begin(), yaml_filename.end());
160  fname_copy.push_back('\0');
161  image_file_name = std::string(dirname(fname_copy.data())) + '/' + image_file_name;
162  }
163  load_parameters.image_file_name = image_file_name;
164 
165  load_parameters.resolution = yaml_get_value<double>(doc, "resolution");
166  load_parameters.origin = yaml_get_value<std::vector<double>>(doc, "origin");
167  if (load_parameters.origin.size() != 3) {
168  throw YAML::Exception(
169  doc["origin"].Mark(), "value of the 'origin' tag should have 3 elements, not " +
170  std::to_string(load_parameters.origin.size()));
171  }
172 
173  load_parameters.free_thresh = yaml_get_value<double>(doc, "free_thresh");
174  load_parameters.occupied_thresh = yaml_get_value<double>(doc, "occupied_thresh");
175 
176  auto map_mode_node = doc["mode"];
177  if (!map_mode_node.IsDefined()) {
178  load_parameters.mode = MapMode::Trinary;
179  } else {
180  load_parameters.mode = map_mode_from_string(map_mode_node.as<std::string>());
181  }
182 
183  try {
184  load_parameters.negate = yaml_get_value<int>(doc, "negate");
185  } catch (YAML::Exception &) {
186  load_parameters.negate = yaml_get_value<bool>(doc, "negate");
187  }
188 
189  RCLCPP_INFO_STREAM(rclcpp::get_logger("map_io"), "resolution: " << load_parameters.resolution);
190  RCLCPP_INFO_STREAM(rclcpp::get_logger("map_io"), "origin[0]: " << load_parameters.origin[0]);
191  RCLCPP_INFO_STREAM(rclcpp::get_logger("map_io"), "origin[1]: " << load_parameters.origin[1]);
192  RCLCPP_INFO_STREAM(rclcpp::get_logger("map_io"), "origin[2]: " << load_parameters.origin[2]);
193  RCLCPP_INFO_STREAM(rclcpp::get_logger("map_io"), "free_thresh: " << load_parameters.free_thresh);
194  RCLCPP_INFO_STREAM(
195  rclcpp::get_logger(
196  "map_io"), "occupied_thresh: " << load_parameters.occupied_thresh);
197  RCLCPP_INFO_STREAM(
198  rclcpp::get_logger("map_io"),
199  "mode: " << map_mode_to_string(load_parameters.mode));
200  RCLCPP_INFO_STREAM(rclcpp::get_logger("map_io"), "negate: " << load_parameters.negate);
201 
202  return load_parameters;
203 }
204 
205 void loadMapFromFile(
206  const LoadParameters & load_parameters,
207  nav_msgs::msg::OccupancyGrid & map)
208 {
209  Magick::InitializeMagick(nullptr);
210  nav_msgs::msg::OccupancyGrid msg;
211 
212  RCLCPP_INFO_STREAM(
213  rclcpp::get_logger("map_io"), "Loading image_file: " <<
214  load_parameters.image_file_name);
215  Magick::Image img(load_parameters.image_file_name);
216 
217  // Copy the image data into the map structure
218  msg.info.width = img.size().width();
219  msg.info.height = img.size().height();
220 
221  msg.info.resolution = load_parameters.resolution;
222  msg.info.origin.position.x = load_parameters.origin[0];
223  msg.info.origin.position.y = load_parameters.origin[1];
224  msg.info.origin.position.z = 0.0;
225  msg.info.origin.orientation = orientationAroundZAxis(load_parameters.origin[2]);
226 
227  // Allocate space to hold the data
228  msg.data.resize(msg.info.width * msg.info.height);
229 
230  // Convert the image to grayscale
231  Magick::Image gray = img;
232  gray.type(Magick::GrayscaleType);
233 
234  // Prepare grayscale matrix from image
235  size_t width = gray.columns();
236  size_t height = gray.rows();
237 
238  std::vector<uint8_t> buffer(width * height);
239  gray.write(0, 0, width, height, "I", Magick::CharPixel, buffer.data());
240 
241  // Map the grayscale buffer to an Eigen matrix (row-major layout)
242  Eigen::Map<Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>>
243  gray_matrix(buffer.data(), height, width);
244 
245  bool has_alpha = img.matte();
246 
247  // Handle different map modes with if else condition
248  // Trinary and Scale modes are handled together
249  // because they share a lot of code
250  // Raw mode is handled separately in else if block
251  Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> result(height, width);
252 
253  if (load_parameters.mode == MapMode::Trinary || load_parameters.mode == MapMode::Scale) {
254  // Convert grayscale to float in range [0.0, 1.0]
255  Eigen::Matrix<float, Eigen::Dynamic, Eigen::Dynamic,
256  Eigen::RowMajor> normalized = gray_matrix.cast<float>() / 255.0f;
257 
258  // Negate the image if specified (e.g. for black=occupied vs. white=occupied convention)
259  if (!load_parameters.negate) {
260  normalized = (1.0f - normalized.array()).matrix();
261  }
262 
263  // Compute binary occupancy masks
264  Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> occupied =
265  (normalized.array() >= load_parameters.occupied_thresh).cast<uint8_t>();
266 
267  Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> free =
268  (normalized.array() <= load_parameters.free_thresh).cast<uint8_t>();
269 
270  // Initialize occupancy grid with UNKNOWN values (-1)
271  result.setConstant(nav2_util::OCC_GRID_UNKNOWN);
272 
273  // Apply occupied and free cell updates
274  result = (occupied.array() > 0).select(nav2_util::OCC_GRID_OCCUPIED, result);
275  result = (free.array() > 0).select(nav2_util::OCC_GRID_FREE, result);
276 
277  // Handle intermediate (gray) values if in Scale mode
278  if (load_parameters.mode == MapMode::Scale) {
279  // Create in-between mask
280  auto in_between_mask = (normalized.array() > load_parameters.free_thresh) &&
281  (normalized.array() < load_parameters.occupied_thresh);
282 
283  if (in_between_mask.any()) {
284  // Scale in-between values to [0,100] range
285  Eigen::ArrayXXf scaled_float = ((normalized.array() - load_parameters.free_thresh) /
286  (load_parameters.occupied_thresh - load_parameters.free_thresh)) * 100.0f;
287 
288  // Round and cast to int8_t
289  Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> scaled_int =
290  scaled_float.array().round().cast<int8_t>();
291 
292  result = in_between_mask.select(scaled_int, result);
293  }
294  }
295 
296  // Apply alpha transparency mask: mark transparent cells as UNKNOWN
297  if (has_alpha) {
298  // Allocate buffer only once and map directly to Eigen without extra copy
299  std::vector<uint8_t> alpha_buf(width * height);
300  img.write(0, 0, width, height, "A", Magick::CharPixel, alpha_buf.data());
301 
302  // Map alpha buffer as Eigen::Array for efficient elementwise ops
303  Eigen::Map<Eigen::Array<uint8_t, Eigen::Dynamic, Eigen::Dynamic,
304  Eigen::RowMajor>> alpha_array(
305  alpha_buf.data(), height, width);
306 
307  // Apply mask directly with Eigen::select
308  result = (alpha_array < 255).select(nav2_util::OCC_GRID_UNKNOWN, result);
309  }
310 
311  } else if (load_parameters.mode == MapMode::Raw) {
312  // Raw mode: interpret raw image pixel values directly as occupancy values
313  result = gray_matrix.cast<int8_t>();
314 
315  // Clamp out-of-bound values (outside [-1, 100]) to UNKNOWN (-1)
316  auto out_of_bounds = (result.array() < nav2_util::OCC_GRID_FREE) ||
317  (result.array() > nav2_util::OCC_GRID_OCCUPIED);
318 
319  result = out_of_bounds.select(nav2_util::OCC_GRID_UNKNOWN, result);
320 
321  } else {
322  // If the map mode is not recognized, throw an error
323  throw std::runtime_error("Invalid map mode");
324  }
325 
326  // Flip image vertically (as ROS expects origin at bottom-left)
327  Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic,
328  Eigen::RowMajor> flipped = result.colwise().reverse();
329  std::memcpy(msg.data.data(), flipped.data(), width * height);
330 
331  // Since loadMapFromFile() does not belong to any node, publishing in a system time.
332  rclcpp::Clock clock(RCL_SYSTEM_TIME);
333  msg.info.map_load_time = clock.now();
334  msg.header.frame_id = "map";
335  msg.header.stamp = clock.now();
336 
337  RCLCPP_INFO_STREAM(
338  rclcpp::get_logger(
339  "map_io"), "Read map " << load_parameters.image_file_name
340  << ": " << msg.info.width << " X " << msg.info.height << " map @ "
341  << msg.info.resolution << " m/cell");
342 
343  map = msg;
344 }
345 
346 LOAD_MAP_STATUS loadMapFromYaml(
347  const std::string & yaml_file,
348  nav_msgs::msg::OccupancyGrid & map)
349 {
350  if (yaml_file.empty()) {
351  RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_io"), "YAML file name is empty, can't load!");
352  return MAP_DOES_NOT_EXIST;
353  }
354  RCLCPP_INFO_STREAM(rclcpp::get_logger("map_io"), "Loading yaml file: " << yaml_file);
355  LoadParameters load_parameters;
356  try {
357  load_parameters = loadMapYaml(yaml_file);
358  } catch (YAML::Exception & e) {
359  RCLCPP_ERROR_STREAM(
360  rclcpp::get_logger(
361  "map_io"), "Failed processing YAML file " << yaml_file << " at position (" <<
362  e.mark.line << ":" << e.mark.column << ") for reason: " << e.what());
363  return INVALID_MAP_METADATA;
364  } catch (std::exception & e) {
365  RCLCPP_ERROR_STREAM(
366  rclcpp::get_logger("map_io"), "Failed to parse map YAML loaded from file " << yaml_file <<
367  " for reason: " << e.what());
368  return INVALID_MAP_METADATA;
369  }
370  try {
371  loadMapFromFile(load_parameters, map);
372  } catch (std::exception & e) {
373  RCLCPP_ERROR_STREAM(
374  rclcpp::get_logger(
375  "map_io"), "Failed to load image file " << load_parameters.image_file_name <<
376  " for reason: " << e.what());
377  return INVALID_MAP_DATA;
378  }
379 
380  return LOAD_MAP_SUCCESS;
381 }
382 
383 // === Map output part ===
384 
391 void checkSaveParameters(SaveParameters & save_parameters)
392 {
393  // Magick must me initialized before any activity with images
394  Magick::InitializeMagick(nullptr);
395 
396  // Checking map file name
397  if (save_parameters.map_file_name == "") {
398  rclcpp::Clock clock(RCL_SYSTEM_TIME);
399  save_parameters.map_file_name = "map_" +
400  std::to_string(static_cast<int>(clock.now().seconds()));
401  RCLCPP_WARN_STREAM(
402  rclcpp::get_logger("map_io"), "Map file unspecified. Map will be saved to " <<
403  save_parameters.map_file_name << " file");
404  }
405 
406  // Checking thresholds
407  if (save_parameters.occupied_thresh == 0.0) {
408  save_parameters.occupied_thresh = 0.65;
409  RCLCPP_WARN_STREAM(
410  rclcpp::get_logger(
411  "map_io"), "Occupied threshold unspecified. Setting it to default value: " <<
412  save_parameters.occupied_thresh);
413  }
414  if (save_parameters.free_thresh == 0.0) {
415  save_parameters.free_thresh = 0.25;
416  RCLCPP_WARN_STREAM(
417  rclcpp::get_logger("map_io"), "Free threshold unspecified. Setting it to default value: " <<
418  save_parameters.free_thresh);
419  }
420  if (1.0 < save_parameters.occupied_thresh) {
421  RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_io"), "Threshold_occupied must be 1.0 or less");
422  throw std::runtime_error("Incorrect thresholds");
423  }
424  if (save_parameters.free_thresh < 0.0) {
425  RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_io"), "Free threshold must be 0.0 or greater");
426  throw std::runtime_error("Incorrect thresholds");
427  }
428  if (save_parameters.occupied_thresh <= save_parameters.free_thresh) {
429  RCLCPP_ERROR_STREAM(
430  rclcpp::get_logger(
431  "map_io"), "Threshold_free must be smaller than threshold_occupied");
432  throw std::runtime_error("Incorrect thresholds");
433  }
434 
435  // Checking image format
436  if (save_parameters.image_format == "") {
437  save_parameters.image_format = save_parameters.mode == MapMode::Scale ? "png" : "pgm";
438  RCLCPP_WARN_STREAM(
439  rclcpp::get_logger("map_io"), "Image format unspecified. Setting it to: " <<
440  save_parameters.image_format);
441  }
442 
443  std::transform(
444  save_parameters.image_format.begin(),
445  save_parameters.image_format.end(),
446  save_parameters.image_format.begin(),
447  [](unsigned char c) {return std::tolower(c);});
448 
449  const std::vector<std::string> BLESSED_FORMATS{"bmp", "pgm", "png"};
450  if (
451  std::find(BLESSED_FORMATS.begin(), BLESSED_FORMATS.end(), save_parameters.image_format) ==
452  BLESSED_FORMATS.end())
453  {
454  std::stringstream ss;
455  bool first = true;
456  for (auto & format_name : BLESSED_FORMATS) {
457  if (!first) {
458  ss << ", ";
459  }
460  ss << "'" << format_name << "'";
461  first = false;
462  }
463  RCLCPP_WARN_STREAM(
464  rclcpp::get_logger("map_io"), "Requested image format '" << save_parameters.image_format <<
465  "' is not one of the recommended formats: " << ss.str());
466  }
467  const std::string FALLBACK_FORMAT = "png";
468 
469  try {
470  Magick::CoderInfo info(save_parameters.image_format);
471  if (!info.isWritable()) {
472  RCLCPP_WARN_STREAM(
473  rclcpp::get_logger("map_io"), "Format '" << save_parameters.image_format <<
474  "' is not writable. Using '" << FALLBACK_FORMAT << "' instead");
475  save_parameters.image_format = FALLBACK_FORMAT;
476  }
477  } catch (Magick::ErrorOption & e) {
478  RCLCPP_WARN_STREAM(
479  rclcpp::get_logger(
480  "map_io"), "Format '" << save_parameters.image_format << "' is not usable. Using '" <<
481  FALLBACK_FORMAT << "' instead:" << std::endl << e.what());
482  save_parameters.image_format = FALLBACK_FORMAT;
483  }
484 
485  // Checking map mode
486  if (
487  save_parameters.mode == MapMode::Scale &&
488  (save_parameters.image_format == "pgm" ||
489  save_parameters.image_format == "jpg" ||
490  save_parameters.image_format == "jpeg"))
491  {
492  RCLCPP_WARN_STREAM(
493  rclcpp::get_logger("map_io"), "Map mode 'scale' requires transparency, but format '" <<
494  save_parameters.image_format <<
495  "' does not support it. Consider switching image format to 'png'.");
496  }
497 }
498 
505 void tryWriteMapToFile(
506  const nav_msgs::msg::OccupancyGrid & map,
507  const SaveParameters & save_parameters)
508 {
509  RCLCPP_INFO_STREAM(
510  rclcpp::get_logger(
511  "map_io"), "Received a " << map.info.width << " X " << map.info.height << " map @ " <<
512  map.info.resolution << " m/pix");
513 
514  std::string mapdatafile = save_parameters.map_file_name + "." + save_parameters.image_format;
515  {
516  // should never see this color, so the initialization value is just for debugging
517  Magick::Image image({map.info.width, map.info.height}, "red");
518 
519  // In scale mode, we need the alpha (matte) channel. Else, we don't.
520  // NOTE: GraphicsMagick seems to have trouble loading the alpha channel when saved with
521  // Magick::GreyscaleMatte, so we use TrueColorMatte instead.
522  image.type(
523  save_parameters.mode == MapMode::Scale ?
524  Magick::TrueColorMatteType : Magick::GrayscaleType);
525 
526  // Since we only need to support 100 different pixel levels, 8 bits is fine
527  image.depth(8);
528 
529  int free_thresh_int = std::rint(save_parameters.free_thresh * 100.0);
530  int occupied_thresh_int = std::rint(save_parameters.occupied_thresh * 100.0);
531 
532  for (size_t y = 0; y < map.info.height; y++) {
533  for (size_t x = 0; x < map.info.width; x++) {
534  int8_t map_cell = map.data[map.info.width * (map.info.height - y - 1) + x];
535 
536  Magick::Color pixel;
537 
538  switch (save_parameters.mode) {
539  case MapMode::Trinary:
540  if (map_cell < 0 || 100 < map_cell) {
541  pixel = Magick::ColorGray(205 / 255.0);
542  } else if (map_cell <= free_thresh_int) {
543  pixel = Magick::ColorGray(254 / 255.0);
544  } else if (occupied_thresh_int <= map_cell) {
545  pixel = Magick::ColorGray(0 / 255.0);
546  } else {
547  pixel = Magick::ColorGray(205 / 255.0);
548  }
549  break;
550  case MapMode::Scale:
551  if (map_cell < 0 || 100 < map_cell) {
552  pixel = Magick::ColorGray{0.5};
553  pixel.alphaQuantum(TransparentOpacity);
554  } else {
555  pixel = Magick::ColorGray{(100.0 - map_cell) / 100.0};
556  }
557  break;
558  case MapMode::Raw:
559  Magick::Quantum q;
560  if (map_cell < 0 || 100 < map_cell) {
561  q = MaxRGB;
562  } else {
563  q = map_cell / 255.0 * MaxRGB;
564  }
565  pixel = Magick::Color(q, q, q);
566  break;
567  default:
568  RCLCPP_ERROR_STREAM(
569  rclcpp::get_logger(
570  "map_io"), "Map mode should be Trinary, Scale or Raw");
571  throw std::runtime_error("Invalid map mode");
572  }
573  image.pixelColor(x, y, pixel);
574  }
575  }
576 
577  RCLCPP_INFO_STREAM(
578  rclcpp::get_logger("map_io"),
579  "Writing map occupancy data to " << mapdatafile);
580  image.write(mapdatafile);
581  }
582 
583  std::string mapmetadatafile = save_parameters.map_file_name + ".yaml";
584  {
585  std::ofstream yaml(mapmetadatafile);
586 
587  geometry_msgs::msg::Quaternion orientation = map.info.origin.orientation;
588  tf2::Matrix3x3 mat(tf2::Quaternion(orientation.x, orientation.y, orientation.z, orientation.w));
589  double yaw, pitch, roll;
590  mat.getEulerYPR(yaw, pitch, roll);
591 
592  const int file_name_index = mapdatafile.find_last_of("/\\");
593  std::string image_name = mapdatafile.substr(file_name_index + 1);
594 
595  YAML::Emitter e;
596  e << YAML::Precision(3);
597  e << YAML::BeginMap;
598  e << YAML::Key << "image" << YAML::Value << image_name;
599  e << YAML::Key << "mode" << YAML::Value << map_mode_to_string(save_parameters.mode);
600  e << YAML::Key << "resolution" << YAML::Value << map.info.resolution;
601  e << YAML::Key << "origin" << YAML::Flow << YAML::BeginSeq << map.info.origin.position.x <<
602  map.info.origin.position.y << yaw << YAML::EndSeq;
603  e << YAML::Key << "negate" << YAML::Value << 0;
604 
605  if (save_parameters.mode == MapMode::Trinary) {
606  // For Trinary mode, the thresholds depend on the pixel values in the saved map,
607  // not on the thresholds used to threshold the map.
608  // As these values are fixed above, the thresholds must also be fixed to separate the
609  // pixel values into occupied, free and unknown.
610  e << YAML::Key << "occupied_thresh" << YAML::Value << 0.65;
611  e << YAML::Key << "free_thresh" << YAML::Value << 0.196;
612  } else {
613  e << YAML::Key << "occupied_thresh" << YAML::Value << save_parameters.occupied_thresh;
614  e << YAML::Key << "free_thresh" << YAML::Value << save_parameters.free_thresh;
615  }
616 
617  if (!e.good()) {
618  RCLCPP_ERROR_STREAM(
619  rclcpp::get_logger("map_io"), "YAML writer failed with an error " << e.GetLastError() <<
620  ". The map metadata may be invalid.");
621  }
622 
623  RCLCPP_INFO_STREAM(rclcpp::get_logger("map_io"), "Writing map metadata to " << mapmetadatafile);
624  std::ofstream(mapmetadatafile) << e.c_str();
625  }
626  RCLCPP_INFO_STREAM(rclcpp::get_logger("map_io"), "Map saved");
627 }
628 
629 bool saveMapToFile(
630  const nav_msgs::msg::OccupancyGrid & map,
631  const SaveParameters & save_parameters)
632 {
633  // Local copy of SaveParameters that might be modified by checkSaveParameters()
634  SaveParameters save_parameters_loc = save_parameters;
635 
636  try {
637  // Checking map parameters for consistency
638  checkSaveParameters(save_parameters_loc);
639 
640  tryWriteMapToFile(map, save_parameters_loc);
641  } catch (std::exception & e) {
642  RCLCPP_ERROR_STREAM(
643  rclcpp::get_logger("map_io"),
644  "Failed to write map for reason: " << e.what());
645  return false;
646  }
647  return true;
648 }
649 
650 } // namespace nav2_map_server