Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
map_io.hpp
1 // Copyright (c) 2018 Intel Corporation
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 
15 /* OccupancyGrid map input-output library */
16 
17 #ifndef NAV2_MAP_SERVER__MAP_IO_HPP_
18 #define NAV2_MAP_SERVER__MAP_IO_HPP_
19 
20 #include <string>
21 #include <vector>
22 
23 #include "nav2_map_server/map_mode.hpp"
24 #include "nav_msgs/msg/occupancy_grid.hpp"
25 
26 /* Map input part */
27 
28 namespace nav2_map_server
29 {
30 
32 {
33  std::string image_file_name;
34  double resolution{0};
35  std::vector<double> origin{0, 0, 0};
36  double free_thresh;
37  double occupied_thresh;
38  MapMode mode;
39  bool negate;
40 };
41 
42 typedef enum
43 {
44  LOAD_MAP_SUCCESS,
45  MAP_DOES_NOT_EXIST,
46  INVALID_MAP_METADATA,
47  INVALID_MAP_DATA
48 } LOAD_MAP_STATUS;
49 
56 LoadParameters loadMapYaml(const std::string & yaml_filename);
57 
64 void loadMapFromFile(
65  const LoadParameters & load_parameters,
66  nav_msgs::msg::OccupancyGrid & map);
67 
75 LOAD_MAP_STATUS loadMapFromYaml(
76  const std::string & yaml_file,
77  nav_msgs::msg::OccupancyGrid & map);
78 
79 
80 /* Map output part */
81 
83 {
84  std::string map_file_name{""};
85  std::string image_format{""};
86  double free_thresh{0.0};
87  double occupied_thresh{0.0};
88  MapMode mode{MapMode::Trinary};
89 };
90 
97 bool saveMapToFile(
98  const nav_msgs::msg::OccupancyGrid & map,
99  const SaveParameters & save_parameters);
100 
108 std::string expand_user_home_dir_if_needed(
109  std::string yaml_filename,
110  std::string home_dir);
111 
112 } // namespace nav2_map_server
113 
114 #endif // NAV2_MAP_SERVER__MAP_IO_HPP_