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 
114  template<typename ParamType>
115  inline ParamType declare_or_get_parameter(
116  const std::string & parameter_name,
117  const ParamType & default_value,
118  const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
119  {
120  return nav2::declare_or_get_parameter(
121  this, parameter_name,
122  default_value, parameter_descriptor);
123  }
124 
133  template<
134  typename MessageT,
135  typename CallbackT>
136  typename nav2::Subscription<MessageT>::SharedPtr
138  const std::string & topic_name,
139  CallbackT && callback,
140  const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS(),
141  const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr)
142  {
143  return nav2::interfaces::create_subscription<MessageT>(
144  shared_from_this(), topic_name,
145  std::forward<CallbackT>(callback), qos, callback_group);
146  }
147 
155  template<typename MessageT>
156  typename nav2::Publisher<MessageT>::SharedPtr
158  const std::string & topic_name,
159  const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS(),
160  const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr)
161  {
162  auto pub = nav2::interfaces::create_publisher<MessageT>(
163  shared_from_this(), topic_name, qos, callback_group);
164  this->add_managed_entity(pub);
165 
166  // Automatically activate the publisher if the node is already active
167  if (get_current_state().id() ==
168  lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
169  {
170  pub->on_activate();
171  }
172 
173  return pub;
174  }
175 
182  template<typename ServiceT>
183  typename nav2::ServiceClient<ServiceT>::SharedPtr
185  const std::string & service_name,
186  bool use_internal_executor = false)
187  {
188  return nav2::interfaces::create_client<ServiceT>(
189  shared_from_this(), service_name, use_internal_executor);
190  }
191 
199  template<typename ServiceT>
200  typename nav2::ServiceServer<ServiceT>::SharedPtr
202  const std::string & service_name,
203  typename nav2::ServiceServer<ServiceT>::CallbackType cb,
204  rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
205  {
206  return nav2::interfaces::create_service<ServiceT>(
207  shared_from_this(), service_name, cb, callback_group);
208  }
209 
220  template<typename ActionT>
221  typename nav2::SimpleActionServer<ActionT>::SharedPtr
223  const std::string & action_name,
224  typename nav2::SimpleActionServer<ActionT>::ExecuteCallback execute_callback,
225  typename nav2::SimpleActionServer<ActionT>::CompletionCallback compl_cb = nullptr,
226  std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
227  bool spin_thread = false,
228  const bool realtime = false)
229  {
230  return nav2::interfaces::create_action_server<ActionT>(
231  shared_from_this(), action_name, execute_callback,
232  compl_cb, server_timeout, spin_thread, realtime);
233  }
234 
241  template<typename ActionT>
242  typename nav2::ActionClient<ActionT>::SharedPtr
244  const std::string & action_name,
245  rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
246  {
247  return nav2::interfaces::create_action_client<ActionT>(
248  shared_from_this(), action_name, callback_group);
249  }
250 
254  nav2::LifecycleNode::SharedPtr shared_from_this()
255  {
256  return std::static_pointer_cast<nav2::LifecycleNode>(
257  rclcpp_lifecycle::LifecycleNode::shared_from_this());
258  }
259 
263  nav2::LifecycleNode::WeakPtr weak_from_this()
264  {
265  return std::static_pointer_cast<nav2::LifecycleNode>(
266  rclcpp_lifecycle::LifecycleNode::shared_from_this());
267  }
268 
275  nav2::CallbackReturn on_error(const rclcpp_lifecycle::State & /*state*/)
276  {
277  RCLCPP_FATAL(
278  get_logger(),
279  "Lifecycle node %s does not have error state implemented", get_name());
280  return nav2::CallbackReturn::SUCCESS;
281  }
282 
286  void autostart()
287  {
288  using lifecycle_msgs::msg::State;
289  autostart_timer_ = this->create_wall_timer(
290  0s,
291  [this]() -> void {
292  autostart_timer_->cancel();
293  RCLCPP_INFO(get_logger(), "Auto-starting node: %s", this->get_name());
294  if (configure().id() != State::PRIMARY_STATE_INACTIVE) {
295  RCLCPP_ERROR(
296  get_logger(), "Auto-starting node %s failed to configure!", this->get_name());
297  return;
298  }
299  if (activate().id() != State::PRIMARY_STATE_ACTIVE) {
300  RCLCPP_ERROR(
301  get_logger(), "Auto-starting node %s failed to activate!", this->get_name());
302  }
303  });
304  }
305 
311  virtual void on_rcl_preshutdown()
312  {
313  RCLCPP_INFO(
314  get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)",
315  this->get_name());
316 
317  runCleanups();
318 
319  destroyBond();
320  }
321 
325  void createBond()
326  {
327  if (bond_heartbeat_period > 0.0) {
328  RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name());
329 
330  bond_ = std::make_shared<bond::Bond>(
331  std::string("bond"),
332  this->get_name(),
333  shared_from_this());
334 
335  bond_->setHeartbeatPeriod(bond_heartbeat_period);
336  bond_->setHeartbeatTimeout(4.0);
337  bond_->start();
338  }
339  }
340 
344  void destroyBond()
345  {
346  if (bond_heartbeat_period > 0.0) {
347  RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name());
348 
349  if (bond_) {
350  bond_.reset();
351  }
352  }
353  }
354 
355 protected:
360  {
361  RCLCPP_INFO(
362  get_logger(),
363  "\n\t%s lifecycle node launched. \n"
364  "\tWaiting on external lifecycle transitions to activate\n"
365  "\tSee https://design.ros2.org/articles/node_lifecycle.html for more information.",
366  get_name());
367  }
368 
375  {
376  rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
377 
378  rcl_preshutdown_cb_handle_ = std::make_unique<rclcpp::PreShutdownCallbackHandle>(
379  context->add_pre_shutdown_callback(
380  std::bind(&LifecycleNode::on_rcl_preshutdown, this))
381  );
382  }
383 
387  void runCleanups()
388  {
389  /*
390  * In case this lifecycle node wasn't properly shut down, do it here.
391  * We will give the user some ability to clean up properly here, but it's
392  * best effort; i.e. we aren't trying to account for all possible states.
393  */
394  if (get_current_state().id() ==
395  lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
396  {
397  this->deactivate();
398  }
399 
400  if (get_current_state().id() ==
401  lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
402  {
403  this->cleanup();
404  }
405  }
406 
407  // Connection to tell that server is still up
408  std::unique_ptr<rclcpp::PreShutdownCallbackHandle> rcl_preshutdown_cb_handle_{nullptr};
409  std::shared_ptr<bond::Bond> bond_{nullptr};
410  double bond_heartbeat_period{0.1};
411  rclcpp::TimerBase::SharedPtr autostart_timer_;
412 
413 private:
419  static bool getEnableLifecycleServices(const rclcpp::NodeOptions & options)
420  {
421  // Check if the parameter is explicitly set in NodeOptions
422  for (const auto & param : options.parameter_overrides()) {
423  if (param.get_name() == "enable_lifecycle_services") {
424  return param.as_bool();
425  }
426  }
427  // Default to true if not specified
428  return true;
429  }
430 };
431 
432 } // namespace nav2
433 
434 #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.
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.