rclcpp  beta1
C++ ROS Client Library API
Public Member Functions | List of all members
rclcpp::node::Node Class Reference

Node is the single point of entry for creating publishers and subscribers. More...

#include <node.hpp>

Inheritance diagram for rclcpp::node::Node:
std::enable_shared_from_this< Node >

Public Member Functions

 Node (const std::string &node_name, bool use_intra_process_comms=false)
 Create a new node with the specified name. More...
 
 Node (const std::string &node_name, rclcpp::context::Context::SharedPtr context, bool use_intra_process_comms=false)
 Create a node based on the node name and a rclcpp::context::Context. More...
 
virtual ~Node ()
 
const char * get_name () const
 Get the name of the node. More...
 
rclcpp::callback_group::CallbackGroup::SharedPtr create_callback_group (rclcpp::callback_group::CallbackGroupType group_type)
 Create and return a callback group. More...
 
const std::vector< rclcpp::callback_group::CallbackGroup::WeakPtr > & get_callback_groups () const
 Return the list of callback groups in the node. More...
 
template<typename MessageT , typename Alloc = std::allocator<void>, typename PublisherT = ::rclcpp::publisher::Publisher<MessageT, Alloc>>
std::shared_ptr< PublisherT > create_publisher (const std::string &topic_name, size_t qos_history_depth, std::shared_ptr< Alloc > allocator=nullptr)
 Create and return a Publisher. More...
 
template<typename MessageT , typename Alloc = std::allocator<void>, typename PublisherT = ::rclcpp::publisher::Publisher<MessageT, Alloc>>
std::shared_ptr< PublisherT > create_publisher (const std::string &topic_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_default, std::shared_ptr< Alloc > allocator=nullptr)
 Create and return a Publisher. More...
 
template<typename MessageT , typename CallbackT , typename Alloc = std::allocator<void>, typename SubscriptionT = rclcpp::subscription::Subscription<MessageT, Alloc>>
std::shared_ptr< SubscriptionT > create_subscription (const std::string &topic_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_default, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr, bool ignore_local_publications=false, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr msg_mem_strat=nullptr, std::shared_ptr< Alloc > allocator=nullptr)
 Create and return a Subscription. More...
 
template<typename MessageT , typename CallbackT , typename Alloc = std::allocator<void>, typename SubscriptionT = rclcpp::subscription::Subscription<MessageT, Alloc>>
std::shared_ptr< SubscriptionT > create_subscription (const std::string &topic_name, size_t qos_history_depth, CallbackT &&callback, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr, bool ignore_local_publications=false, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr msg_mem_strat=nullptr, std::shared_ptr< Alloc > allocator=nullptr)
 Create and return a Subscription. More...
 
template<typename DurationT = std::milli, typename CallbackT >
rclcpp::timer::WallTimer< CallbackT >::SharedPtr create_wall_timer (std::chrono::duration< int64_t, DurationT > period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
 Create a timer. More...
 
template<typename ServiceT >
rclcpp::client::Client< ServiceT >::SharedPtr create_client (const std::string &service_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
 
template<typename ServiceT , typename CallbackT >
rclcpp::service::Service< ServiceT >::SharedPtr create_service (const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
 
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters (const std::vector< rclcpp::parameter::ParameterVariant > &parameters)
 
rcl_interfaces::msg::SetParametersResult set_parameters_atomically (const std::vector< rclcpp::parameter::ParameterVariant > &parameters)
 
std::vector< rclcpp::parameter::ParameterVariantget_parameters (const std::vector< std::string > &names) const
 
rclcpp::parameter::ParameterVariant get_parameter (const std::string &name) const
 
bool get_parameter (const std::string &name, rclcpp::parameter::ParameterVariant &parameter) const
 
template<typename ParameterT >
bool get_parameter (const std::string &name, ParameterT &parameter) const
 
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters (const std::vector< std::string > &names) const
 
std::vector< uint8_t > get_parameter_types (const std::vector< std::string > &names) const
 
rcl_interfaces::msg::ListParametersResult list_parameters (const std::vector< std::string > &prefixes, uint64_t depth) const
 
template<typename CallbackT >
void register_param_change_callback (CallbackT &&callback)
 Register the callback for parameter changes. More...
 
std::map< std::string, std::stringget_topic_names_and_types () const
 
size_t count_publishers (const std::string &topic_name) const
 
size_t count_subscribers (const std::string &topic_name) const
 
rclcpp::event::Event::SharedPtr get_graph_event ()
 Return a graph event, which will be set anytime a graph change occurs. More...
 
void wait_for_graph_change (rclcpp::event::Event::SharedPtr event, std::chrono::nanoseconds timeout)
 Wait for a graph event to occur by waiting on an Event to become set. More...
 
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface ()
 Return the Node's internal NodeBaseInterface implementation. More...
 
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface ()
 Return the Node's internal NodeGraphInterface implementation. More...
 
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface ()
 Return the Node's internal NodeTimersInterface implementation. More...
 
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface ()
 Return the Node's internal NodeTopicsInterface implementation. More...
 
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface ()
 Return the Node's internal NodeServicesInterface implementation. More...
 
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface ()
 Return the Node's internal NodeParametersInterface implementation. More...
 
template<typename ServiceT >
client::Client< ServiceT >::SharedPtr create_client (const std::string &service_name, const rmw_qos_profile_t &qos_profile, rclcpp::callback_group::CallbackGroup::SharedPtr group)
 
- Public Member Functions inherited from std::enable_shared_from_this< Node >
enable_shared_from_this (T... args)
 
operator= (T... args)
 
shared_from_this (T... args)
 
~enable_shared_from_this (T... args)
 

Detailed Description

Node is the single point of entry for creating publishers and subscribers.

Constructor & Destructor Documentation

§ Node() [1/2]

rclcpp::node::Node::Node ( const std::string node_name,
bool  use_intra_process_comms = false 
)
explicit

Create a new node with the specified name.

Parameters
[in]node_nameName of the node.
[in]use_intra_process_commsTrue to use the optimized intra-process communication pipeline to pass messages between nodes in the same process using shared memory.

§ Node() [2/2]

rclcpp::node::Node::Node ( const std::string node_name,
rclcpp::context::Context::SharedPtr  context,
bool  use_intra_process_comms = false 
)

Create a node based on the node name and a rclcpp::context::Context.

Parameters
[in]node_nameName of the node.
[in]contextThe context for the node (usually represents the state of a process).
[in]use_intra_process_commsTrue to use the optimized intra-process communication pipeline to pass messages between nodes in the same process using shared memory.

§ ~Node()

virtual rclcpp::node::Node::~Node ( )
virtual

Member Function Documentation

§ get_name()

const char* rclcpp::node::Node::get_name ( ) const

Get the name of the node.

Returns
The name of the node.

§ create_callback_group()

rclcpp::callback_group::CallbackGroup::SharedPtr rclcpp::node::Node::create_callback_group ( rclcpp::callback_group::CallbackGroupType  group_type)

Create and return a callback group.

§ get_callback_groups()

const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr>& rclcpp::node::Node::get_callback_groups ( ) const

Return the list of callback groups in the node.

§ create_publisher() [1/2]

template<typename MessageT , typename Alloc , typename PublisherT >
std::shared_ptr< PublisherT > rclcpp::node::Node::create_publisher ( const std::string topic_name,
size_t  qos_history_depth,
std::shared_ptr< Alloc >  allocator = nullptr 
)

Create and return a Publisher.

Parameters
[in]topic_nameThe topic for this publisher to publish on.
[in]qos_history_depthThe depth of the publisher message queue.
[in]allocatorOptional custom allocator.
Returns
Shared pointer to the created publisher.

§ create_publisher() [2/2]

template<typename MessageT , typename Alloc , typename PublisherT >
std::shared_ptr< PublisherT > rclcpp::node::Node::create_publisher ( const std::string topic_name,
const rmw_qos_profile_t qos_profile = rmw_qos_profile_default,
std::shared_ptr< Alloc >  allocator = nullptr 
)

Create and return a Publisher.

Parameters
[in]topic_nameThe topic for this publisher to publish on.
[in]qos_profileThe quality of service profile to pass on to the rmw implementation.
[in]allocatorOptional custom allocator.
Returns
Shared pointer to the created publisher.

§ create_subscription() [1/2]

template<typename MessageT , typename CallbackT , typename Alloc , typename SubscriptionT >
std::shared_ptr< SubscriptionT > rclcpp::node::Node::create_subscription ( const std::string topic_name,
CallbackT &&  callback,
const rmw_qos_profile_t qos_profile = rmw_qos_profile_default,
rclcpp::callback_group::CallbackGroup::SharedPtr  group = nullptr,
bool  ignore_local_publications = false,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr  msg_mem_strat = nullptr,
std::shared_ptr< Alloc >  allocator = nullptr 
)

Create and return a Subscription.

Parameters
[in]topic_nameThe topic to subscribe on.
[in]callbackThe user-defined callback function.
[in]qos_profileThe quality of service profile to pass on to the rmw implementation.
[in]groupThe callback group for this subscription. NULL for no callback group.
[in]ignore_local_publicationsTrue to ignore local publications.
[in]msg_mem_stratThe message memory strategy to use for allocating messages.
[in]allocatorOptional custom allocator.
Returns
Shared pointer to the created subscription.

§ create_subscription() [2/2]

template<typename MessageT , typename CallbackT , typename Alloc , typename SubscriptionT >
std::shared_ptr< SubscriptionT > rclcpp::node::Node::create_subscription ( const std::string topic_name,
size_t  qos_history_depth,
CallbackT &&  callback,
rclcpp::callback_group::CallbackGroup::SharedPtr  group = nullptr,
bool  ignore_local_publications = false,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy< MessageT, Alloc >::SharedPtr  msg_mem_strat = nullptr,
std::shared_ptr< Alloc >  allocator = nullptr 
)

Create and return a Subscription.

Parameters
[in]topic_nameThe topic to subscribe on.
[in]qos_history_depthThe depth of the subscription's incoming message queue.
[in]callbackThe user-defined callback function.
[in]groupThe callback group for this subscription. NULL for no callback group.
[in]ignore_local_publicationsTrue to ignore local publications.
[in]msg_mem_stratThe message memory strategy to use for allocating messages.
[in]allocatorOptional custom allocator.
Returns
Shared pointer to the created subscription.

§ create_wall_timer()

template<typename DurationT , typename CallbackT >
rclcpp::timer::WallTimer< CallbackT >::SharedPtr rclcpp::node::Node::create_wall_timer ( std::chrono::duration< int64_t, DurationT >  period,
CallbackT  callback,
rclcpp::callback_group::CallbackGroup::SharedPtr  group = nullptr 
)

Create a timer.

Parameters
[in]periodTime interval between triggers of the callback.
[in]callbackUser-defined callback function.
[in]groupCallback group to execute this timer's callback in.

§ create_client() [1/2]

template<typename ServiceT >
rclcpp::client::Client<ServiceT>::SharedPtr rclcpp::node::Node::create_client ( const std::string service_name,
const rmw_qos_profile_t qos_profile = rmw_qos_profile_services_default,
rclcpp::callback_group::CallbackGroup::SharedPtr  group = nullptr 
)

§ create_service()

template<typename ServiceT , typename CallbackT >
rclcpp::service::Service< ServiceT >::SharedPtr rclcpp::node::Node::create_service ( const std::string service_name,
CallbackT &&  callback,
const rmw_qos_profile_t qos_profile = rmw_qos_profile_services_default,
rclcpp::callback_group::CallbackGroup::SharedPtr  group = nullptr 
)

§ set_parameters()

std::vector<rcl_interfaces::msg::SetParametersResult> rclcpp::node::Node::set_parameters ( const std::vector< rclcpp::parameter::ParameterVariant > &  parameters)

§ set_parameters_atomically()

rcl_interfaces::msg::SetParametersResult rclcpp::node::Node::set_parameters_atomically ( const std::vector< rclcpp::parameter::ParameterVariant > &  parameters)

§ get_parameters()

std::vector<rclcpp::parameter::ParameterVariant> rclcpp::node::Node::get_parameters ( const std::vector< std::string > &  names) const

§ get_parameter() [1/3]

rclcpp::parameter::ParameterVariant rclcpp::node::Node::get_parameter ( const std::string name) const

§ get_parameter() [2/3]

bool rclcpp::node::Node::get_parameter ( const std::string name,
rclcpp::parameter::ParameterVariant parameter 
) const

§ get_parameter() [3/3]

template<typename ParameterT >
bool rclcpp::node::Node::get_parameter ( const std::string name,
ParameterT &  parameter 
) const

§ describe_parameters()

std::vector<rcl_interfaces::msg::ParameterDescriptor> rclcpp::node::Node::describe_parameters ( const std::vector< std::string > &  names) const

§ get_parameter_types()

std::vector<uint8_t> rclcpp::node::Node::get_parameter_types ( const std::vector< std::string > &  names) const

§ list_parameters()

rcl_interfaces::msg::ListParametersResult rclcpp::node::Node::list_parameters ( const std::vector< std::string > &  prefixes,
uint64_t  depth 
) const

§ register_param_change_callback()

template<typename CallbackT >
void rclcpp::node::Node::register_param_change_callback ( CallbackT &&  callback)

Register the callback for parameter changes.

Parameters
[in]callbackUser defined callback function. It is expected to atomically set parameters.
Note
Repeated invocations of this function will overwrite previous callbacks

§ get_topic_names_and_types()

std::map<std::string, std::string> rclcpp::node::Node::get_topic_names_and_types ( ) const

§ count_publishers()

size_t rclcpp::node::Node::count_publishers ( const std::string topic_name) const

§ count_subscribers()

size_t rclcpp::node::Node::count_subscribers ( const std::string topic_name) const

§ get_graph_event()

rclcpp::event::Event::SharedPtr rclcpp::node::Node::get_graph_event ( )

Return a graph event, which will be set anytime a graph change occurs.

§ wait_for_graph_change()

void rclcpp::node::Node::wait_for_graph_change ( rclcpp::event::Event::SharedPtr  event,
std::chrono::nanoseconds  timeout 
)

Wait for a graph event to occur by waiting on an Event to become set.

The given Event must be acquire through the get_graph_event() method.

Exceptions
InvalidEventErrorif the given event is nullptr
EventNotRegisteredErrorif the given event was not acquired with get_graph_event().

§ get_node_base_interface()

rclcpp::node_interfaces::NodeBaseInterface::SharedPtr rclcpp::node::Node::get_node_base_interface ( )

Return the Node's internal NodeBaseInterface implementation.

§ get_node_graph_interface()

rclcpp::node_interfaces::NodeGraphInterface::SharedPtr rclcpp::node::Node::get_node_graph_interface ( )

Return the Node's internal NodeGraphInterface implementation.

§ get_node_timers_interface()

rclcpp::node_interfaces::NodeTimersInterface::SharedPtr rclcpp::node::Node::get_node_timers_interface ( )

Return the Node's internal NodeTimersInterface implementation.

§ get_node_topics_interface()

rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr rclcpp::node::Node::get_node_topics_interface ( )

Return the Node's internal NodeTopicsInterface implementation.

§ get_node_services_interface()

rclcpp::node_interfaces::NodeServicesInterface::SharedPtr rclcpp::node::Node::get_node_services_interface ( )

Return the Node's internal NodeServicesInterface implementation.

§ get_node_parameters_interface()

rclcpp::node_interfaces::NodeParametersInterface::SharedPtr rclcpp::node::Node::get_node_parameters_interface ( )

Return the Node's internal NodeParametersInterface implementation.

§ create_client() [2/2]

template<typename ServiceT >
client::Client<ServiceT>::SharedPtr rclcpp::node::Node::create_client ( const std::string service_name,
const rmw_qos_profile_t qos_profile,
rclcpp::callback_group::CallbackGroup::SharedPtr  group 
)

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