Nav2 Navigation Stack - kilted  kilted
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_util/node_thread.hpp"
28 #include "nav2_util/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 
36 
37 namespace nav2_lifecycle_manager
38 {
39 using namespace std::chrono_literals; // NOLINT
40 
41 using nav2_msgs::srv::ManageLifecycleNodes;
42 
44 enum NodeState
45 {
46  UNCONFIGURED,
47  ACTIVE,
48  INACTIVE,
49  FINALIZED,
50  UNKNOWN,
51 };
52 
59 class LifecycleManager : public rclcpp::Node
60 {
61 public:
66  explicit LifecycleManager(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
71 
72 protected:
73  // Callback group used by services and timers
74  rclcpp::CallbackGroup::SharedPtr callback_group_;
75  std::unique_ptr<nav2_util::NodeThread> service_thread_;
76 
77  // The services provided by this node
78  nav2_util::ServiceServer<ManageLifecycleNodes>::SharedPtr manager_srv_;
79  nav2_util::ServiceServer<std_srvs::srv::Trigger>::SharedPtr is_active_srv_;
86  void managerCallback(
87  const std::shared_ptr<rmw_request_id_t> request_header,
88  const std::shared_ptr<ManageLifecycleNodes::Request> request,
89  std::shared_ptr<ManageLifecycleNodes::Response> response);
97  void isActiveCallback(
98  const std::shared_ptr<rmw_request_id_t> request_header,
99  const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
100  std::shared_ptr<std_srvs::srv::Trigger::Response> response);
101 
102  // Support functions for the service calls
107  bool startup();
112  bool configure();
117  bool cleanup();
122  bool shutdown();
127  bool reset(bool hard_reset = false);
132  bool pause();
137  bool resume();
138 
144  void onRclPreshutdown();
145 
146  // Support function for creating service clients
150  void createLifecycleServiceClients();
151 
152  // Support function for creating service servers
156  void createLifecycleServiceServers();
157 
158  // Support functions for shutdown
162  void shutdownAllNodes();
166  void destroyLifecycleServiceClients();
167 
168  // Support function for creating bond timer
172  void createBondTimer();
173 
174  // Support function for creating bond connection
178  bool createBondConnection(const std::string & node_name);
179 
180  // Support function for killing bond connections
184  void destroyBondTimer();
185 
186  // Support function for checking on bond connections
191  void checkBondConnections();
192 
193  // Support function for checking if bond connections come back after respawn
198  void checkBondRespawnConnection();
199 
203  bool changeStateForNode(
204  const std::string & node_name,
205  std::uint8_t transition);
206 
210  bool changeStateForAllNodes(std::uint8_t transition, bool hard_change = false);
211 
212  // Convenience function to highlight the output on the console
216  void message(const std::string & msg);
217 
218  // Diagnostics functions
222  void CreateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);
223 
230  void registerRclPreshutdownCallback();
231 
235  bool isActive();
236 
237  // Timer thread to look at bond connections
238  rclcpp::TimerBase::SharedPtr init_timer_;
239  rclcpp::TimerBase::SharedPtr bond_timer_;
240  rclcpp::TimerBase::SharedPtr bond_respawn_timer_;
241  std::chrono::milliseconds bond_timeout_;
242  std::chrono::milliseconds service_timeout_;
243 
244  // A map of all nodes to check bond connection
245  std::map<std::string, std::shared_ptr<bond::Bond>> bond_map_;
246 
247  // A map of all nodes to be controlled
248  std::map<std::string, std::shared_ptr<nav2_util::LifecycleServiceClient>> node_map_;
249 
250  std::map<std::uint8_t, std::string> transition_label_map_;
251 
252  // A map of the expected transitions to primary states
253  std::unordered_map<std::uint8_t, std::uint8_t> transition_state_map_;
254 
255  // The names of the nodes to be managed, in the order of desired bring-up
256  std::vector<std::string> node_names_;
257 
258  // Whether to automatically start up the system
259  bool autostart_;
260  bool attempt_respawn_reconnection_;
261 
262  NodeState managed_nodes_state_{NodeState::UNCONFIGURED};
263  diagnostic_updater::Updater diagnostics_updater_;
264 
265  rclcpp::Time bond_respawn_start_time_{0};
266  rclcpp::Duration bond_respawn_max_duration_{10s};
267 };
268 
269 } // namespace nav2_lifecycle_manager
270 
271 #endif // NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_HPP_
Implements service interface to transition the lifecycle nodes of Nav2 stack. It receives transition ...