occupancy_grid_file_io.h
Go to the documentation of this file.
1 // Copyright 2017 Intermodalics All Rights Reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 #ifndef OCCUPANCY_GRID_FILE_IO_H_
15 #define OCCUPANCY_GRID_FILE_IO_H_
16 #include <string>
17 
18 #include <nav_msgs/MapMetaData.h>
19 #include <nav_msgs/OccupancyGrid.h>
20 
22 // Save an occupancy grid as two files:
23 // one pgm file contains the cells data and one yaml file which contains
24 // the map metadata.
25 // Format of both files are compatible with the existing ROS node map_server.
26 // See http://wiki.ros.org/map_server for more info.
27 // @param map_name Name of the map. Both the pgm and yaml files get this name.
28 // @param map_uuid Uuid of the localization map corresponding to the
29 // occupancy grid. Can be empty if not used.
30 // @param map_directory Directory where both pgm and yaml files are saved.
31 // @param occupancy_grid Occupancy grid to save.
33  const std::string& map_name, const std::string& map_uuid,
34  const std::string& map_directory, const nav_msgs::OccupancyGrid& occupancy_grid);
35 
36 // Save data from an occupancy grid in a pgm file.
37 // Format is compatible with the existing ROS node map_server.
38 // See http://wiki.ros.org/map_server for more info.
39 // @param map_name Name of the map. The file gets this name.
40 // @param map_directory Directory where the file is saved.
41 // @param occupancy_grid Occupancy grid to save.
43  const std::string& map_name, const std::string& map_directory,
44  const nav_msgs::OccupancyGrid& occupancy_grid);
45 
46 // Save metadata from an occupancy grid in a yaml file.
47 // Format is compatible with the existing ROS node map_server.
48 // See http://wiki.ros.org/map_server for more info.
49 // @param map_name Name of the map. The file gets this name.
50 // @param map_uuid Uuid of the localization map corresponding to the
51 // occupancy grid. Can be empty if not used.
52 // @param map_directory Directory where the file is saved.
53 // @param map_metadata Occupancy grid metadata to save.
55  const std::string& map_name, const std::string& map_uuid,
56  const std::string& map_directory, const nav_msgs::MapMetaData& map_metadata);
57 
58 // Load an occupancy grid from two files:
59 // one pgm file contains the cells data and one yaml file which contains
60 // the map metadata.
61 // @param map_name Name of the map, i.e. of both files.
62 // @param map_directory Directory where both pgm and yaml files are located.
63 // @param occupancy_grid Loaded occupancy grid.
64 // @param map_uuid Uuid of the localization map corresponding to the
65 // occupancy grid.
67  const std::string& map_name, const std::string& map_directory,
68  nav_msgs::OccupancyGrid* occupancy_grid, std::string* map_uuid);
69 
70 // Load an occupancy grid data from a pgm file.
71 // @param map_name Name of the map, i.e. of the file.
72 // @param map_directory Directory where the file is located.
73 // @param negate true if blacker pixels should be considered free, and whiter
74 // pixels occupied.
75 // @param occupied_threshold Threshold between 0 and 1. Greater values are
76 // considered as occupied.
77 // @param free_threshold Threshold between 0 and 1. Smaller values are
78 // considered as free.
79 // @param occupancy_grid Loaded occupancy grid.
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);
84 
85 // Load an occupancy grid metadata from a yaml file.
86 // @param map_name Name of the map, i.e. of the file.
87 // @param map_directory Directory where the file is located.
88 // @param map_metadata Loaded occupancy grid metadata.
89 // @param negate true if blacker pixels should be considered free, and whiter
90 // pixels occupied.
91 // @param occupied_threshold Threshold between 0 and 1. Greater values are
92 // considered as occupied.
93 // @param free_threshold Threshold between 0 and 1. Smaller values are
94 // considered as free.
95 // @param map_uuid Uuid of the localization map corresponding to the
96 // 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);
101 } // namespace occupancy_grid_file_io
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)


tango_ros_native
Author(s):
autogenerated on Mon Jun 10 2019 15:37:51