Nav2 Navigation Stack - jazzy  jazzy
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 "rclcpp/rclcpp.hpp"
29 #include "std_srvs/srv/empty.hpp"
30 #include "nav2_msgs/srv/manage_lifecycle_nodes.hpp"
31 #include "std_srvs/srv/trigger.hpp"
32 #include "bondcpp/bond.hpp"
33 #include "diagnostic_updater/diagnostic_updater.hpp"
34 
35 
36 namespace nav2_lifecycle_manager
37 {
38 using namespace std::chrono_literals; // NOLINT
39 
40 using nav2_msgs::srv::ManageLifecycleNodes;
41 
43 enum NodeState
44 {
45  UNCONFIGURED,
46  ACTIVE,
47  INACTIVE,
48  FINALIZED,
49  UNKNOWN,
50 };
51 
58 class LifecycleManager : public rclcpp::Node
59 {
60 public:
65  explicit LifecycleManager(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
70 
71 protected:
72  // Callback group used by services and timers
73  rclcpp::CallbackGroup::SharedPtr callback_group_;
74  std::unique_ptr<nav2_util::NodeThread> service_thread_;
75 
76  // The services provided by this node
77  rclcpp::Service<ManageLifecycleNodes>::SharedPtr manager_srv_;
78  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr is_active_srv_;
85  void managerCallback(
86  const std::shared_ptr<rmw_request_id_t> request_header,
87  const std::shared_ptr<ManageLifecycleNodes::Request> request,
88  std::shared_ptr<ManageLifecycleNodes::Response> response);
96  void isActiveCallback(
97  const std::shared_ptr<rmw_request_id_t> request_header,
98  const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
99  std::shared_ptr<std_srvs::srv::Trigger::Response> response);
100 
101  // Support functions for the service calls
106  bool startup();
111  bool configure();
116  bool cleanup();
121  bool shutdown();
126  bool reset(bool hard_reset = false);
131  bool pause();
136  bool resume();
137 
143  void onRclPreshutdown();
144 
145  // Support function for creating service clients
149  void createLifecycleServiceClients();
150 
151  // Support functions for shutdown
155  void shutdownAllNodes();
159  void destroyLifecycleServiceClients();
160 
161  // Support function for creating bond timer
165  void createBondTimer();
166 
167  // Support function for creating bond connection
171  bool createBondConnection(const std::string & node_name);
172 
173  // Support function for killing bond connections
177  void destroyBondTimer();
178 
179  // Support function for checking on bond connections
184  void checkBondConnections();
185 
186  // Support function for checking if bond connections come back after respawn
191  void checkBondRespawnConnection();
192 
196  bool changeStateForNode(
197  const std::string & node_name,
198  std::uint8_t transition);
199 
203  bool changeStateForAllNodes(std::uint8_t transition, bool hard_change = false);
204 
205  // Convenience function to highlight the output on the console
209  void message(const std::string & msg);
210 
211  // Diagnostics functions
215  void CreateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);
216 
223  void registerRclPreshutdownCallback();
224 
228  bool isActive();
229 
230  // Timer thread to look at bond connections
231  rclcpp::TimerBase::SharedPtr init_timer_;
232  rclcpp::TimerBase::SharedPtr bond_timer_;
233  rclcpp::TimerBase::SharedPtr bond_respawn_timer_;
234  std::chrono::milliseconds bond_timeout_;
235 
236  // A map of all nodes to check bond connection
237  std::map<std::string, std::shared_ptr<bond::Bond>> bond_map_;
238 
239  // A map of all nodes to be controlled
240  std::map<std::string, std::shared_ptr<nav2_util::LifecycleServiceClient>> node_map_;
241 
242  std::map<std::uint8_t, std::string> transition_label_map_;
243 
244  // A map of the expected transitions to primary states
245  std::unordered_map<std::uint8_t, std::uint8_t> transition_state_map_;
246 
247  // The names of the nodes to be managed, in the order of desired bring-up
248  std::vector<std::string> node_names_;
249 
250  // Whether to automatically start up the system
251  bool autostart_;
252  bool attempt_respawn_reconnection_;
253 
254  NodeState managed_nodes_state_{NodeState::UNCONFIGURED};
255  diagnostic_updater::Updater diagnostics_updater_;
256 
257  rclcpp::Time bond_respawn_start_time_{0};
258  rclcpp::Duration bond_respawn_max_duration_{10s};
259 };
260 
261 } // namespace nav2_lifecycle_manager
262 
263 #endif // NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_HPP_
Implements service interface to transition the lifecycle nodes of Nav2 stack. It receives transition ...