Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
lifecycle_node.hpp
1 // Copyright (c) 2025 Open Navigation LLC
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_ROS_COMMON__LIFECYCLE_NODE_HPP_
16 #define NAV2_ROS_COMMON__LIFECYCLE_NODE_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <thread>
21 #include <vector>
22 #include <utility>
23 #include <chrono>
24 
25 #include "lifecycle_msgs/msg/state.hpp"
26 #include "nav2_ros_common/node_utils.hpp"
27 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
28 #include "nav2_ros_common/node_thread.hpp"
29 #include "rclcpp_lifecycle/lifecycle_node.hpp"
30 #include "rclcpp/rclcpp.hpp"
31 #include "bondcpp/bond.hpp"
32 #include "bond/msg/constants.hpp"
33 #include "nav2_ros_common/interface_factories.hpp"
34 
35 namespace nav2
36 {
37 
38 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
39 using namespace std::chrono_literals; // NOLINT
40 
45 class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
46 {
47 public:
48  using SharedPtr = std::shared_ptr<nav2::LifecycleNode>;
49  using WeakPtr = std::weak_ptr<nav2::LifecycleNode>;
50  using SharedConstPointer = std::shared_ptr<const nav2::LifecycleNode>;
51 
59  const std::string & node_name,
60  const std::string & ns,
61  const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
62  : rclcpp_lifecycle::LifecycleNode(node_name, ns, options, getEnableLifecycleServices(options))
63  {
64  // server side never times out from lifecycle manager
65  this->declare_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true);
66  this->set_parameter(
67  rclcpp::Parameter(
68  bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true));
69 
70  bond_heartbeat_period = this->declare_or_get_parameter<double>("bond_heartbeat_period", 0.1);
71  bool autostart_node = this->declare_or_get_parameter("autostart_node", false);
72  if (autostart_node) {
73  autostart();
74  }
75 
76  printLifecycleNodeNotification();
77 
78  register_rcl_preshutdown_callback();
79  }
80 
87  const std::string & node_name,
88  const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
89  : nav2::LifecycleNode(node_name, "", options)
90  {}
91 
92  virtual ~LifecycleNode()
93  {
94  RCLCPP_INFO(get_logger(), "Destroying");
95 
96  runCleanups();
97 
98  if (rcl_preshutdown_cb_handle_) {
99  rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
100  context->remove_pre_shutdown_callback(*(rcl_preshutdown_cb_handle_.get()));
101  rcl_preshutdown_cb_handle_.reset();
102  }
103  }
104 
113  template<typename ParameterT>
114  inline ParameterT declare_or_get_parameter(
115  const std::string & parameter_name,
116  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
117  {
118  return nav2::declare_or_get_parameter<ParameterT>(
119  this, parameter_name, parameter_descriptor);
120  }
121 
131  template<typename ParamType>
132  inline ParamType declare_or_get_parameter(
133  const std::string & parameter_name,
134  const ParamType & default_value,
135  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
136  {
137  return nav2::declare_or_get_parameter(
138  this, parameter_name,
139  default_value, parameter_descriptor);
140  }
141 
150  template<
151  typename MessageT,
152  typename CallbackT>
153  typename nav2::Subscription<MessageT>::SharedPtr
155  const std::string & topic_name,
156  CallbackT && callback,
157  const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS(),
158  const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr)
159  {
160  return nav2::interfaces::create_subscription<MessageT>(
161  shared_from_this(), topic_name,
162  std::forward<CallbackT>(callback), qos, callback_group);
163  }
164 
172  template<typename MessageT>
173  typename nav2::Publisher<MessageT>::SharedPtr
175  const std::string & topic_name,
176  const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS(),
177  const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr)
178  {
179  auto pub = nav2::interfaces::create_publisher<MessageT>(
180  shared_from_this(), topic_name, qos, callback_group);
181  this->add_managed_entity(pub);
182 
183  // Automatically activate the publisher if the node is already active
184  if (get_current_state().id() ==
185  lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
186  {
187  pub->on_activate();
188  }
189 
190  return pub;
191  }
192 
199  template<typename ServiceT>
200  typename nav2::ServiceClient<ServiceT>::SharedPtr
202  const std::string & service_name,
203  bool use_internal_executor = false)
204  {
205  return nav2::interfaces::create_client<ServiceT>(
206  shared_from_this(), service_name, use_internal_executor);
207  }
208 
216  template<typename ServiceT>
217  typename nav2::ServiceServer<ServiceT>::SharedPtr
219  const std::string & service_name,
220  typename nav2::ServiceServer<ServiceT>::CallbackType cb,
221  rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
222  {
223  return nav2::interfaces::create_service<ServiceT>(
224  shared_from_this(), service_name, cb, callback_group);
225  }
226 
237  template<typename ActionT>
238  typename nav2::SimpleActionServer<ActionT>::SharedPtr
240  const std::string & action_name,
241  typename nav2::SimpleActionServer<ActionT>::ExecuteCallback execute_callback,
242  typename nav2::SimpleActionServer<ActionT>::CompletionCallback compl_cb = nullptr,
243  std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
244  bool spin_thread = false,
245  const bool realtime = false)
246  {
247  return nav2::interfaces::create_action_server<ActionT>(
248  shared_from_this(), action_name, execute_callback,
249  compl_cb, server_timeout, spin_thread, realtime);
250  }
251 
258  template<typename ActionT>
259  typename nav2::ActionClient<ActionT>::SharedPtr
261  const std::string & action_name,
262  rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
263  {
264  return nav2::interfaces::create_action_client<ActionT>(
265  shared_from_this(), action_name, callback_group);
266  }
267 
271  nav2::LifecycleNode::SharedPtr shared_from_this()
272  {
273  return std::static_pointer_cast<nav2::LifecycleNode>(
274  rclcpp_lifecycle::LifecycleNode::shared_from_this());
275  }
276 
280  nav2::LifecycleNode::WeakPtr weak_from_this()
281  {
282  return std::static_pointer_cast<nav2::LifecycleNode>(
283  rclcpp_lifecycle::LifecycleNode::shared_from_this());
284  }
285 
292  nav2::CallbackReturn on_error(const rclcpp_lifecycle::State & /*state*/)
293  {
294  RCLCPP_FATAL(
295  get_logger(),
296  "Lifecycle node %s does not have error state implemented", get_name());
297  return nav2::CallbackReturn::SUCCESS;
298  }
299 
303  void autostart()
304  {
305  using lifecycle_msgs::msg::State;
306  autostart_timer_ = this->create_wall_timer(
307  0s,
308  [this]() -> void {
309  autostart_timer_->cancel();
310  RCLCPP_INFO(get_logger(), "Auto-starting node: %s", this->get_name());
311  if (configure().id() != State::PRIMARY_STATE_INACTIVE) {
312  RCLCPP_ERROR(
313  get_logger(), "Auto-starting node %s failed to configure!", this->get_name());
314  return;
315  }
316  if (activate().id() != State::PRIMARY_STATE_ACTIVE) {
317  RCLCPP_ERROR(
318  get_logger(), "Auto-starting node %s failed to activate!", this->get_name());
319  }
320  });
321  }
322 
328  virtual void on_rcl_preshutdown()
329  {
330  RCLCPP_INFO(
331  get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)",
332  this->get_name());
333 
334  runCleanups();
335 
336  destroyBond();
337  }
338 
342  void createBond()
343  {
344  if (bond_heartbeat_period > 0.0) {
345  RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name());
346 
347  bond_ = std::make_shared<bond::Bond>(
348  std::string("bond"),
349  this->get_name(),
350  shared_from_this());
351 
352  bond_->setHeartbeatPeriod(bond_heartbeat_period);
353  bond_->setHeartbeatTimeout(4.0);
354  bond_->start();
355  }
356  }
357 
361  void destroyBond()
362  {
363  if (bond_heartbeat_period > 0.0) {
364  RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name());
365 
366  if (bond_) {
367  bond_.reset();
368  }
369  }
370  }
371 
372 protected:
377  {
378  RCLCPP_INFO(
379  get_logger(),
380  "\n\t%s lifecycle node launched. \n"
381  "\tWaiting on external lifecycle transitions to activate\n"
382  "\tSee https://design.ros2.org/articles/node_lifecycle.html for more information.",
383  get_name());
384  }
385 
392  {
393  rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
394 
395  rcl_preshutdown_cb_handle_ = std::make_unique<rclcpp::PreShutdownCallbackHandle>(
396  context->add_pre_shutdown_callback(
397  std::bind(&LifecycleNode::on_rcl_preshutdown, this))
398  );
399  }
400 
404  void runCleanups()
405  {
406  /*
407  * In case this lifecycle node wasn't properly shut down, do it here.
408  * We will give the user some ability to clean up properly here, but it's
409  * best effort; i.e. we aren't trying to account for all possible states.
410  */
411  if (get_current_state().id() ==
412  lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
413  {
414  this->deactivate();
415  }
416 
417  if (get_current_state().id() ==
418  lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
419  {
420  this->cleanup();
421  }
422  }
423 
424  // Connection to tell that server is still up
425  std::unique_ptr<rclcpp::PreShutdownCallbackHandle> rcl_preshutdown_cb_handle_{nullptr};
426  std::shared_ptr<bond::Bond> bond_{nullptr};
427  double bond_heartbeat_period{0.1};
428  rclcpp::TimerBase::SharedPtr autostart_timer_;
429 
430 private:
436  static bool getEnableLifecycleServices(const rclcpp::NodeOptions & options)
437  {
438  // Check if the parameter is explicitly set in NodeOptions
439  for (const auto & param : options.parameter_overrides()) {
440  if (param.get_name() == "enable_lifecycle_services") {
441  return param.as_bool();
442  }
443  }
444  // Default to true if not specified
445  return true;
446  }
447 };
448 
449 } // namespace nav2
450 
451 #endif // NAV2_ROS_COMMON__LIFECYCLE_NODE_HPP_
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
nav2::CallbackReturn on_error(const rclcpp_lifecycle::State &)
Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 nod...
void autostart()
Automatically configure and active the node.
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
void printLifecycleNodeNotification()
Print notifications for lifecycle node.
nav2::Publisher< MessageT >::SharedPtr create_publisher(const std::string &topic_name, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions.
nav2::SimpleActionServer< ActionT >::SharedPtr create_action_server(const std::string &action_name, typename nav2::SimpleActionServer< ActionT >::ExecuteCallback execute_callback, typename nav2::SimpleActionServer< ActionT >::CompletionCallback compl_cb=nullptr, std::chrono::milliseconds server_timeout=std::chrono::milliseconds(500), bool spin_thread=false, const bool realtime=false)
Create a SimpleActionServer to host with an action.
ParameterT declare_or_get_parameter(const std::string &parameter_name, const ParameterDescriptor &parameter_descriptor=ParameterDescriptor())
Declares or gets a parameter with specified type (not value). If the parameter is already declared,...
nav2::ServiceClient< ServiceT >::SharedPtr create_client(const std::string &service_name, bool use_internal_executor=false)
Create a ServiceClient to interface with a service.
void createBond()
Create bond connection to lifecycle manager.
LifecycleNode(const std::string &node_name, const std::string &ns, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A lifecycle node constructor.
virtual void on_rcl_preshutdown()
Perform preshutdown activities before our Context is shutdown. Note that this is related to our Conte...
nav2::Subscription< MessageT >::SharedPtr create_subscription(const std::string &topic_name, CallbackT &&callback, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions.
nav2::ServiceServer< ServiceT >::SharedPtr create_service(const std::string &service_name, typename nav2::ServiceServer< ServiceT >::CallbackType cb, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
Create a ServiceServer to host with a service.
nav2::LifecycleNode::WeakPtr weak_from_this()
Get a shared pointer of this.
void register_rcl_preshutdown_callback()
ParamType declare_or_get_parameter(const std::string &parameter_name, const ParamType &default_value, const ParameterDescriptor &parameter_descriptor=ParameterDescriptor())
Declares or gets a parameter. If the parameter is already declared, returns its value; otherwise decl...
nav2::ActionClient< ActionT >::SharedPtr create_action_client(const std::string &action_name, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
Create a ActionClient to call an action using.
LifecycleNode(const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A lifecycle node constructor with no namespace.
A QoS profile for standard reliable topics with a history of 10 messages.