Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
map_server.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 #ifndef NAV2_MAP_SERVER__MAP_SERVER_HPP_
16 #define NAV2_MAP_SERVER__MAP_SERVER_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include <functional>
21 
22 #include "rclcpp/rclcpp.hpp"
23 #include "nav2_util/lifecycle_node.hpp"
24 #include "nav_msgs/msg/occupancy_grid.hpp"
25 #include "nav_msgs/srv/get_map.hpp"
26 #include "nav2_msgs/srv/load_map.hpp"
27 
28 namespace nav2_map_server
29 {
30 
37 {
38 public:
43  explicit MapServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
44 
48  ~MapServer();
49 
50 protected:
56  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
62  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
68  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
74  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
80  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
81 
91  const std::string & yaml_file,
92  std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response);
93 
97  void updateMsgHeader();
98 
105  void getMapCallback(
106  const std::shared_ptr<rmw_request_id_t> request_header,
107  const std::shared_ptr<nav_msgs::srv::GetMap::Request> request,
108  std::shared_ptr<nav_msgs::srv::GetMap::Response> response);
109 
116  void loadMapCallback(
117  const std::shared_ptr<rmw_request_id_t> request_header,
118  const std::shared_ptr<nav2_msgs::srv::LoadMap::Request> request,
119  std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response);
120 
121  // The name of the service for getting a map
122  const std::string service_name_{"map"};
123 
124  // The name of the service for loading a map
125  const std::string load_map_service_name_{"load_map"};
126 
127  // A service to provide the occupancy grid (GetMap) and the message to return
128  rclcpp::Service<nav_msgs::srv::GetMap>::SharedPtr occ_service_;
129 
130  // A service to load the occupancy grid from file at run time (LoadMap)
131  rclcpp::Service<nav2_msgs::srv::LoadMap>::SharedPtr load_map_service_;
132 
133  // A topic on which the occupancy grid will be published
134  rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr occ_pub_;
135 
136  // The frame ID used in the returned OccupancyGrid message
137  std::string frame_id_;
138 
139  // The message to publish on the occupancy grid topic
140  nav_msgs::msg::OccupancyGrid msg_;
141 
142  // true if msg_ was initialized
143  bool map_available_;
144 };
145 
146 } // namespace nav2_map_server
147 
148 #endif // NAV2_MAP_SERVER__MAP_SERVER_HPP_
Parses the map yaml file and creates a service and a publisher that provides occupancy grid.
Definition: map_server.hpp:37
void loadMapCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::LoadMap::Request > request, std::shared_ptr< nav2_msgs::srv::LoadMap::Response > response)
Map loading service callback.
Definition: map_server.cpp:196
void getMapCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav_msgs::srv::GetMap::Request > request, std::shared_ptr< nav_msgs::srv::GetMap::Response > response)
Map getting service callback.
Definition: map_server.cpp:180
void updateMsgHeader()
Method correcting msg_ header when it belongs to instantiated object.
Definition: map_server.cpp:243
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Start publishing the map using the latched topic.
Definition: map_server.cpp:129
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
Definition: map_server.cpp:174
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Stops publishing the latched topic.
Definition: map_server.cpp:147
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Sets up required params and services. Loads map and its parameters from the file.
Definition: map_server.cpp:81
MapServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for nav2_map_server::MapServer.
Definition: map_server.cpp:65
~MapServer()
A Destructor for nav2_map_server::MapServer.
Definition: map_server.cpp:76
bool loadMapResponseFromYaml(const std::string &yaml_file, std::shared_ptr< nav2_msgs::srv::LoadMap::Response > response)
Load the map YAML, image from map file name and generate output response containing an OccupancyGrid....
Definition: map_server.cpp:217
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets the member variables.
Definition: map_server.cpp:160
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.