ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
Public Types | Public Member Functions | List of all members
rclcpp::node_interfaces::NodeBaseInterface Class Referenceabstract

Pure virtual interface class for the NodeBase part of the Node API. More...

#include <rclcpp/node_interfaces/node_base_interface.hpp>

Inheritance diagram for rclcpp::node_interfaces::NodeBaseInterface:
Inheritance graph
[legend]

Public Types

using CallbackGroupFunction = std::function< void(rclcpp::CallbackGroup::SharedPtr)>
 

Public Member Functions

virtual RCLCPP_PUBLIC const char * get_name () const =0
 Return the name of the node. More...
 
virtual RCLCPP_PUBLIC const char * get_namespace () const =0
 Return the namespace of the node. More...
 
virtual RCLCPP_PUBLIC const char * get_fully_qualified_name () const =0
 Return the fully qualified name of the node. More...
 
virtual RCLCPP_PUBLIC rclcpp::Context::SharedPtr get_context ()=0
 Return the context of the node. More...
 
virtual RCLCPP_PUBLIC rcl_node_tget_rcl_node_handle ()=0
 Return the rcl_node_t node handle (non-const version).
 
virtual RCLCPP_PUBLIC const rcl_node_tget_rcl_node_handle () const =0
 Return the rcl_node_t node handle (const version).
 
virtual RCLCPP_PUBLIC std::shared_ptr< rcl_node_tget_shared_rcl_node_handle ()=0
 Return the rcl_node_t node handle in a std::shared_ptr. More...
 
virtual RCLCPP_PUBLIC std::shared_ptr< const rcl_node_tget_shared_rcl_node_handle () const =0
 Return the rcl_node_t node handle in a std::shared_ptr. More...
 
virtual RCLCPP_PUBLIC rclcpp::CallbackGroup::SharedPtr create_callback_group (rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node=true)=0
 Create and return a callback group.
 
virtual RCLCPP_PUBLIC rclcpp::CallbackGroup::SharedPtr get_default_callback_group ()=0
 Return the default callback group.
 
virtual RCLCPP_PUBLIC bool callback_group_in_node (rclcpp::CallbackGroup::SharedPtr group)=0
 Return true if the given callback group is associated with this node.
 
virtual RCLCPP_PUBLIC void for_each_callback_group (const CallbackGroupFunction &func)=0
 Iterate over the stored callback groups, calling the given function on each valid one. More...
 
virtual RCLCPP_PUBLIC std::atomic_bool & get_associated_with_executor_atomic ()=0
 Return the atomic bool which is used to ensure only one executor is used.
 
virtual RCLCPP_PUBLIC rclcpp::GuardConditionget_notify_guard_condition ()=0
 Return a guard condition that should be notified when the internal node state changes. More...
 
virtual RCLCPP_PUBLIC rclcpp::GuardCondition::SharedPtr get_shared_notify_guard_condition ()=0
 Return a guard condition that should be notified when the internal node state changes. More...
 
virtual RCLCPP_PUBLIC void trigger_notify_guard_condition ()=0
 Trigger the guard condition that notifies of internal node state changes. More...
 
virtual RCLCPP_PUBLIC bool get_use_intra_process_default () const =0
 Return the default preference for using intra process communication.
 
virtual RCLCPP_PUBLIC bool get_enable_topic_statistics_default () const =0
 Return the default preference for enabling topic statistics collection.
 
virtual RCLCPP_PUBLIC std::string resolve_topic_or_service_name (const std::string &name, bool is_service, bool only_expand=false) const =0
 Expand and remap a given topic or service name.
 

Detailed Description

Pure virtual interface class for the NodeBase part of the Node API.

Definition at line 38 of file node_base_interface.hpp.

Member Function Documentation

◆ for_each_callback_group()

virtual RCLCPP_PUBLIC void rclcpp::node_interfaces::NodeBaseInterface::for_each_callback_group ( const CallbackGroupFunction &  func)
pure virtual

Iterate over the stored callback groups, calling the given function on each valid one.

This method is called in a thread-safe way, and also makes sure to only call the given function on those items that are still valid.

Parameters
[in]funcThe callback function to call on each valid callback group.

Implemented in rclcpp::node_interfaces::NodeBase.

◆ get_context()

virtual RCLCPP_PUBLIC rclcpp::Context::SharedPtr rclcpp::node_interfaces::NodeBaseInterface::get_context ( )
pure virtual

Return the context of the node.

Returns
SharedPtr to the node's context.

Implemented in rclcpp::node_interfaces::NodeBase.

Referenced by rclcpp::create_timer(), rclcpp::create_wall_timer(), rclcpp::Publisher< MessageT, AllocatorT >::post_init_setup(), and rclcpp::node_interfaces::NodeGraph::wait_for_graph_change().

Here is the caller graph for this function:

◆ get_fully_qualified_name()

virtual RCLCPP_PUBLIC const char* rclcpp::node_interfaces::NodeBaseInterface::get_fully_qualified_name ( ) const
pure virtual

Return the fully qualified name of the node.

Returns
The fully qualified name of the node.

Implemented in rclcpp::node_interfaces::NodeBase.

◆ get_name()

virtual RCLCPP_PUBLIC const char* rclcpp::node_interfaces::NodeBaseInterface::get_name ( ) const
pure virtual

Return the name of the node.

Returns
The name of the node.

Implemented in rclcpp::node_interfaces::NodeBase.

◆ get_namespace()

virtual RCLCPP_PUBLIC const char* rclcpp::node_interfaces::NodeBaseInterface::get_namespace ( ) const
pure virtual

Return the namespace of the node.

Returns
The namespace of the node.

Implemented in rclcpp::node_interfaces::NodeBase.

◆ get_notify_guard_condition()

virtual RCLCPP_PUBLIC rclcpp::GuardCondition& rclcpp::node_interfaces::NodeBaseInterface::get_notify_guard_condition ( )
pure virtual

Return a guard condition that should be notified when the internal node state changes.

For example, this should be notified when a publisher is added or removed.

Returns
the GuardCondition if it is valid, else throw runtime error

Implemented in rclcpp::node_interfaces::NodeBase.

◆ get_shared_notify_guard_condition()

virtual RCLCPP_PUBLIC rclcpp::GuardCondition::SharedPtr rclcpp::node_interfaces::NodeBaseInterface::get_shared_notify_guard_condition ( )
pure virtual

Return a guard condition that should be notified when the internal node state changes.

For example, this should be notified when a publisher is added or removed.

Returns
the GuardCondition if it is valid, else nullptr

Implemented in rclcpp::node_interfaces::NodeBase.

◆ get_shared_rcl_node_handle() [1/2]

virtual RCLCPP_PUBLIC std::shared_ptr<const rcl_node_t> rclcpp::node_interfaces::NodeBaseInterface::get_shared_rcl_node_handle ( ) const
pure virtual

Return the rcl_node_t node handle in a std::shared_ptr.

This handle remains valid after the Node is destroyed. The actual rcl node is not finalized until it is out of scope everywhere.

Implemented in rclcpp::node_interfaces::NodeBase.

◆ get_shared_rcl_node_handle() [2/2]

virtual RCLCPP_PUBLIC std::shared_ptr<rcl_node_t> rclcpp::node_interfaces::NodeBaseInterface::get_shared_rcl_node_handle ( )
pure virtual

Return the rcl_node_t node handle in a std::shared_ptr.

This handle remains valid after the Node is destroyed. The actual rcl node is not finalized until it is out of scope everywhere.

Implemented in rclcpp::node_interfaces::NodeBase.

◆ trigger_notify_guard_condition()

virtual RCLCPP_PUBLIC void rclcpp::node_interfaces::NodeBaseInterface::trigger_notify_guard_condition ( )
pure virtual

Trigger the guard condition that notifies of internal node state changes.

For example, this should be notified when a publisher is added or removed.

Implemented in rclcpp::node_interfaces::NodeBase.

Referenced by rclcpp::node_interfaces::NodeTimers::add_timer(), and rclcpp::node_interfaces::NodeGraph::notify_graph_change().

Here is the caller graph for this function:

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