#include <string>
#include <nav_msgs/MapMetaData.h>
#include <nav_msgs/OccupancyGrid.h>
Go to the source code of this file.
Namespaces | |
namespace | occupancy_grid_file_io |
Functions | |
bool | occupancy_grid_file_io::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 | occupancy_grid_file_io::LoadOccupancyGridFromFiles (const std::string &map_name, const std::string &map_directory, nav_msgs::OccupancyGrid *occupancy_grid, std::string *map_uuid) |
bool | occupancy_grid_file_io::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 | occupancy_grid_file_io::SaveOccupancyGridDataToPgmFile (const std::string &map_name, const std::string &map_directory, const nav_msgs::OccupancyGrid &occupancy_grid) |
bool | occupancy_grid_file_io::SaveOccupancyGridMetadataToYamlFile (const std::string &map_name, const std::string &map_uuid, const std::string &map_directory, const nav_msgs::MapMetaData &map_metadata) |
bool | occupancy_grid_file_io::SaveOccupancyGridToFiles (const std::string &map_name, const std::string &map_uuid, const std::string &map_directory, const nav_msgs::OccupancyGrid &occupancy_grid) |