Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
lifecycle_manager.hpp
1 // Copyright (c) 2019 Intel Corporation
2 // Copyright (c) 2022 Samsung Research America
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_HPP_
17 #define NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_HPP_
18 
19 #include <map>
20 #include <memory>
21 #include <string>
22 #include <thread>
23 #include <unordered_map>
24 #include <vector>
25 
26 #include "nav2_util/lifecycle_service_client.hpp"
27 #include "nav2_ros_common/node_thread.hpp"
28 #include "nav2_ros_common/service_server.hpp"
29 #include "rclcpp/rclcpp.hpp"
30 #include "std_srvs/srv/empty.hpp"
31 #include "nav2_msgs/srv/manage_lifecycle_nodes.hpp"
32 #include "std_srvs/srv/trigger.hpp"
33 #include "bondcpp/bond.hpp"
34 #include "diagnostic_updater/diagnostic_updater.hpp"
35 #include "nav2_ros_common/lifecycle_node.hpp"
36 
37 
38 namespace nav2_lifecycle_manager
39 {
40 using namespace std::chrono_literals; // NOLINT
41 
42 using nav2_msgs::srv::ManageLifecycleNodes;
43 
45 enum NodeState
46 {
47  UNCONFIGURED,
48  ACTIVE,
49  INACTIVE,
50  FINALIZED,
51  UNKNOWN,
52 };
53 
60 class LifecycleManager : public rclcpp::Node
61 {
62 public:
67  explicit LifecycleManager(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
72 
73 protected:
74  // Callback group used by services and timers
75  rclcpp::CallbackGroup::SharedPtr callback_group_;
76  std::unique_ptr<nav2::NodeThread> service_thread_;
77 
78  // The services provided by this node
79  nav2::ServiceServer<ManageLifecycleNodes>::SharedPtr manager_srv_;
80  nav2::ServiceServer<std_srvs::srv::Trigger>::SharedPtr is_active_srv_;
87  void managerCallback(
88  const std::shared_ptr<rmw_request_id_t> request_header,
89  const std::shared_ptr<ManageLifecycleNodes::Request> request,
90  std::shared_ptr<ManageLifecycleNodes::Response> response);
98  void isActiveCallback(
99  const std::shared_ptr<rmw_request_id_t> request_header,
100  const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
101  std::shared_ptr<std_srvs::srv::Trigger::Response> response);
102 
103  // Support functions for the service calls
108  bool startup();
113  bool configure();
118  bool cleanup();
123  bool shutdown();
128  bool reset(bool hard_reset = false);
133  bool pause();
138  bool resume();
139 
145  void onRclPreshutdown();
146 
147  // Support function for creating service clients
151  void createLifecycleServiceClients();
152 
153  // Support function for creating service servers
157  void createLifecycleServiceServers();
158 
159  // Support functions for shutdown
163  void shutdownAllNodes();
167  void destroyLifecycleServiceClients();
168 
169  // Support function for creating bond timer
173  void createBondTimer();
174 
175  // Support function for creating bond connection
179  bool createBondConnection(const std::string & node_name);
180 
181  // Support function for killing bond connections
185  void destroyBondTimer();
186 
187  // Support function for checking on bond connections
192  void checkBondConnections();
193 
194  // Support function for checking if bond connections come back after respawn
199  void checkBondRespawnConnection();
200 
204  bool changeStateForNode(
205  const std::string & node_name,
206  std::uint8_t transition);
207 
211  bool changeStateForAllNodes(std::uint8_t transition, bool hard_change = false);
212 
213  // Convenience function to highlight the output on the console
217  void message(const std::string & msg);
218 
219  // Diagnostics functions
223  void CreateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);
224 
231  void registerRclPreshutdownCallback();
232 
236  bool isActive();
237 
238  // Timer thread to look at bond connections
239  rclcpp::TimerBase::SharedPtr init_timer_;
240  rclcpp::TimerBase::SharedPtr bond_timer_;
241  rclcpp::TimerBase::SharedPtr bond_respawn_timer_;
242  std::chrono::milliseconds bond_timeout_;
243  std::chrono::milliseconds service_timeout_;
244 
245  // A map of all nodes to check bond connection
246  std::map<std::string, std::shared_ptr<bond::Bond>> bond_map_;
247 
248  // A map of all nodes to be controlled
249  std::map<std::string, std::shared_ptr<nav2_util::LifecycleServiceClient>> node_map_;
250 
251  std::map<std::uint8_t, std::string> transition_label_map_;
252 
253  // A map of the expected transitions to primary states
254  std::unordered_map<std::uint8_t, std::uint8_t> transition_state_map_;
255 
256  // The names of the nodes to be managed, in the order of desired bring-up
257  std::vector<std::string> node_names_;
258 
259  // Whether to automatically start up the system
260  bool autostart_;
261  bool attempt_respawn_reconnection_;
262 
263  NodeState managed_nodes_state_{NodeState::UNCONFIGURED};
264  diagnostic_updater::Updater diagnostics_updater_;
265 
266  rclcpp::Time bond_respawn_start_time_{0};
267  rclcpp::Duration bond_respawn_max_duration_{10s};
268 };
269 
270 } // namespace nav2_lifecycle_manager
271 
272 #endif // NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_HPP_
Implements service interface to transition the lifecycle nodes of Nav2 stack. It receives transition ...