15 #ifndef RCLCPP__NODE_HPP_
16 #define RCLCPP__NODE_HPP_
19 #include <condition_variable>
30 #include "rcutils/macros.h"
32 #include "rcl/error_handling.h"
35 #include "rcl_interfaces/msg/list_parameters_result.hpp"
36 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
37 #include "rcl_interfaces/msg/parameter_event.hpp"
38 #include "rcl_interfaces/msg/set_parameters_result.hpp"
40 #include "rclcpp/callback_group.hpp"
41 #include "rclcpp/client.hpp"
42 #include "rclcpp/clock.hpp"
43 #include "rclcpp/context.hpp"
44 #include "rclcpp/event.hpp"
45 #include "rclcpp/generic_client.hpp"
46 #include "rclcpp/generic_publisher.hpp"
47 #include "rclcpp/generic_subscription.hpp"
48 #include "rclcpp/logger.hpp"
49 #include "rclcpp/macros.hpp"
50 #include "rclcpp/message_memory_strategy.hpp"
51 #include "rclcpp/node_interfaces/node_base_interface.hpp"
52 #include "rclcpp/node_interfaces/node_clock_interface.hpp"
53 #include "rclcpp/node_interfaces/node_graph_interface.hpp"
54 #include "rclcpp/node_interfaces/node_logging_interface.hpp"
55 #include "rclcpp/node_interfaces/node_parameters_interface.hpp"
56 #include "rclcpp/node_interfaces/node_services_interface.hpp"
57 #include "rclcpp/node_interfaces/node_time_source_interface.hpp"
58 #include "rclcpp/node_interfaces/node_timers_interface.hpp"
59 #include "rclcpp/node_interfaces/node_topics_interface.hpp"
60 #include "rclcpp/node_interfaces/node_type_descriptions_interface.hpp"
61 #include "rclcpp/node_interfaces/node_waitables_interface.hpp"
62 #include "rclcpp/node_options.hpp"
63 #include "rclcpp/parameter.hpp"
64 #include "rclcpp/publisher.hpp"
65 #include "rclcpp/publisher_options.hpp"
66 #include "rclcpp/qos.hpp"
67 #include "rclcpp/service.hpp"
68 #include "rclcpp/subscription.hpp"
69 #include "rclcpp/subscription_options.hpp"
70 #include "rclcpp/subscription_traits.hpp"
71 #include "rclcpp/time.hpp"
72 #include "rclcpp/timer.hpp"
73 #include "rclcpp/visibility_control.hpp"
79 class Node :
public std::enable_shared_from_this<Node>
82 RCLCPP_SMART_PTR_DEFINITIONS(
Node)
92 const std::string & node_name,
104 const std::string & node_name,
105 const std::string & namespace_,
148 rclcpp::CallbackGroup::SharedPtr
150 rclcpp::CallbackGroupType group_type,
151 bool automatically_add_to_executor_with_node =
true);
194 typename AllocatorT = std::allocator<void>,
196 std::shared_ptr<PublisherT>
198 const std::string & topic_name,
216 typename AllocatorT = std::allocator<void>,
218 typename MessageMemoryStrategyT =
typename SubscriptionT::MessageMemoryStrategyType
220 std::shared_ptr<SubscriptionT>
222 const std::string & topic_name,
224 CallbackT && callback,
227 typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
228 MessageMemoryStrategyT::create_default()
239 template<
typename DurationRepT =
int64_t,
typename DurationT = std::milli,
typename CallbackT>
242 std::chrono::duration<DurationRepT, DurationT> period,
244 rclcpp::CallbackGroup::SharedPtr group =
nullptr,
245 bool autostart =
true);
253 template<
typename DurationRepT =
int64_t,
typename DurationT = std::milli,
typename CallbackT>
256 std::chrono::duration<DurationRepT, DurationT> period,
258 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
268 template<
typename ServiceT>
269 [[deprecated(
"use rclcpp::QoS instead of rmw_qos_profile_t")]]
272 const std::string & service_name,
273 const rmw_qos_profile_t & qos_profile,
274 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
283 template<
typename ServiceT>
286 const std::string & service_name,
288 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
299 template<
typename ServiceT,
typename CallbackT>
300 [[deprecated(
"use rclcpp::QoS instead of rmw_qos_profile_t")]]
303 const std::string & service_name,
304 CallbackT && callback,
305 const rmw_qos_profile_t & qos_profile,
306 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
316 template<
typename ServiceT,
typename CallbackT>
319 const std::string & service_name,
320 CallbackT && callback,
322 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
333 rclcpp::GenericClient::SharedPtr
335 const std::string & service_name,
336 const std::string & service_type,
338 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
353 template<
typename AllocatorT = std::allocator<
void>>
355 const std::string & topic_name,
356 const std::string & topic_type,
380 typename AllocatorT = std::allocator<void>>
382 const std::string & topic_name,
383 const std::string & topic_type,
385 CallbackT && callback,
446 const std::string & name,
448 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
449 rcl_interfaces::msg::ParameterDescriptor(),
450 bool ignore_override =
false);
471 const std::string & name,
472 rclcpp::ParameterType type,
473 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
474 rcl_interfaces::msg::ParameterDescriptor{},
475 bool ignore_override =
false);
498 template<
typename ParameterT>
501 const std::string & name,
502 const ParameterT & default_value,
503 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
504 rcl_interfaces::msg::ParameterDescriptor(),
505 bool ignore_override =
false);
511 template<
typename ParameterT>
514 const std::string & name,
515 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
516 rcl_interfaces::msg::ParameterDescriptor(),
517 bool ignore_override =
false);
566 template<
typename ParameterT>
567 std::vector<ParameterT>
569 const std::string & namespace_,
570 const std::map<std::string, ParameterT> & parameters,
571 bool ignore_overrides =
false);
580 template<
typename ParameterT>
581 std::vector<ParameterT>
583 const std::string & namespace_,
586 std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
588 bool ignore_overrides =
false);
658 rcl_interfaces::msg::SetParametersResult
710 std::vector<rcl_interfaces::msg::SetParametersResult>
711 set_parameters(
const std::vector<rclcpp::Parameter> & parameters);
758 rcl_interfaces::msg::SetParametersResult
817 template<
typename ParameterT>
819 get_parameter(
const std::string & name, ParameterT & parameter)
const;
836 template<
typename ParameterT>
839 const std::string & name,
840 ParameterT & parameter,
841 const ParameterT & alternative_value)
const;
855 template<
typename ParameterT>
858 const std::string & name,
859 const ParameterT & alternative_value)
const;
882 std::vector<rclcpp::Parameter>
922 template<
typename ParameterT>
925 const std::string & prefix,
926 std::map<std::string, ParameterT> & values)
const;
946 rcl_interfaces::msg::ParameterDescriptor
969 std::vector<rcl_interfaces::msg::ParameterDescriptor>
1006 rcl_interfaces::msg::ListParametersResult
1007 list_parameters(
const std::vector<std::string> & prefixes, uint64_t depth)
const;
1011 using PreSetParametersCallbackType =
1012 rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType;
1016 using OnSetParametersCallbackType =
1017 rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType;
1018 using OnParametersSetCallbackType [[deprecated(
"use OnSetParametersCallbackType instead")]] =
1019 OnSetParametersCallbackType;
1023 using PostSetParametersCallbackType =
1024 rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType;
1084 PreSetParametersCallbackHandle::SharedPtr
1158 OnSetParametersCallbackHandle::SharedPtr
1219 PostSetParametersCallbackHandle::SharedPtr
1279 std::vector<std::string>
1288 std::map<std::string, std::vector<std::string>>
1297 std::map<std::string, std::vector<std::string>>
1311 std::map<std::string, std::vector<std::string>>
1313 const std::string & node_name,
1314 const std::string & namespace_)
const;
1379 std::vector<rclcpp::TopicEndpointInfo>
1405 std::vector<rclcpp::TopicEndpointInfo>
1414 rclcpp::Event::SharedPtr
1431 rclcpp::Event::SharedPtr event,
1432 std::chrono::nanoseconds timeout);
1439 rclcpp::Clock::SharedPtr
1447 rclcpp::Clock::ConstSharedPtr
1460 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
1465 rclcpp::node_interfaces::NodeClockInterface::SharedPtr
1470 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
1475 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
1480 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
1485 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
1490 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
1495 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
1500 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
1505 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
1510 rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr
1612 rclcpp::Node::SharedPtr
1631 const std::string & sub_namespace);
1634 RCLCPP_DISABLE_COPY(
Node)
1636 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
1637 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
1638 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
1639 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
1640 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
1641 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
1642 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
1643 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
1644 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
1645 rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr node_type_descriptions_;
1646 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1649 const std::string sub_namespace_;
1650 const std::string effective_namespace_;
1656 std::shared_ptr<NodeImpl> hidden_impl_{
nullptr};
1661 #ifndef RCLCPP__NODE_IMPL_HPP_
1663 #include "node_impl.hpp"
Generic timer. Periodically executes a user-specified callback.
Encapsulation of options for node initialization.
Node is the single point of entry for creating publishers and subscribers.
RCLCPP_PUBLIC rclcpp::Logger get_logger() const
Get the logger of the node.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
RCLCPP_PUBLIC std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnSetParametersCallbackType callback)
Add a callback to validate parameters before they are set.
RCLCPP_PUBLIC bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
RCLCPP_PUBLIC rclcpp::Node::SharedPtr create_sub_node(const std::string &sub_namespace)
Create a sub-node, which will extend the namespace of all entities created with it.
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter ¶meter)
Set a single parameter.
RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
rclcpp::Service< ServiceT >::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
RCLCPP_PUBLIC std::vector< rclcpp::TopicEndpointInfo > get_publishers_info_by_topic(const std::string &topic_name, bool no_mangle=false) const
Return the topic endpoint information about publishers on a given topic.
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
RCLCPP_PUBLIC const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
bool get_parameter_or(const std::string &name, ParameterT ¶meter, const ParameterT &alternative_value) const
Get the parameter value, or the "alternative_value" if not set, and assign it to "parameter".
RCLCPP_PUBLIC const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
RCLCPP_PUBLIC size_t count_publishers(const std::string &topic_name) const
Return the number of publishers created for a given topic.
rclcpp::GenericTimer< CallbackT >::SharedPtr create_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create a timer that uses the node clock to drive the callback.
RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_service_names_and_types() const
Return a map of existing service names to list of service types.
RCLCPP_PUBLIC size_t count_subscribers(const std::string &topic_name) const
Return the number of subscribers created for a given topic.
std::vector< ParameterT > declare_parameters(const std::string &namespace_, const std::map< std::string, ParameterT > ¶meters, bool ignore_overrides=false)
Declare and initialize several parameters with the same namespace and type.
RCLCPP_PUBLIC std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const
Return a vector of parameter descriptors, one for each of the given names.
RCLCPP_PUBLIC Time now() const
Returns current time from the time source specified by clock_type.
RCLCPP_PUBLIC rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
RCLCPP_PUBLIC void for_each_callback_group(const node_interfaces::NodeBaseInterface::CallbackGroupFunction &func)
Iterate over the callback groups in the node, calling the given function on each valid one.
RCLCPP_PUBLIC rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
RCLCPP_PUBLIC void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_topic_names_and_types() const
Return a map of existing topic names to list of topic types.
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
RCLCPP_PUBLIC Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
RCLCPP_PUBLIC size_t count_services(const std::string &service_name) const
Return the number of services created for a given service.
RCLCPP_PUBLIC const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
RCLCPP_PUBLIC rclcpp::GenericClient::SharedPtr create_generic_client(const std::string &service_name, const std::string &service_type, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a GenericClient.
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, all at once.
RCLCPP_PUBLIC 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.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
RCLCPP_PUBLIC void remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle *const handler)
Remove a callback registered with add_pre_set_parameters_callback.
RCLCPP_PUBLIC const char * get_name() const
Get the name of the node.
RCLCPP_PUBLIC std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, one at a time.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr get_node_type_descriptions_interface()
Return the Node's internal NodeTypeDescriptionsInterface implementation.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_service_names_and_types_by_node(const std::string &node_name, const std::string &namespace_) const
Return a map of existing service names to list of service types for a specific node.
RCLCPP_PUBLIC void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
RCLCPP_PUBLIC std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const
Return a vector of parameter types, one for each of the given names.
RCLCPP_PUBLIC std::vector< rclcpp::TopicEndpointInfo > get_subscriptions_info_by_topic(const std::string &topic_name, bool no_mangle=false) const
Return the topic endpoint information about subscriptions on a given topic.
std::shared_ptr< rclcpp::GenericSubscription > create_generic_subscription(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
RCLCPP_PUBLIC rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node=true)
Create and return a callback group.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeTimeSourceInterface implementation.
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED PreSetParametersCallbackHandle::SharedPtr add_pre_set_parameters_callback(PreSetParametersCallbackType callback)
Add a callback that gets triggered before parameters are validated.
RCLCPP_PUBLIC rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const
Return a list of parameters with any of the given prefixes, up to the given depth.
std::shared_ptr< SubscriptionT > create_subscription(const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const SubscriptionOptionsWithAllocator< AllocatorT > &options=SubscriptionOptionsWithAllocator< AllocatorT >(), typename MessageMemoryStrategyT::SharedPtr msg_mem_strat=(MessageMemoryStrategyT::create_default()))
Create and return a Subscription.
RCLCPP_PUBLIC size_t count_clients(const std::string &service_name) const
Return the number of clients created for a given service.
std::shared_ptr< PublisherT > create_publisher(const std::string &topic_name, const rclcpp::QoS &qos, const PublisherOptionsWithAllocator< AllocatorT > &options=PublisherOptionsWithAllocator< AllocatorT >())
Create and return a Publisher.
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr, bool autostart=true)
Create a wall timer that uses the wall clock to drive the callback.
RCLCPP_PUBLIC const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
RCLCPP_PUBLIC const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
RCLCPP_PUBLIC std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.
RCLCPP_PUBLIC const char * get_namespace() const
Get the namespace of the node.
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED PostSetParametersCallbackHandle::SharedPtr add_post_set_parameters_callback(PostSetParametersCallbackType callback)
Add a callback that gets triggered after parameters are set successfully.
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
RCLCPP_PUBLIC void remove_post_set_parameters_callback(const PostSetParametersCallbackHandle *const handler)
Remove a callback registered with add_post_set_parameters_callback.
std::shared_ptr< rclcpp::GenericPublisher > create_generic_publisher(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=(rclcpp::PublisherOptionsWithAllocator< AllocatorT >()))
Create and return a GenericPublisher.
Store the type and value of a parameter.
Structure to store an arbitrary parameter with templated get/set methods.
A publisher publishes messages of any type to a topic.
Encapsulation of Quality of Service settings.
Subscription implementation, templated on the type of message this subscription receives.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
Structure containing optional configuration for Publishers.
Structure containing optional configuration for Subscriptions.