Nav2 Navigation Stack - humble  humble
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;
47 class LifecycleManager : public rclcpp::Node
48 {
49 public:
54  explicit LifecycleManager(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
59 
60 protected:
61  // Callback group used by services and timers
62  rclcpp::CallbackGroup::SharedPtr callback_group_;
63  std::unique_ptr<nav2_util::NodeThread> service_thread_;
64 
65  // The services provided by this node
66  rclcpp::Service<ManageLifecycleNodes>::SharedPtr manager_srv_;
67  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr is_active_srv_;
74  void managerCallback(
75  const std::shared_ptr<rmw_request_id_t> request_header,
76  const std::shared_ptr<ManageLifecycleNodes::Request> request,
77  std::shared_ptr<ManageLifecycleNodes::Response> response);
85  void isActiveCallback(
86  const std::shared_ptr<rmw_request_id_t> request_header,
87  const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
88  std::shared_ptr<std_srvs::srv::Trigger::Response> response);
89 
90  // Support functions for the service calls
95  bool startup();
100  bool shutdown();
105  bool reset(bool hard_reset = false);
110  bool pause();
115  bool resume();
116 
122  void onRclPreshutdown();
123 
124  // Support function for creating service clients
128  void createLifecycleServiceClients();
129 
130  // Support functions for shutdown
134  void shutdownAllNodes();
138  void destroyLifecycleServiceClients();
139 
140  // Support function for creating bond timer
144  void createBondTimer();
145 
146  // Support function for creating bond connection
150  bool createBondConnection(const std::string & node_name);
151 
152  // Support function for killing bond connections
156  void destroyBondTimer();
157 
158  // Support function for checking on bond connections
163  void checkBondConnections();
164 
165  // Support function for checking if bond connections come back after respawn
170  void checkBondRespawnConnection();
171 
175  bool changeStateForNode(
176  const std::string & node_name,
177  std::uint8_t transition);
178 
182  bool changeStateForAllNodes(std::uint8_t transition, bool hard_change = false);
183 
184  // Convenience function to highlight the output on the console
188  void message(const std::string & msg);
189 
190  // Diagnostics functions
194  void CreateActiveDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);
195 
202  void registerRclPreshutdownCallback();
203 
204  // Timer thread to look at bond connections
205  rclcpp::TimerBase::SharedPtr init_timer_;
206  rclcpp::TimerBase::SharedPtr bond_timer_;
207  rclcpp::TimerBase::SharedPtr bond_respawn_timer_;
208  std::chrono::milliseconds bond_timeout_;
209 
210  // A map of all nodes to check bond connection
211  std::map<std::string, std::shared_ptr<bond::Bond>> bond_map_;
212 
213  // A map of all nodes to be controlled
214  std::map<std::string, std::shared_ptr<nav2_util::LifecycleServiceClient>> node_map_;
215 
216  std::map<std::uint8_t, std::string> transition_label_map_;
217 
218  // A map of the expected transitions to primary states
219  std::unordered_map<std::uint8_t, std::uint8_t> transition_state_map_;
220 
221  // The names of the nodes to be managed, in the order of desired bring-up
222  std::vector<std::string> node_names_;
223 
224  // Whether to automatically start up the system
225  bool autostart_;
226  bool attempt_respawn_reconnection_;
227 
228  bool system_active_{false};
229  diagnostic_updater::Updater diagnostics_updater_;
230 
231  rclcpp::Time bond_respawn_start_time_{0};
232  rclcpp::Duration bond_respawn_max_duration_{10s};
233 };
234 
235 } // namespace nav2_lifecycle_manager
236 
237 #endif // NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_HPP_
Implements service interface to transition the lifecycle nodes of Nav2 stack. It receives transition ...