32 #include "nav2_map_server/map_io.hpp"
38 #include <Eigen/Dense>
48 #include "nav2_util/geometry_utils.hpp"
50 #include "yaml-cpp/yaml.h"
52 #include "tf2/LinearMath/Matrix3x3.hpp"
53 #include "tf2/LinearMath/Quaternion.hpp"
54 #include "nav2_util/occ_grid_values.hpp"
59 char * dirname(
char * path)
61 static const char dot[] =
".";
71 if (*c ==
'\\') {*c =
'/';}
76 last_slash = path != NULL ? strrchr(path,
'/') : NULL;
78 if (last_slash != NULL && last_slash == path) {
82 }
else if (last_slash != NULL && last_slash[1] ==
'\0') {
84 last_slash =
reinterpret_cast<char *
>(memchr(path, last_slash - path,
'/'));
87 if (last_slash != NULL) {
94 path =
reinterpret_cast<char *
>(dot);
101 namespace nav2_map_server
103 using nav2_util::geometry_utils::orientationAroundZAxis;
112 T yaml_get_value(
const YAML::Node & node,
const std::string & key)
115 return node[key].as<T>();
116 }
catch (YAML::Exception & e) {
117 std::stringstream ss;
118 ss <<
"Failed to parse YAML tag '" << key <<
"' for reason: " << e.msg;
119 throw YAML::Exception(e.mark, ss.str());
123 std::string get_home_dir()
125 if (
const char * home_dir = std::getenv(
"HOME")) {
126 return std::string{home_dir};
128 return std::string{};
131 std::string expand_user_home_dir_if_needed(
132 std::string yaml_filename,
133 std::string home_variable_value)
135 if (yaml_filename.size() < 2 || !(yaml_filename[0] ==
'~' && yaml_filename[1] ==
'/')) {
136 return yaml_filename;
138 if (home_variable_value.empty()) {
141 "map_io"),
"Map yaml file name starts with '~/' but no HOME variable set. \n"
142 <<
"[INFO] [map_io] User home dir will be not expanded \n");
143 return yaml_filename;
145 const std::string prefix{home_variable_value};
146 return yaml_filename.replace(0, 1, prefix);
149 LoadParameters loadMapYaml(
const std::string & yaml_filename)
151 YAML::Node doc = YAML::LoadFile(expand_user_home_dir_if_needed(yaml_filename, get_home_dir()));
152 LoadParameters load_parameters;
154 auto image_file_name = yaml_get_value<std::string>(doc,
"image");
155 if (image_file_name.empty()) {
156 throw YAML::Exception(doc[
"image"].Mark(),
"The image tag was empty.");
158 if (image_file_name[0] !=
'/') {
160 std::vector<char> fname_copy(yaml_filename.begin(), yaml_filename.end());
161 fname_copy.push_back(
'\0');
162 image_file_name = std::string(dirname(fname_copy.data())) +
'/' + image_file_name;
164 load_parameters.image_file_name = image_file_name;
166 load_parameters.resolution = yaml_get_value<double>(doc,
"resolution");
167 load_parameters.origin = yaml_get_value<std::vector<double>>(doc,
"origin");
168 if (load_parameters.origin.size() != 3) {
169 throw YAML::Exception(
170 doc[
"origin"].Mark(),
"value of the 'origin' tag should have 3 elements, not " +
171 std::to_string(load_parameters.origin.size()));
174 load_parameters.free_thresh = yaml_get_value<double>(doc,
"free_thresh");
175 load_parameters.occupied_thresh = yaml_get_value<double>(doc,
"occupied_thresh");
177 auto map_mode_node = doc[
"mode"];
178 if (!map_mode_node.IsDefined()) {
179 load_parameters.mode = MapMode::Trinary;
181 load_parameters.mode = map_mode_from_string(map_mode_node.as<std::string>());
185 load_parameters.negate = yaml_get_value<int>(doc,
"negate");
186 }
catch (YAML::Exception &) {
187 load_parameters.negate = yaml_get_value<bool>(doc,
"negate");
190 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"resolution: " << load_parameters.resolution);
191 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"origin[0]: " << load_parameters.origin[0]);
192 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"origin[1]: " << load_parameters.origin[1]);
193 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"origin[2]: " << load_parameters.origin[2]);
194 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"free_thresh: " << load_parameters.free_thresh);
197 "map_io"),
"occupied_thresh: " << load_parameters.occupied_thresh);
199 rclcpp::get_logger(
"map_io"),
200 "mode: " << map_mode_to_string(load_parameters.mode));
201 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"negate: " << load_parameters.negate);
203 return load_parameters;
206 void loadMapFromFile(
207 const LoadParameters & load_parameters,
208 nav_msgs::msg::OccupancyGrid & map)
210 Magick::InitializeMagick(
nullptr);
211 nav_msgs::msg::OccupancyGrid msg;
214 rclcpp::get_logger(
"map_io"),
"Loading image_file: " <<
215 load_parameters.image_file_name);
216 Magick::Image img(load_parameters.image_file_name);
219 msg.info.width = img.size().width();
220 msg.info.height = img.size().height();
222 msg.info.resolution = load_parameters.resolution;
223 msg.info.origin.position.x = load_parameters.origin[0];
224 msg.info.origin.position.y = load_parameters.origin[1];
225 msg.info.origin.position.z = 0.0;
226 msg.info.origin.orientation = orientationAroundZAxis(load_parameters.origin[2]);
229 msg.data.resize(msg.info.width * msg.info.height);
232 Magick::Image gray = img;
233 gray.type(Magick::GrayscaleType);
236 size_t width = gray.columns();
237 size_t height = gray.rows();
239 std::vector<uint8_t> buffer(width * height);
240 gray.write(0, 0, width, height,
"I", Magick::CharPixel, buffer.data());
243 Eigen::Map<Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>>
244 gray_matrix(buffer.data(), height, width);
246 bool has_alpha = img.matte();
252 Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> result(height, width);
254 if (load_parameters.mode == MapMode::Trinary || load_parameters.mode == MapMode::Scale) {
256 Eigen::Matrix<float, Eigen::Dynamic, Eigen::Dynamic,
257 Eigen::RowMajor> normalized = gray_matrix.cast<
float>() / 255.0f;
260 if (!load_parameters.negate) {
261 normalized = (1.0f - normalized.array()).matrix();
265 Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> occupied =
266 (normalized.array() >= load_parameters.occupied_thresh).cast<uint8_t>();
268 Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> free =
269 (normalized.array() <= load_parameters.free_thresh).cast<uint8_t>();
272 result.setConstant(nav2_util::OCC_GRID_UNKNOWN);
275 result = (occupied.array() > 0).select(nav2_util::OCC_GRID_OCCUPIED, result);
276 result = (free.array() > 0).select(nav2_util::OCC_GRID_FREE, result);
279 if (load_parameters.mode == MapMode::Scale) {
281 auto in_between_mask = (normalized.array() > load_parameters.free_thresh) &&
282 (normalized.array() < load_parameters.occupied_thresh);
284 if (in_between_mask.any()) {
286 Eigen::ArrayXXf scaled_float = ((normalized.array() - load_parameters.free_thresh) /
287 (load_parameters.occupied_thresh - load_parameters.free_thresh)) * 100.0f;
290 Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> scaled_int =
291 scaled_float.array().round().cast<int8_t>();
293 result = in_between_mask.select(scaled_int, result);
300 std::vector<uint8_t> alpha_buf(width * height);
301 img.write(0, 0, width, height,
"A", Magick::CharPixel, alpha_buf.data());
304 Eigen::Map<Eigen::Array<uint8_t, Eigen::Dynamic, Eigen::Dynamic,
305 Eigen::RowMajor>> alpha_array(
306 alpha_buf.data(), height, width);
309 result = (alpha_array < 255).select(nav2_util::OCC_GRID_UNKNOWN, result);
312 }
else if (load_parameters.mode == MapMode::Raw) {
314 result = gray_matrix.cast<int8_t>();
317 auto out_of_bounds = (result.array() < nav2_util::OCC_GRID_FREE) ||
318 (result.array() > nav2_util::OCC_GRID_OCCUPIED);
320 result = out_of_bounds.select(nav2_util::OCC_GRID_UNKNOWN, result);
324 throw std::runtime_error(
"Invalid map mode");
328 Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic,
329 Eigen::RowMajor> flipped = result.colwise().reverse();
330 std::memcpy(msg.data.data(), flipped.data(), width * height);
333 rclcpp::Clock clock(RCL_SYSTEM_TIME);
334 msg.info.map_load_time = clock.now();
335 msg.header.frame_id =
"map";
336 msg.header.stamp = clock.now();
340 "map_io"),
"Read map " << load_parameters.image_file_name
341 <<
": " << msg.info.width <<
" X " << msg.info.height <<
" map @ "
342 << msg.info.resolution <<
" m/cell");
347 LOAD_MAP_STATUS loadMapFromYaml(
348 const std::string & yaml_file,
349 nav_msgs::msg::OccupancyGrid & map)
351 if (yaml_file.empty()) {
352 RCLCPP_ERROR_STREAM(rclcpp::get_logger(
"map_io"),
"YAML file name is empty, can't load!");
353 return MAP_DOES_NOT_EXIST;
355 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"Loading yaml file: " << yaml_file);
356 LoadParameters load_parameters;
358 load_parameters = loadMapYaml(yaml_file);
359 }
catch (YAML::Exception & e) {
362 "map_io"),
"Failed processing YAML file " << yaml_file <<
" at position (" <<
363 e.mark.line <<
":" << e.mark.column <<
") for reason: " << e.what());
364 return INVALID_MAP_METADATA;
365 }
catch (std::exception & e) {
367 rclcpp::get_logger(
"map_io"),
"Failed to parse map YAML loaded from file " << yaml_file <<
368 " for reason: " << e.what());
369 return INVALID_MAP_METADATA;
372 loadMapFromFile(load_parameters, map);
373 }
catch (std::exception & e) {
376 "map_io"),
"Failed to load image file " << load_parameters.image_file_name <<
377 " for reason: " << e.what());
378 return INVALID_MAP_DATA;
381 return LOAD_MAP_SUCCESS;
392 void checkSaveParameters(SaveParameters & save_parameters)
395 Magick::InitializeMagick(
nullptr);
398 if (save_parameters.map_file_name ==
"") {
399 rclcpp::Clock clock(RCL_SYSTEM_TIME);
400 save_parameters.map_file_name =
"map_" +
401 std::to_string(
static_cast<int>(clock.now().seconds()));
403 rclcpp::get_logger(
"map_io"),
"Map file unspecified. Map will be saved to " <<
404 save_parameters.map_file_name <<
" file");
408 if (save_parameters.occupied_thresh == 0.0) {
409 save_parameters.occupied_thresh = 0.65;
412 "map_io"),
"Occupied threshold unspecified. Setting it to default value: " <<
413 save_parameters.occupied_thresh);
415 if (save_parameters.free_thresh == 0.0) {
416 save_parameters.free_thresh = 0.25;
418 rclcpp::get_logger(
"map_io"),
"Free threshold unspecified. Setting it to default value: " <<
419 save_parameters.free_thresh);
421 if (1.0 < save_parameters.occupied_thresh) {
422 RCLCPP_ERROR_STREAM(rclcpp::get_logger(
"map_io"),
"Threshold_occupied must be 1.0 or less");
423 throw std::runtime_error(
"Incorrect thresholds");
425 if (save_parameters.free_thresh < 0.0) {
426 RCLCPP_ERROR_STREAM(rclcpp::get_logger(
"map_io"),
"Free threshold must be 0.0 or greater");
427 throw std::runtime_error(
"Incorrect thresholds");
429 if (save_parameters.occupied_thresh <= save_parameters.free_thresh) {
432 "map_io"),
"Threshold_free must be smaller than threshold_occupied");
433 throw std::runtime_error(
"Incorrect thresholds");
437 if (save_parameters.image_format ==
"") {
438 save_parameters.image_format = save_parameters.mode == MapMode::Scale ?
"png" :
"pgm";
440 rclcpp::get_logger(
"map_io"),
"Image format unspecified. Setting it to: " <<
441 save_parameters.image_format);
445 save_parameters.image_format.begin(),
446 save_parameters.image_format.end(),
447 save_parameters.image_format.begin(),
448 [](
unsigned char c) {return std::tolower(c);});
450 const std::vector<std::string> BLESSED_FORMATS{
"bmp",
"pgm",
"png"};
452 std::find(BLESSED_FORMATS.begin(), BLESSED_FORMATS.end(), save_parameters.image_format) ==
453 BLESSED_FORMATS.end())
455 std::stringstream ss;
457 for (
auto & format_name : BLESSED_FORMATS) {
461 ss <<
"'" << format_name <<
"'";
465 rclcpp::get_logger(
"map_io"),
"Requested image format '" << save_parameters.image_format <<
466 "' is not one of the recommended formats: " << ss.str());
468 const std::string FALLBACK_FORMAT =
"png";
471 Magick::CoderInfo info(save_parameters.image_format);
472 if (!info.isWritable()) {
474 rclcpp::get_logger(
"map_io"),
"Format '" << save_parameters.image_format <<
475 "' is not writable. Using '" << FALLBACK_FORMAT <<
"' instead");
476 save_parameters.image_format = FALLBACK_FORMAT;
478 }
catch (Magick::ErrorOption & e) {
481 "map_io"),
"Format '" << save_parameters.image_format <<
"' is not usable. Using '" <<
482 FALLBACK_FORMAT <<
"' instead:" << std::endl << e.what());
483 save_parameters.image_format = FALLBACK_FORMAT;
488 save_parameters.mode == MapMode::Scale &&
489 (save_parameters.image_format ==
"pgm" ||
490 save_parameters.image_format ==
"jpg" ||
491 save_parameters.image_format ==
"jpeg"))
494 rclcpp::get_logger(
"map_io"),
"Map mode 'scale' requires transparency, but format '" <<
495 save_parameters.image_format <<
496 "' does not support it. Consider switching image format to 'png'.");
506 void tryWriteMapToFile(
507 const nav_msgs::msg::OccupancyGrid & map,
508 const SaveParameters & save_parameters)
512 "map_io"),
"Received a " << map.info.width <<
" X " << map.info.height <<
" map @ " <<
513 map.info.resolution <<
" m/pix");
515 std::string mapdatafile = save_parameters.map_file_name +
"." + save_parameters.image_format;
518 Magick::Image image({map.info.width, map.info.height},
"red");
524 save_parameters.mode == MapMode::Scale ?
525 Magick::TrueColorMatteType : Magick::GrayscaleType);
530 int free_thresh_int = std::rint(save_parameters.free_thresh * 100.0);
531 int occupied_thresh_int = std::rint(save_parameters.occupied_thresh * 100.0);
533 for (
size_t y = 0; y < map.info.height; y++) {
534 for (
size_t x = 0; x < map.info.width; x++) {
535 int8_t map_cell = map.data[map.info.width * (map.info.height - y - 1) + x];
539 switch (save_parameters.mode) {
540 case MapMode::Trinary:
541 if (map_cell < 0 || 100 < map_cell) {
542 pixel = Magick::ColorGray(205 / 255.0);
543 }
else if (map_cell <= free_thresh_int) {
544 pixel = Magick::ColorGray(254 / 255.0);
545 }
else if (occupied_thresh_int <= map_cell) {
546 pixel = Magick::ColorGray(0 / 255.0);
548 pixel = Magick::ColorGray(205 / 255.0);
552 if (map_cell < 0 || 100 < map_cell) {
553 pixel = Magick::ColorGray{0.5};
554 pixel.alphaQuantum(TransparentOpacity);
556 pixel = Magick::ColorGray{(100.0 - map_cell) / 100.0};
561 if (map_cell < 0 || 100 < map_cell) {
564 q = map_cell / 255.0 * MaxRGB;
566 pixel = Magick::Color(q, q, q);
571 "map_io"),
"Map mode should be Trinary, Scale or Raw");
572 throw std::runtime_error(
"Invalid map mode");
574 image.pixelColor(x, y, pixel);
579 rclcpp::get_logger(
"map_io"),
580 "Writing map occupancy data to " << mapdatafile);
581 image.write(mapdatafile);
584 std::string mapmetadatafile = save_parameters.map_file_name +
".yaml";
586 std::ofstream yaml(mapmetadatafile);
588 geometry_msgs::msg::Quaternion orientation = map.info.origin.orientation;
589 tf2::Matrix3x3 mat(tf2::Quaternion(orientation.x, orientation.y, orientation.z, orientation.w));
590 double yaw, pitch, roll;
591 mat.getEulerYPR(yaw, pitch, roll);
593 const int file_name_index = mapdatafile.find_last_of(
"/\\");
594 std::string image_name = mapdatafile.substr(file_name_index + 1);
597 e << YAML::Precision(3);
599 e << YAML::Key <<
"image" << YAML::Value << image_name;
600 e << YAML::Key <<
"mode" << YAML::Value << map_mode_to_string(save_parameters.mode);
601 e << YAML::Key <<
"resolution" << YAML::Value << map.info.resolution;
602 e << YAML::Key <<
"origin" << YAML::Flow << YAML::BeginSeq << map.info.origin.position.x <<
603 map.info.origin.position.y << yaw << YAML::EndSeq;
604 e << YAML::Key <<
"negate" << YAML::Value << 0;
606 if (save_parameters.mode == MapMode::Trinary) {
611 e << YAML::Key <<
"occupied_thresh" << YAML::Value << 0.65;
612 e << YAML::Key <<
"free_thresh" << YAML::Value << 0.196;
614 e << YAML::Key <<
"occupied_thresh" << YAML::Value << save_parameters.occupied_thresh;
615 e << YAML::Key <<
"free_thresh" << YAML::Value << save_parameters.free_thresh;
620 rclcpp::get_logger(
"map_io"),
"YAML writer failed with an error " << e.GetLastError() <<
621 ". The map metadata may be invalid.");
624 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"Writing map metadata to " << mapmetadatafile);
625 std::ofstream(mapmetadatafile) << e.c_str();
627 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"Map saved");
631 const nav_msgs::msg::OccupancyGrid & map,
632 const SaveParameters & save_parameters)
635 SaveParameters save_parameters_loc = save_parameters;
639 checkSaveParameters(save_parameters_loc);
641 tryWriteMapToFile(map, save_parameters_loc);
642 }
catch (std::exception & e) {
644 rclcpp::get_logger(
"map_io"),
645 "Failed to write map for reason: " << e.what());