15 #ifndef NAV2_ROS_COMMON__LIFECYCLE_NODE_HPP_
16 #define NAV2_ROS_COMMON__LIFECYCLE_NODE_HPP_
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"
38 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
39 using namespace std::chrono_literals;
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>;
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))
65 this->declare_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM,
true);
68 bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM,
true));
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);
76 printLifecycleNodeNotification();
78 register_rcl_preshutdown_callback();
87 const std::string & node_name,
88 const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
94 RCLCPP_INFO(get_logger(),
"Destroying");
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();
113 template<
typename ParameterT>
115 const std::string & parameter_name,
116 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
118 return nav2::declare_or_get_parameter<ParameterT>(
119 this, parameter_name, parameter_descriptor);
131 template<
typename ParamType>
133 const std::string & parameter_name,
134 const ParamType & default_value,
135 const ParameterDescriptor & parameter_descriptor = ParameterDescriptor())
137 return nav2::declare_or_get_parameter(
138 this, parameter_name,
139 default_value, parameter_descriptor);
153 typename nav2::Subscription<MessageT>::SharedPtr
155 const std::string & topic_name,
156 CallbackT && callback,
158 const rclcpp::CallbackGroup::SharedPtr & callback_group =
nullptr)
160 return nav2::interfaces::create_subscription<MessageT>(
161 shared_from_this(), topic_name,
162 std::forward<CallbackT>(callback), qos, callback_group);
172 template<
typename MessageT>
173 typename nav2::Publisher<MessageT>::SharedPtr
175 const std::string & topic_name,
177 const rclcpp::CallbackGroup::SharedPtr & callback_group =
nullptr)
179 auto pub = nav2::interfaces::create_publisher<MessageT>(
180 shared_from_this(), topic_name, qos, callback_group);
181 this->add_managed_entity(pub);
184 if (get_current_state().
id() ==
185 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
199 template<
typename ServiceT>
200 typename nav2::ServiceClient<ServiceT>::SharedPtr
202 const std::string & service_name,
203 bool use_internal_executor =
false)
205 return nav2::interfaces::create_client<ServiceT>(
206 shared_from_this(), service_name, use_internal_executor);
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)
223 return nav2::interfaces::create_service<ServiceT>(
224 shared_from_this(), service_name, cb, callback_group);
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)
247 return nav2::interfaces::create_action_server<ActionT>(
248 shared_from_this(), action_name, execute_callback,
249 compl_cb, server_timeout, spin_thread, realtime);
258 template<
typename ActionT>
259 typename nav2::ActionClient<ActionT>::SharedPtr
261 const std::string & action_name,
262 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr)
264 return nav2::interfaces::create_action_client<ActionT>(
265 shared_from_this(), action_name, callback_group);
273 return std::static_pointer_cast<nav2::LifecycleNode>(
274 rclcpp_lifecycle::LifecycleNode::shared_from_this());
282 return std::static_pointer_cast<nav2::LifecycleNode>(
283 rclcpp_lifecycle::LifecycleNode::shared_from_this());
292 nav2::CallbackReturn
on_error(
const rclcpp_lifecycle::State & )
296 "Lifecycle node %s does not have error state implemented", get_name());
297 return nav2::CallbackReturn::SUCCESS;
305 using lifecycle_msgs::msg::State;
306 autostart_timer_ = this->create_wall_timer(
309 autostart_timer_->cancel();
310 RCLCPP_INFO(get_logger(),
"Auto-starting node: %s", this->get_name());
311 if (configure().
id() != State::PRIMARY_STATE_INACTIVE) {
313 get_logger(),
"Auto-starting node %s failed to configure!", this->get_name());
316 if (activate().
id() != State::PRIMARY_STATE_ACTIVE) {
318 get_logger(),
"Auto-starting node %s failed to activate!", this->get_name());
331 get_logger(),
"Running Nav2 LifecycleNode rcl preshutdown (%s)",
344 if (bond_heartbeat_period > 0.0) {
345 RCLCPP_INFO(get_logger(),
"Creating bond (%s) to lifecycle manager.", this->get_name());
347 bond_ = std::make_shared<bond::Bond>(
352 bond_->setHeartbeatPeriod(bond_heartbeat_period);
353 bond_->setHeartbeatTimeout(4.0);
363 if (bond_heartbeat_period > 0.0) {
364 RCLCPP_INFO(get_logger(),
"Destroying bond (%s) to lifecycle manager.", this->get_name());
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.",
393 rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
395 rcl_preshutdown_cb_handle_ = std::make_unique<rclcpp::PreShutdownCallbackHandle>(
396 context->add_pre_shutdown_callback(
411 if (get_current_state().
id() ==
412 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
417 if (get_current_state().
id() ==
418 lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
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_;
436 static bool getEnableLifecycleServices(
const rclcpp::NodeOptions & options)
439 for (
const auto & param : options.parameter_overrides()) {
440 if (param.get_name() ==
"enable_lifecycle_services") {
441 return param.as_bool();
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 ¶meter_name, const ParameterDescriptor ¶meter_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 ¶meter_name, const ParamType &default_value, const ParameterDescriptor ¶meter_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.