rclcpp
master
C++ ROS Client Library API
|
Node is the single point of entry for creating publishers and subscribers. More...
#include <node.hpp>
Public Member Functions | |
Node (const std::string &node_name, const std::string &namespace_="", bool use_intra_process_comms=false) | |
Create a new node with the specified name. More... | |
Node (const std::string &node_name, const std::string &namespace_, rclcpp::Context::SharedPtr context, const std::vector< std::string > &arguments, const std::vector< Parameter > &initial_parameters, bool use_global_arguments=true, bool use_intra_process_comms=false, bool start_parameter_services=true) | |
Create a node based on the node name and a rclcpp::Context. More... | |
virtual | ~Node () |
const char * | get_name () const |
Get the name of the node. More... | |
const char * | get_namespace () const |
Get the namespace of the node. More... | |
rclcpp::Logger | get_logger () const |
Get the logger 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<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<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< typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, 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< typename rclcpp::subscription_traits::has_message_type< CallbackT >::type, 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< typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>> | |
std::shared_ptr< SubscriptionT > | create_subscription (const std::string &topic_name, CallbackT &&callback, size_t qos_history_depth, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr, bool ignore_local_publications=false, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< typename rclcpp::subscription_traits::has_message_type< CallbackT >::type, 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::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< 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< 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 > ¶meters) |
rcl_interfaces::msg::SetParametersResult | set_parameters_atomically (const std::vector< rclcpp::Parameter > ¶meters) |
template<typename ParameterT > | |
void | set_parameter_if_not_set (const std::string &name, const ParameterT &value) |
std::vector< rclcpp::Parameter > | get_parameters (const std::vector< std::string > &names) const |
rclcpp::Parameter | get_parameter (const std::string &name) const |
bool | get_parameter (const std::string &name, rclcpp::Parameter ¶meter) const |
template<typename ParameterT > | |
bool | get_parameter (const std::string &name, ParameterT ¶meter) const |
Assign the value of the parameter if set into the parameter argument. More... | |
template<typename ParameterT > | |
bool | get_parameter_or (const std::string &name, ParameterT &value, const ParameterT &alternative_value) const |
Get the parameter value, or the "alternative value" if not set, and assign it to "value". More... | |
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::vector< std::string > > | get_topic_names_and_types () const |
std::map< std::string, std::vector< std::string > > | get_service_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::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::SharedPtr event, std::chrono::nanoseconds timeout) |
Wait for a graph event to occur by waiting on an Event to become set. More... | |
rclcpp::Clock::SharedPtr | get_clock () |
Time | now () |
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr | get_node_base_interface () |
Return the Node's internal NodeBaseInterface implementation. More... | |
rclcpp::node_interfaces::NodeClockInterface::SharedPtr | get_node_clock_interface () |
Return the Node's internal NodeClockInterface 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< 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 > | |
T | enable_shared_from_this (T... args) |
T | operator= (T... args) |
T | shared_from_this (T... args) |
T | ~enable_shared_from_this (T... args) |
Node is the single point of entry for creating publishers and subscribers.
|
explicit |
Create a new node with the specified name.
[in] | node_name | Name of the node. |
[in] | namespace_ | Namespace of the node. |
[in] | use_intra_process_comms | True to use the optimized intra-process communication pipeline to pass messages between nodes in the same process using shared memory. |
rclcpp::Node::Node | ( | const std::string & | node_name, |
const std::string & | namespace_, | ||
rclcpp::Context::SharedPtr | context, | ||
const std::vector< std::string > & | arguments, | ||
const std::vector< Parameter > & | initial_parameters, | ||
bool | use_global_arguments = true , |
||
bool | use_intra_process_comms = false , |
||
bool | start_parameter_services = true |
||
) |
Create a node based on the node name and a rclcpp::Context.
[in] | node_name | Name of the node. |
[in] | namespace_ | Namespace of the node. |
[in] | context | The context for the node (usually represents the state of a process). |
[in] | arguments | Command line arguments that should apply only to this node. |
[in] | initial_parameters | a list of initial values for parameters on the node. This can be used to provide remapping rules that only affect one instance. |
[in] | use_global_arguments | False to prevent node using arguments passed to the process. |
[in] | use_intra_process_comms | True to use the optimized intra-process communication pipeline to pass messages between nodes in the same process using shared memory. |
|
virtual |
const char* rclcpp::Node::get_name | ( | ) | const |
Get the name of the node.
const char* rclcpp::Node::get_namespace | ( | ) | const |
Get the namespace of the node.
rclcpp::Logger rclcpp::Node::get_logger | ( | ) | const |
Get the logger of the node.
rclcpp::callback_group::CallbackGroup::SharedPtr rclcpp::Node::create_callback_group | ( | rclcpp::callback_group::CallbackGroupType | group_type | ) |
Create and return a callback group.
const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr>& rclcpp::Node::get_callback_groups | ( | ) | const |
Return the list of callback groups in the node.
std::shared_ptr< PublisherT > rclcpp::Node::create_publisher | ( | const std::string & | topic_name, |
size_t | qos_history_depth, | ||
std::shared_ptr< Alloc > | allocator = nullptr |
||
) |
Create and return a Publisher.
[in] | topic_name | The topic for this publisher to publish on. |
[in] | qos_history_depth | The depth of the publisher message queue. |
[in] | allocator | Optional custom allocator. |
std::shared_ptr< PublisherT > rclcpp::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.
[in] | topic_name | The topic for this publisher to publish on. |
[in] | qos_profile | The quality of service profile to pass on to the rmw implementation. |
[in] | allocator | Optional custom allocator. |
std::shared_ptr< SubscriptionT > rclcpp::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< typename rclcpp::subscription_traits::has_message_type< CallbackT >::type, Alloc >::SharedPtr | msg_mem_strat = nullptr , |
||
std::shared_ptr< Alloc > | allocator = nullptr |
||
) |
Create and return a Subscription.
[in] | topic_name | The topic to subscribe on. |
[in] | callback | The user-defined callback function. |
[in] | qos_profile | The quality of service profile to pass on to the rmw implementation. |
[in] | group | The callback group for this subscription. NULL for no callback group. |
[in] | ignore_local_publications | True to ignore local publications. |
[in] | msg_mem_strat | The message memory strategy to use for allocating messages. |
[in] | allocator | Optional custom allocator. |
std::shared_ptr< SubscriptionT > rclcpp::Node::create_subscription | ( | const std::string & | topic_name, |
CallbackT && | callback, | ||
size_t | qos_history_depth, | ||
rclcpp::callback_group::CallbackGroup::SharedPtr | group = nullptr , |
||
bool | ignore_local_publications = false , |
||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy< typename rclcpp::subscription_traits::has_message_type< CallbackT >::type, Alloc >::SharedPtr | msg_mem_strat = nullptr , |
||
std::shared_ptr< Alloc > | allocator = nullptr |
||
) |
Create and return a Subscription.
[in] | topic_name | The topic to subscribe on. |
[in] | qos_history_depth | The depth of the subscription's incoming message queue. |
[in] | callback | The user-defined callback function. |
[in] | group | The callback group for this subscription. NULL for no callback group. |
[in] | ignore_local_publications | True to ignore local publications. |
[in] | msg_mem_strat | The message memory strategy to use for allocating messages. |
[in] | allocator | Optional custom allocator. |
rclcpp::WallTimer< CallbackT >::SharedPtr rclcpp::Node::create_wall_timer | ( | std::chrono::duration< int64_t, DurationT > | period, |
CallbackT | callback, | ||
rclcpp::callback_group::CallbackGroup::SharedPtr | group = nullptr |
||
) |
Create a timer.
[in] | period | Time interval between triggers of the callback. |
[in] | callback | User-defined callback function. |
[in] | group | Callback group to execute this timer's callback in. |
rclcpp::Client<ServiceT>::SharedPtr rclcpp::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 |
||
) |
rclcpp::Service< ServiceT >::SharedPtr rclcpp::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 |
||
) |
std::vector<rcl_interfaces::msg::SetParametersResult> rclcpp::Node::set_parameters | ( | const std::vector< rclcpp::Parameter > & | parameters | ) |
rcl_interfaces::msg::SetParametersResult rclcpp::Node::set_parameters_atomically | ( | const std::vector< rclcpp::Parameter > & | parameters | ) |
void rclcpp::Node::set_parameter_if_not_set | ( | const std::string & | name, |
const ParameterT & | value | ||
) |
std::vector<rclcpp::Parameter> rclcpp::Node::get_parameters | ( | const std::vector< std::string > & | names | ) | const |
rclcpp::Parameter rclcpp::Node::get_parameter | ( | const std::string & | name | ) | const |
bool rclcpp::Node::get_parameter | ( | const std::string & | name, |
rclcpp::Parameter & | parameter | ||
) | const |
bool rclcpp::Node::get_parameter | ( | const std::string & | name, |
ParameterT & | parameter | ||
) | const |
Assign the value of the parameter if set into the parameter argument.
If the parameter was not set, then the "parameter" argument is never assigned a value.
[in] | name | The name of the parameter to get. |
[out] | parameter | The output where the value of the parameter should be assigned. |
bool rclcpp::Node::get_parameter_or | ( | const std::string & | name, |
ParameterT & | value, | ||
const ParameterT & | alternative_value | ||
) | const |
Get the parameter value, or the "alternative value" if not set, and assign it to "value".
If the parameter was not set, then the "value" argument is assigned the "alternative_value". In all cases, the parameter remains not set after this function is called.
[in] | name | The name of the parameter to get. |
[out] | value | The output where the value of the parameter should be assigned. |
[in] | alternative_value | Value to be stored in output if the parameter was not set. |
std::vector<rcl_interfaces::msg::ParameterDescriptor> rclcpp::Node::describe_parameters | ( | const std::vector< std::string > & | names | ) | const |
std::vector<uint8_t> rclcpp::Node::get_parameter_types | ( | const std::vector< std::string > & | names | ) | const |
rcl_interfaces::msg::ListParametersResult rclcpp::Node::list_parameters | ( | const std::vector< std::string > & | prefixes, |
uint64_t | depth | ||
) | const |
void rclcpp::Node::register_param_change_callback | ( | CallbackT && | callback | ) |
Register the callback for parameter changes.
[in] | callback | User defined callback function. It is expected to atomically set parameters. |
std::map<std::string, std::vector<std::string> > rclcpp::Node::get_topic_names_and_types | ( | ) | const |
std::map<std::string, std::vector<std::string> > rclcpp::Node::get_service_names_and_types | ( | ) | const |
size_t rclcpp::Node::count_publishers | ( | const std::string & | topic_name | ) | const |
size_t rclcpp::Node::count_subscribers | ( | const std::string & | topic_name | ) | const |
rclcpp::Event::SharedPtr rclcpp::Node::get_graph_event | ( | ) |
Return a graph event, which will be set anytime a graph change occurs.
void rclcpp::Node::wait_for_graph_change | ( | rclcpp::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.
InvalidEventError | if the given event is nullptr |
EventNotRegisteredError | if the given event was not acquired with get_graph_event(). |
rclcpp::Clock::SharedPtr rclcpp::Node::get_clock | ( | ) |
Time rclcpp::Node::now | ( | ) |
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr rclcpp::Node::get_node_base_interface | ( | ) |
Return the Node's internal NodeBaseInterface implementation.
rclcpp::node_interfaces::NodeClockInterface::SharedPtr rclcpp::Node::get_node_clock_interface | ( | ) |
Return the Node's internal NodeClockInterface implementation.
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr rclcpp::Node::get_node_graph_interface | ( | ) |
Return the Node's internal NodeGraphInterface implementation.
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr rclcpp::Node::get_node_timers_interface | ( | ) |
Return the Node's internal NodeTimersInterface implementation.
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr rclcpp::Node::get_node_topics_interface | ( | ) |
Return the Node's internal NodeTopicsInterface implementation.
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr rclcpp::Node::get_node_services_interface | ( | ) |
Return the Node's internal NodeServicesInterface implementation.
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr rclcpp::Node::get_node_parameters_interface | ( | ) |
Return the Node's internal NodeParametersInterface implementation.
Client<ServiceT>::SharedPtr rclcpp::Node::create_client | ( | const std::string & | service_name, |
const rmw_qos_profile_t & | qos_profile, | ||
rclcpp::callback_group::CallbackGroup::SharedPtr | group | ||
) |