Nav2 Navigation Stack - kilted  kilted
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 <memory>
19 #include <string>
20 
21 #include "nav2_util/lifecycle_node.hpp"
22 #include "nav2_util/service_server.hpp"
23 #include "nav_msgs/msg/occupancy_grid.hpp"
24 #include "nav_msgs/srv/get_map.hpp"
25 #include "nav2_msgs/srv/load_map.hpp"
26 #include "rclcpp/rclcpp.hpp"
27 #include "rclcpp_lifecycle/state.hpp"
28 
29 namespace nav2_map_server
30 {
31 
38 {
39 public:
44  explicit MapServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
45 
49  ~MapServer();
50 
51 protected:
57  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
63  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
69  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
75  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
81  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
82 
92  const std::string & yaml_file,
93  std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response);
94 
98  void updateMsgHeader();
99 
106  void getMapCallback(
107  const std::shared_ptr<rmw_request_id_t> request_header,
108  const std::shared_ptr<nav_msgs::srv::GetMap::Request> request,
109  std::shared_ptr<nav_msgs::srv::GetMap::Response> response);
110 
117  void loadMapCallback(
118  const std::shared_ptr<rmw_request_id_t> request_header,
119  const std::shared_ptr<nav2_msgs::srv::LoadMap::Request> request,
120  std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response);
121 
122  // The name of the service for getting a map
123  const std::string service_name_{"map"};
124 
125  // The name of the service for loading a map
126  const std::string load_map_service_name_{"load_map"};
127 
128  // A service to provide the occupancy grid (GetMap) and the message to return
129  nav2_util::ServiceServer<nav_msgs::srv::GetMap,
130  std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr occ_service_;
131 
132  // A service to load the occupancy grid from file at run time (LoadMap)
133  nav2_util::ServiceServer<nav2_msgs::srv::LoadMap,
134  std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr load_map_service_;
135 
136  // A topic on which the occupancy grid will be published
137  rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr occ_pub_;
138 
139  // The frame ID used in the returned OccupancyGrid message
140  std::string frame_id_;
141 
142  // The message to publish on the occupancy grid topic
143  nav_msgs::msg::OccupancyGrid msg_;
144 
145  // true if msg_ was initialized
146  bool map_available_;
147 };
148 
149 } // namespace nav2_map_server
150 
151 #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:38
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:200
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:184
void updateMsgHeader()
Method correcting msg_ header when it belongs to instantiated object.
Definition: map_server.cpp:247
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Start publishing the map using the latched topic.
Definition: map_server.cpp:133
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
Definition: map_server.cpp:178
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Stops publishing the latched topic.
Definition: map_server.cpp:151
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:221
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets the member variables.
Definition: map_server.cpp:164
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
A simple wrapper on ROS2 services server.