14 #ifndef OCCUPANCY_GRID_FILE_IO_H_ 15 #define OCCUPANCY_GRID_FILE_IO_H_ 18 #include <nav_msgs/MapMetaData.h> 19 #include <nav_msgs/OccupancyGrid.h> 33 const std::string& map_name,
const std::string& map_uuid,
34 const std::string& map_directory,
const nav_msgs::OccupancyGrid& occupancy_grid);
43 const std::string& map_name,
const std::string& map_directory,
44 const nav_msgs::OccupancyGrid& occupancy_grid);
55 const std::string& map_name,
const std::string& map_uuid,
56 const std::string& map_directory,
const nav_msgs::MapMetaData& map_metadata);
67 const std::string& map_name,
const std::string& map_directory,
68 nav_msgs::OccupancyGrid* occupancy_grid, std::string* map_uuid);
81 const std::string& map_name,
const std::string& map_directory,
82 bool negate,
double occupied_threshold,
double free_threshold,
83 nav_msgs::OccupancyGrid* occupancy_grid);
98 const std::string& map_name,
const std::string& map_directory,
99 nav_msgs::MapMetaData* map_metadata,
int* negate,
100 double* occupied_threshold,
double* free_threshold, std::string* map_uuid);
102 #endif // OCCUPANCY_GRID_FILE_IO_H_ bool SaveOccupancyGridDataToPgmFile(const std::string &map_name, const std::string &map_directory, const nav_msgs::OccupancyGrid &occupancy_grid)
bool LoadOccupancyGridFromFiles(const std::string &map_name, const std::string &map_directory, nav_msgs::OccupancyGrid *occupancy_grid, std::string *map_uuid)
bool SaveOccupancyGridToFiles(const std::string &map_name, const std::string &map_uuid, const std::string &map_directory, const nav_msgs::OccupancyGrid &occupancy_grid)
bool LoadOccupancyGridMetadataFromYamlFile(const std::string &map_name, const std::string &map_directory, nav_msgs::MapMetaData *map_metadata, int *negate, double *occupied_threshold, double *free_threshold, std::string *map_uuid)
bool LoadOccupancyGridDataFromPgmFile(const std::string &map_name, const std::string &map_directory, bool negate, double occupied_threshold, double free_threshold, nav_msgs::OccupancyGrid *occupancy_grid)
bool SaveOccupancyGridMetadataToYamlFile(const std::string &map_name, const std::string &map_uuid, const std::string &map_directory, const nav_msgs::MapMetaData &map_metadata)