Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2::LifecycleNode Class Reference

A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters. More...

#include <nav2_ros_common/include/nav2_ros_common/lifecycle_node.hpp>

Inheritance diagram for nav2::LifecycleNode:
Inheritance graph
[legend]
Collaboration diagram for nav2::LifecycleNode:
Collaboration graph
[legend]

Public Types

using SharedPtr = std::shared_ptr< nav2::LifecycleNode >
 
using WeakPtr = std::weak_ptr< nav2::LifecycleNode >
 
using SharedConstPointer = std::shared_ptr< const nav2::LifecycleNode >
 

Public Member Functions

 LifecycleNode (const std::string &node_name, const std::string &ns, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor. More...
 
 LifecycleNode (const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor with no namespace. More...
 
template<typename ParamType >
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 declares it and returns the default value. More...
 
template<typename MessageT , typename CallbackT >
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. More...
 
template<typename MessageT >
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. More...
 
template<typename ServiceT >
nav2::ServiceClient< ServiceT >::SharedPtr create_client (const std::string &service_name, bool use_internal_executor=false)
 Create a ServiceClient to interface with a service. More...
 
template<typename ServiceT >
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. More...
 
template<typename ActionT >
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. More...
 
template<typename ActionT >
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. More...
 
nav2::LifecycleNode::SharedPtr shared_from_this ()
 Get a shared pointer of this.
 
nav2::LifecycleNode::WeakPtr weak_from_this ()
 Get a shared pointer of this.
 
nav2::CallbackReturn on_error (const rclcpp_lifecycle::State &)
 Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More...
 
void autostart ()
 Automatically configure and active the node.
 
virtual void on_rcl_preshutdown ()
 Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context's shutdown sequence, not the lifecycle node state machine.
 
void createBond ()
 Create bond connection to lifecycle manager.
 
void destroyBond ()
 Destroy bond connection to lifecycle manager.
 

Protected Member Functions

void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 

Protected Attributes

std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::shared_ptr< bond::Bond > bond_ {nullptr}
 
double bond_heartbeat_period {0.1}
 
rclcpp::TimerBase::SharedPtr autostart_timer_
 

Detailed Description

A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.

Definition at line 45 of file lifecycle_node.hpp.

Constructor & Destructor Documentation

◆ LifecycleNode() [1/2]

nav2::LifecycleNode::LifecycleNode ( const std::string &  node_name,
const std::string &  ns,
const rclcpp::NodeOptions &  options = rclcpp::NodeOptions() 
)
inline

A lifecycle node constructor.

Parameters
node_nameName for the node
namespaceNamespace for the node, if any
optionsNode options

Definition at line 58 of file lifecycle_node.hpp.

◆ LifecycleNode() [2/2]

nav2::LifecycleNode::LifecycleNode ( const std::string &  node_name,
const rclcpp::NodeOptions &  options = rclcpp::NodeOptions() 
)
inline

A lifecycle node constructor with no namespace.

Parameters
node_nameName for the node
optionsNode options

Definition at line 86 of file lifecycle_node.hpp.

Member Function Documentation

◆ create_action_client()

template<typename ActionT >
nav2::ActionClient<ActionT>::SharedPtr nav2::LifecycleNode::create_action_client ( const std::string &  action_name,
rclcpp::CallbackGroup::SharedPtr  callback_group = nullptr 
)
inline

Create a ActionClient to call an action using.

Parameters
action_nameName of action
callback_groupThe callback group to use (if provided)
Returns
A shared pointer to the created nav2::ActionClient

Definition at line 243 of file lifecycle_node.hpp.

◆ create_action_server()

template<typename ActionT >
nav2::SimpleActionServer<ActionT>::SharedPtr nav2::LifecycleNode::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 
)
inline

Create a SimpleActionServer to host with an action.

Parameters
action_nameName of action
execute_callbackCallback function to handle action execution
completion_callbackCallback function to handle action completion (optional)
server_timeoutTimeout for the action server (default is 500ms)
spin_threadWhether to spin with a dedicated thread internally (default is false)
realtimeWhether the action server's worker thread should have elevated
Returns
A shared pointer to the created nav2::SimpleActionServer

Definition at line 222 of file lifecycle_node.hpp.

◆ create_client()

template<typename ServiceT >
nav2::ServiceClient<ServiceT>::SharedPtr nav2::LifecycleNode::create_client ( const std::string &  service_name,
bool  use_internal_executor = false 
)
inline

Create a ServiceClient to interface with a service.

Parameters
service_nameName of service
use_internal_executorWhether to use the internal executor (default is false)
Returns
A shared pointer to the created nav2::ServiceClient

Definition at line 184 of file lifecycle_node.hpp.

Referenced by nav2_simple_commander.robot_navigator.BasicNavigator::lifecycleShutdown(), and nav2_simple_commander.robot_navigator.BasicNavigator::lifecycleStartup().

Here is the caller graph for this function:

◆ create_publisher()

template<typename MessageT >
nav2::Publisher<MessageT>::SharedPtr nav2::LifecycleNode::create_publisher ( const std::string &  topic_name,
const rclcpp::QoS &  qos = nav2::qos::StandardTopicQoS(),
const rclcpp::CallbackGroup::SharedPtr &  callback_group = nullptr 
)
inline

Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions.

Parameters
topic_nameName of topic
qosQoS settings for the publisher (default is nav2::qos::StandardTopicQoS())
callback_groupThe callback group to use (if provided)
Returns
A shared pointer to the created nav2::Publisher

Definition at line 157 of file lifecycle_node.hpp.

◆ create_service()

template<typename ServiceT >
nav2::ServiceServer<ServiceT>::SharedPtr nav2::LifecycleNode::create_service ( const std::string &  service_name,
typename nav2::ServiceServer< ServiceT >::CallbackType  cb,
rclcpp::CallbackGroup::SharedPtr  callback_group = nullptr 
)
inline

Create a ServiceServer to host with a service.

Parameters
service_nameName of service
callbackCallback function to handle service requests
callback_groupThe callback group to use (if provided)
Returns
A shared pointer to the created nav2::ServiceServer

Definition at line 201 of file lifecycle_node.hpp.

◆ create_subscription()

template<typename MessageT , typename CallbackT >
nav2::Subscription<MessageT>::SharedPtr nav2::LifecycleNode::create_subscription ( const std::string &  topic_name,
CallbackT &&  callback,
const rclcpp::QoS &  qos = nav2::qos::StandardTopicQoS(),
const rclcpp::CallbackGroup::SharedPtr &  callback_group = nullptr 
)
inline

Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions.

Parameters
topic_nameName of topic
callbackCallback function to handle incoming messages
qosQoS settings for the subscription (default is nav2::qos::StandardTopicQoS())
callback_groupThe callback group to use (if provided)
Returns
A shared pointer to the created nav2::Subscription

Definition at line 137 of file lifecycle_node.hpp.

◆ declare_or_get_parameter()

template<typename ParamType >
ParamType nav2::LifecycleNode::declare_or_get_parameter ( const std::string &  parameter_name,
const ParamType &  default_value,
const ParameterDescriptor &  parameter_descriptor = ParameterDescriptor() 
)
inline

Declares or gets a parameter. If the parameter is already declared, returns its value; otherwise declares it and returns the default value.

Parameters
parameter_nameName of the parameter
default_valueDefault value of the parameter
parameter_descriptorOptional parameter descriptor
Returns
The value of the param from the override if existent, otherwise the default value.

Definition at line 115 of file lifecycle_node.hpp.

Referenced by nav2_bt_navigator::BtNavigator::on_configure().

Here is the caller graph for this function:

◆ on_error()

nav2::CallbackReturn nav2::LifecycleNode::on_error ( const rclcpp_lifecycle::State &  )
inline

Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine.

Parameters
stateState prior to error transition
Returns
Return type for success or failed transition to error state

Definition at line 275 of file lifecycle_node.hpp.

◆ register_rcl_preshutdown_callback()

void nav2::LifecycleNode::register_rcl_preshutdown_callback ( )
inlineprotected

Register our preshutdown callback for this Node's rcl Context. The callback fires before this Node's Context is shutdown. Note this is not directly related to the lifecycle state machine.

Definition at line 374 of file lifecycle_node.hpp.

References on_rcl_preshutdown().

Here is the call graph for this function:

◆ runCleanups()

void nav2::LifecycleNode::runCleanups ( )
inlineprotected

Run some common cleanup steps shared between rcl preshutdown and destruction.

Definition at line 387 of file lifecycle_node.hpp.

Referenced by nav2_costmap_2d::Costmap2DROS::on_rcl_preshutdown().

Here is the caller graph for this function:

The documentation for this class was generated from the following file: