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"
51 #include "tf2/LinearMath/Matrix3x3.h"
52 #include "tf2/LinearMath/Quaternion.h"
53 #include "nav2_util/occ_grid_values.hpp"
58 char * dirname(
char * path)
60 static const char dot[] =
".";
70 if (*c ==
'\\') {*c =
'/';}
75 last_slash = path != NULL ? strrchr(path,
'/') : NULL;
77 if (last_slash != NULL && last_slash == path) {
81 }
else if (last_slash != NULL && last_slash[1] ==
'\0') {
83 last_slash =
reinterpret_cast<char *
>(memchr(path, last_slash - path,
'/'));
86 if (last_slash != NULL) {
93 path =
reinterpret_cast<char *
>(dot);
100 namespace nav2_map_server
102 using nav2_util::geometry_utils::orientationAroundZAxis;
111 T yaml_get_value(
const YAML::Node & node,
const std::string & key)
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());
122 std::string get_home_dir()
124 if (
const char * home_dir = std::getenv(
"HOME")) {
125 return std::string{home_dir};
127 return std::string{};
130 std::string expand_user_home_dir_if_needed(
131 std::string yaml_filename,
132 std::string home_variable_value)
134 if (yaml_filename.size() < 2 || !(yaml_filename[0] ==
'~' && yaml_filename[1] ==
'/')) {
135 return yaml_filename;
137 if (home_variable_value.empty()) {
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;
144 const std::string prefix{home_variable_value};
145 return yaml_filename.replace(0, 1, prefix);
148 LoadParameters loadMapYaml(
const std::string & yaml_filename)
150 YAML::Node doc = YAML::LoadFile(expand_user_home_dir_if_needed(yaml_filename, get_home_dir()));
151 LoadParameters load_parameters;
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.");
157 if (image_file_name[0] !=
'/') {
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;
163 load_parameters.image_file_name = image_file_name;
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()));
173 load_parameters.free_thresh = yaml_get_value<double>(doc,
"free_thresh");
174 load_parameters.occupied_thresh = yaml_get_value<double>(doc,
"occupied_thresh");
176 auto map_mode_node = doc[
"mode"];
177 if (!map_mode_node.IsDefined()) {
178 load_parameters.mode = MapMode::Trinary;
180 load_parameters.mode = map_mode_from_string(map_mode_node.as<std::string>());
184 load_parameters.negate = yaml_get_value<int>(doc,
"negate");
185 }
catch (YAML::Exception &) {
186 load_parameters.negate = yaml_get_value<bool>(doc,
"negate");
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);
196 "map_io"),
"occupied_thresh: " << load_parameters.occupied_thresh);
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);
202 return load_parameters;
205 void loadMapFromFile(
206 const LoadParameters & load_parameters,
207 nav_msgs::msg::OccupancyGrid & map)
209 Magick::InitializeMagick(
nullptr);
210 nav_msgs::msg::OccupancyGrid msg;
213 rclcpp::get_logger(
"map_io"),
"Loading image_file: " <<
214 load_parameters.image_file_name);
215 Magick::Image img(load_parameters.image_file_name);
218 msg.info.width = img.size().width();
219 msg.info.height = img.size().height();
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]);
228 msg.data.resize(msg.info.width * msg.info.height);
231 Magick::Image gray = img;
232 gray.type(Magick::GrayscaleType);
235 size_t width = gray.columns();
236 size_t height = gray.rows();
238 std::vector<uint8_t> buffer(width * height);
239 gray.write(0, 0, width, height,
"I", Magick::CharPixel, buffer.data());
242 Eigen::Map<Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>>
243 gray_matrix(buffer.data(), height, width);
245 bool has_alpha = img.matte();
251 Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> result(height, width);
253 if (load_parameters.mode == MapMode::Trinary || load_parameters.mode == MapMode::Scale) {
255 Eigen::Matrix<float, Eigen::Dynamic, Eigen::Dynamic,
256 Eigen::RowMajor> normalized = gray_matrix.cast<
float>() / 255.0f;
259 if (!load_parameters.negate) {
260 normalized = (1.0f - normalized.array()).matrix();
264 Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> occupied =
265 (normalized.array() >= load_parameters.occupied_thresh).cast<uint8_t>();
267 Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> free =
268 (normalized.array() <= load_parameters.free_thresh).cast<uint8_t>();
271 result.setConstant(nav2_util::OCC_GRID_UNKNOWN);
274 result = (occupied.array() > 0).select(nav2_util::OCC_GRID_OCCUPIED, result);
275 result = (free.array() > 0).select(nav2_util::OCC_GRID_FREE, result);
278 if (load_parameters.mode == MapMode::Scale) {
280 auto in_between_mask = (normalized.array() > load_parameters.free_thresh) &&
281 (normalized.array() < load_parameters.occupied_thresh);
283 if (in_between_mask.any()) {
285 Eigen::ArrayXXf scaled_float = ((normalized.array() - load_parameters.free_thresh) /
286 (load_parameters.occupied_thresh - load_parameters.free_thresh)) * 100.0f;
289 Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> scaled_int =
290 scaled_float.array().round().cast<int8_t>();
292 result = in_between_mask.select(scaled_int, result);
299 std::vector<uint8_t> alpha_buf(width * height);
300 img.write(0, 0, width, height,
"A", Magick::CharPixel, alpha_buf.data());
303 Eigen::Map<Eigen::Array<uint8_t, Eigen::Dynamic, Eigen::Dynamic,
304 Eigen::RowMajor>> alpha_array(
305 alpha_buf.data(), height, width);
308 result = (alpha_array < 255).select(nav2_util::OCC_GRID_UNKNOWN, result);
311 }
else if (load_parameters.mode == MapMode::Raw) {
313 result = gray_matrix.cast<int8_t>();
316 auto out_of_bounds = (result.array() < nav2_util::OCC_GRID_FREE) ||
317 (result.array() > nav2_util::OCC_GRID_OCCUPIED);
319 result = out_of_bounds.select(nav2_util::OCC_GRID_UNKNOWN, result);
323 throw std::runtime_error(
"Invalid map mode");
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);
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();
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");
346 LOAD_MAP_STATUS loadMapFromYaml(
347 const std::string & yaml_file,
348 nav_msgs::msg::OccupancyGrid & map)
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;
354 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"Loading yaml file: " << yaml_file);
355 LoadParameters load_parameters;
357 load_parameters = loadMapYaml(yaml_file);
358 }
catch (YAML::Exception & e) {
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) {
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;
371 loadMapFromFile(load_parameters, map);
372 }
catch (std::exception & e) {
375 "map_io"),
"Failed to load image file " << load_parameters.image_file_name <<
376 " for reason: " << e.what());
377 return INVALID_MAP_DATA;
380 return LOAD_MAP_SUCCESS;
391 void checkSaveParameters(SaveParameters & save_parameters)
394 Magick::InitializeMagick(
nullptr);
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()));
402 rclcpp::get_logger(
"map_io"),
"Map file unspecified. Map will be saved to " <<
403 save_parameters.map_file_name <<
" file");
407 if (save_parameters.occupied_thresh == 0.0) {
408 save_parameters.occupied_thresh = 0.65;
411 "map_io"),
"Occupied threshold unspecified. Setting it to default value: " <<
412 save_parameters.occupied_thresh);
414 if (save_parameters.free_thresh == 0.0) {
415 save_parameters.free_thresh = 0.25;
417 rclcpp::get_logger(
"map_io"),
"Free threshold unspecified. Setting it to default value: " <<
418 save_parameters.free_thresh);
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");
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");
428 if (save_parameters.occupied_thresh <= save_parameters.free_thresh) {
431 "map_io"),
"Threshold_free must be smaller than threshold_occupied");
432 throw std::runtime_error(
"Incorrect thresholds");
436 if (save_parameters.image_format ==
"") {
437 save_parameters.image_format = save_parameters.mode == MapMode::Scale ?
"png" :
"pgm";
439 rclcpp::get_logger(
"map_io"),
"Image format unspecified. Setting it to: " <<
440 save_parameters.image_format);
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);});
449 const std::vector<std::string> BLESSED_FORMATS{
"bmp",
"pgm",
"png"};
451 std::find(BLESSED_FORMATS.begin(), BLESSED_FORMATS.end(), save_parameters.image_format) ==
452 BLESSED_FORMATS.end())
454 std::stringstream ss;
456 for (
auto & format_name : BLESSED_FORMATS) {
460 ss <<
"'" << format_name <<
"'";
464 rclcpp::get_logger(
"map_io"),
"Requested image format '" << save_parameters.image_format <<
465 "' is not one of the recommended formats: " << ss.str());
467 const std::string FALLBACK_FORMAT =
"png";
470 Magick::CoderInfo info(save_parameters.image_format);
471 if (!info.isWritable()) {
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;
477 }
catch (Magick::ErrorOption & e) {
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;
487 save_parameters.mode == MapMode::Scale &&
488 (save_parameters.image_format ==
"pgm" ||
489 save_parameters.image_format ==
"jpg" ||
490 save_parameters.image_format ==
"jpeg"))
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'.");
505 void tryWriteMapToFile(
506 const nav_msgs::msg::OccupancyGrid & map,
507 const SaveParameters & save_parameters)
511 "map_io"),
"Received a " << map.info.width <<
" X " << map.info.height <<
" map @ " <<
512 map.info.resolution <<
" m/pix");
514 std::string mapdatafile = save_parameters.map_file_name +
"." + save_parameters.image_format;
517 Magick::Image image({map.info.width, map.info.height},
"red");
523 save_parameters.mode == MapMode::Scale ?
524 Magick::TrueColorMatteType : Magick::GrayscaleType);
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);
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];
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);
547 pixel = Magick::ColorGray(205 / 255.0);
551 if (map_cell < 0 || 100 < map_cell) {
552 pixel = Magick::ColorGray{0.5};
553 pixel.alphaQuantum(TransparentOpacity);
555 pixel = Magick::ColorGray{(100.0 - map_cell) / 100.0};
560 if (map_cell < 0 || 100 < map_cell) {
563 q = map_cell / 255.0 * MaxRGB;
565 pixel = Magick::Color(q, q, q);
570 "map_io"),
"Map mode should be Trinary, Scale or Raw");
571 throw std::runtime_error(
"Invalid map mode");
573 image.pixelColor(x, y, pixel);
578 rclcpp::get_logger(
"map_io"),
579 "Writing map occupancy data to " << mapdatafile);
580 image.write(mapdatafile);
583 std::string mapmetadatafile = save_parameters.map_file_name +
".yaml";
585 std::ofstream yaml(mapmetadatafile);
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);
592 const int file_name_index = mapdatafile.find_last_of(
"/\\");
593 std::string image_name = mapdatafile.substr(file_name_index + 1);
596 e << YAML::Precision(3);
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;
605 if (save_parameters.mode == MapMode::Trinary) {
610 e << YAML::Key <<
"occupied_thresh" << YAML::Value << 0.65;
611 e << YAML::Key <<
"free_thresh" << YAML::Value << 0.196;
613 e << YAML::Key <<
"occupied_thresh" << YAML::Value << save_parameters.occupied_thresh;
614 e << YAML::Key <<
"free_thresh" << YAML::Value << save_parameters.free_thresh;
619 rclcpp::get_logger(
"map_io"),
"YAML writer failed with an error " << e.GetLastError() <<
620 ". The map metadata may be invalid.");
623 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"Writing map metadata to " << mapmetadatafile);
624 std::ofstream(mapmetadatafile) << e.c_str();
626 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"map_io"),
"Map saved");
630 const nav_msgs::msg::OccupancyGrid & map,
631 const SaveParameters & save_parameters)
634 SaveParameters save_parameters_loc = save_parameters;
638 checkSaveParameters(save_parameters_loc);
640 tryWriteMapToFile(map, save_parameters_loc);
641 }
catch (std::exception & e) {
643 rclcpp::get_logger(
"map_io"),
644 "Failed to write map for reason: " << e.what());