17#ifndef EASYNAV_COSTMAP_COMMON__MAP_IO_HPP_
18#define EASYNAV_COSTMAP_COMMON__MAP_IO_HPP_
23#include "nav_msgs/msg/occupancy_grid.hpp"
103LoadParameters
loadMapYaml(
const std::string & yaml_filename);
112 const LoadParameters & load_parameters,
113 nav_msgs::msg::OccupancyGrid & map);
123 const std::string & yaml_file,
124 nav_msgs::msg::OccupancyGrid & map);
145 const nav_msgs::msg::OccupancyGrid & map,
146 const SaveParameters & save_parameters);
156 std::string yaml_filename,
157 std::string home_dir);
Provides a mapping for often used cost values.
Definition cost_values.hpp:41
LOAD_MAP_STATUS
Definition map_io.hpp:90
@ INVALID_MAP_METADATA
Definition map_io.hpp:93
@ MAP_DOES_NOT_EXIST
Definition map_io.hpp:92
@ INVALID_MAP_DATA
Definition map_io.hpp:94
@ LOAD_MAP_SUCCESS
Definition map_io.hpp:91
MapMode map_mode_from_string(std::string map_mode_name)
Convert the name of a map mode to a MapMode enum.
Definition map_io.cpp:681
bool saveMapToFile(const nav_msgs::msg::OccupancyGrid &map, const SaveParameters &save_parameters)
Write OccupancyGrid map to file.
Definition map_io.cpp:631
LoadParameters loadMapYaml(const std::string &yaml_filename)
Load and parse the given YAML file.
Definition map_io.cpp:150
MapMode
Definition map_io.hpp:37
@ Raw
Lightness = 0 - Free (0) ... (linearly interpolate to) Lightness = 100 - Occupied (100) Lightness >= ...
Definition map_io.hpp:59
@ Scale
Together with associated threshold values (occupied and free): alpha < 1.0 - Unknown (-1) lightness >...
Definition map_io.hpp:52
@ Trinary
Together with associated threshold values (occupied and free): lightness >= occupied threshold - Occu...
Definition map_io.hpp:44
std::string expand_user_home_dir_if_needed(std::string yaml_filename, std::string home_dir)
Expand ~/ to home user dir.
Definition map_io.cpp:132
void loadMapFromFile(const LoadParameters &load_parameters, nav_msgs::msg::OccupancyGrid &map)
Load the image from map file and generate an OccupancyGrid.
Definition map_io.cpp:207
LOAD_MAP_STATUS loadMapFromYaml(const std::string &yaml_file, nav_msgs::msg::OccupancyGrid &map)
Load the map YAML, image from map file and generate an OccupancyGrid.
Definition map_io.cpp:348
const char * map_mode_to_string(MapMode map_mode)
Convert a MapMode enum to the name of the map mode.
Definition map_io.cpp:667
double resolution
Definition map_io.hpp:81
double free_thresh
Definition map_io.hpp:83
bool negate
Definition map_io.hpp:86
double occupied_thresh
Definition map_io.hpp:84
std::string image_file_name
Definition map_io.hpp:80
MapMode mode
Definition map_io.hpp:85
std::vector< double > origin
Definition map_io.hpp:82
Definition map_io.hpp:130
double free_thresh
Definition map_io.hpp:133
std::string image_format
Definition map_io.hpp:132
std::string map_file_name
Definition map_io.hpp:131
double occupied_thresh
Definition map_io.hpp:134
MapMode mode
Definition map_io.hpp:135