Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
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>
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 ¶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 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 () |
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
Definition at line 45 of file lifecycle_node.hpp.
|
inline |
A lifecycle node constructor.
node_name | Name for the node |
namespace | Namespace for the node, if any |
options | Node options |
Definition at line 58 of file lifecycle_node.hpp.
|
inline |
A lifecycle node constructor with no namespace.
node_name | Name for the node |
options | Node options |
Definition at line 86 of file lifecycle_node.hpp.
|
inline |
Create a ActionClient to call an action using.
action_name | Name of action |
callback_group | The callback group to use (if provided) |
Definition at line 243 of file lifecycle_node.hpp.
|
inline |
Create a SimpleActionServer to host with an action.
action_name | Name of action |
execute_callback | Callback function to handle action execution |
completion_callback | Callback function to handle action completion (optional) |
server_timeout | Timeout for the action server (default is 500ms) |
spin_thread | Whether to spin with a dedicated thread internally (default is false) |
realtime | Whether the action server's worker thread should have elevated |
Definition at line 222 of file lifecycle_node.hpp.
|
inline |
Create a ServiceClient to interface with a service.
service_name | Name of service |
use_internal_executor | Whether to use the internal executor (default is false) |
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().
|
inline |
Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions.
topic_name | Name of topic |
qos | QoS settings for the publisher (default is nav2::qos::StandardTopicQoS()) |
callback_group | The callback group to use (if provided) |
Definition at line 157 of file lifecycle_node.hpp.
|
inline |
Create a ServiceServer to host with a service.
service_name | Name of service |
callback | Callback function to handle service requests |
callback_group | The callback group to use (if provided) |
Definition at line 201 of file lifecycle_node.hpp.
|
inline |
Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions.
topic_name | Name of topic |
callback | Callback function to handle incoming messages |
qos | QoS settings for the subscription (default is nav2::qos::StandardTopicQoS()) |
callback_group | The callback group to use (if provided) |
Definition at line 137 of file lifecycle_node.hpp.
|
inline |
Declares or gets a parameter. If the parameter is already declared, returns its value; otherwise declares it and returns the default value.
parameter_name | Name of the parameter |
default_value | Default value of the parameter |
parameter_descriptor | Optional parameter descriptor |
Definition at line 115 of file lifecycle_node.hpp.
Referenced by nav2_bt_navigator::BtNavigator::on_configure().
|
inline |
Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine.
state | State prior to error transition |
Definition at line 275 of file lifecycle_node.hpp.
|
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().
|
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().