00001 // Copyright 2017 Intermodalics All Rights Reserved. 00002 // 00003 // Licensed under the Apache License, Version 2.0 (the "License"); 00004 // you may not use this file except in compliance with the License. 00005 // You may obtain a copy of the License at 00006 // 00007 // http://www.apache.org/licenses/LICENSE-2.0 00008 // 00009 // Unless required by applicable law or agreed to in writing, software 00010 // distributed under the License is distributed on an "AS IS" BASIS, 00011 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00012 // See the License for the specific language governing permissions and 00013 // limitations under the License. 00014 #ifndef OCCUPANCY_GRID_FILE_IO_H_ 00015 #define OCCUPANCY_GRID_FILE_IO_H_ 00016 #include <string> 00017 00018 #include <nav_msgs/MapMetaData.h> 00019 #include <nav_msgs/OccupancyGrid.h> 00020 00021 namespace occupancy_grid_file_io { 00022 // Save an occupancy grid as two files: 00023 // one pgm file contains the cells data and one yaml file which contains 00024 // the map metadata. 00025 // Format of both files are compatible with the existing ROS node map_server. 00026 // See http://wiki.ros.org/map_server for more info. 00027 // @param map_name Name of the map. Both the pgm and yaml files get this name. 00028 // @param map_uuid Uuid of the localization map corresponding to the 00029 // occupancy grid. Can be empty if not used. 00030 // @param map_directory Directory where both pgm and yaml files are saved. 00031 // @param occupancy_grid Occupancy grid to save. 00032 bool SaveOccupancyGridToFiles( 00033 const std::string& map_name, const std::string& map_uuid, 00034 const std::string& map_directory, const nav_msgs::OccupancyGrid& occupancy_grid); 00035 00036 // Save data from an occupancy grid in a pgm file. 00037 // Format is compatible with the existing ROS node map_server. 00038 // See http://wiki.ros.org/map_server for more info. 00039 // @param map_name Name of the map. The file gets this name. 00040 // @param map_directory Directory where the file is saved. 00041 // @param occupancy_grid Occupancy grid to save. 00042 bool SaveOccupancyGridDataToPgmFile( 00043 const std::string& map_name, const std::string& map_directory, 00044 const nav_msgs::OccupancyGrid& occupancy_grid); 00045 00046 // Save metadata from an occupancy grid in a yaml file. 00047 // Format is compatible with the existing ROS node map_server. 00048 // See http://wiki.ros.org/map_server for more info. 00049 // @param map_name Name of the map. The file gets this name. 00050 // @param map_uuid Uuid of the localization map corresponding to the 00051 // occupancy grid. Can be empty if not used. 00052 // @param map_directory Directory where the file is saved. 00053 // @param map_metadata Occupancy grid metadata to save. 00054 bool SaveOccupancyGridMetadataToYamlFile( 00055 const std::string& map_name, const std::string& map_uuid, 00056 const std::string& map_directory, const nav_msgs::MapMetaData& map_metadata); 00057 00058 // Load an occupancy grid from two files: 00059 // one pgm file contains the cells data and one yaml file which contains 00060 // the map metadata. 00061 // @param map_name Name of the map, i.e. of both files. 00062 // @param map_directory Directory where both pgm and yaml files are located. 00063 // @param occupancy_grid Loaded occupancy grid. 00064 // @param map_uuid Uuid of the localization map corresponding to the 00065 // occupancy grid. 00066 bool LoadOccupancyGridFromFiles( 00067 const std::string& map_name, const std::string& map_directory, 00068 nav_msgs::OccupancyGrid* occupancy_grid, std::string* map_uuid); 00069 00070 // Load an occupancy grid data from a pgm file. 00071 // @param map_name Name of the map, i.e. of the file. 00072 // @param map_directory Directory where the file is located. 00073 // @param negate true if blacker pixels should be considered free, and whiter 00074 // pixels occupied. 00075 // @param occupied_threshold Threshold between 0 and 1. Greater values are 00076 // considered as occupied. 00077 // @param free_threshold Threshold between 0 and 1. Smaller values are 00078 // considered as free. 00079 // @param occupancy_grid Loaded occupancy grid. 00080 bool LoadOccupancyGridDataFromPgmFile( 00081 const std::string& map_name, const std::string& map_directory, 00082 bool negate, double occupied_threshold, double free_threshold, 00083 nav_msgs::OccupancyGrid* occupancy_grid); 00084 00085 // Load an occupancy grid metadata from a yaml file. 00086 // @param map_name Name of the map, i.e. of the file. 00087 // @param map_directory Directory where the file is located. 00088 // @param map_metadata Loaded occupancy grid metadata. 00089 // @param negate true if blacker pixels should be considered free, and whiter 00090 // pixels occupied. 00091 // @param occupied_threshold Threshold between 0 and 1. Greater values are 00092 // considered as occupied. 00093 // @param free_threshold Threshold between 0 and 1. Smaller values are 00094 // considered as free. 00095 // @param map_uuid Uuid of the localization map corresponding to the 00096 // occupancy grid. 00097 bool LoadOccupancyGridMetadataFromYamlFile( 00098 const std::string& map_name, const std::string& map_directory, 00099 nav_msgs::MapMetaData* map_metadata, int* negate, 00100 double* occupied_threshold, double* free_threshold, std::string* map_uuid); 00101 } // namespace occupancy_grid_file_io 00102 #endif // OCCUPANCY_GRID_FILE_IO_H_