rclcpp  master
C++ ROS Client Library API
node.hpp
Go to the documentation of this file.
1 // Copyright 2014 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__NODE_HPP_
16 #define RCLCPP__NODE_HPP_
17 
18 #include <atomic>
19 #include <condition_variable>
20 #include <functional>
21 #include <list>
22 #include <map>
23 #include <memory>
24 #include <mutex>
25 #include <string>
26 #include <tuple>
27 #include <utility>
28 #include <vector>
29 
30 #include "rcutils/macros.h"
31 
32 #include "rcl/error_handling.h"
33 #include "rcl/node.h"
34 
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"
39 
41 #include "rclcpp/client.hpp"
42 #include "rclcpp/clock.hpp"
43 #include "rclcpp/context.hpp"
44 #include "rclcpp/event.hpp"
47 #include "rclcpp/logger.hpp"
48 #include "rclcpp/macros.hpp"
60 #include "rclcpp/node_options.hpp"
61 #include "rclcpp/parameter.hpp"
62 #include "rclcpp/publisher.hpp"
64 #include "rclcpp/qos.hpp"
65 #include "rclcpp/service.hpp"
66 #include "rclcpp/subscription.hpp"
69 #include "rclcpp/time.hpp"
70 #include "rclcpp/timer.hpp"
72 
73 namespace rclcpp
74 {
75 
77 class Node : public std::enable_shared_from_this<Node>
78 {
79 public:
81 
82 
83 
89  explicit Node(
90  const std::string & node_name,
91  const NodeOptions & options = NodeOptions());
92 
94 
101  explicit Node(
102  const std::string & node_name,
103  const std::string & namespace_,
104  const NodeOptions & options = NodeOptions());
105 
107  virtual ~Node();
108 
110 
112  const char *
113  get_name() const;
114 
116 
126  const char *
127  get_namespace() const;
128 
130 
135  const char *
136  get_fully_qualified_name() const;
137 
139 
142  get_logger() const;
143 
146  rclcpp::CallbackGroup::SharedPtr
148  rclcpp::CallbackGroupType group_type,
149  bool automatically_add_to_executor_with_node = true);
150 
154  get_callback_groups() const;
155 
157 
184  template<
185  typename MessageT,
186  typename AllocatorT = std::allocator<void>,
187  typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
190  const std::string & topic_name,
191  const rclcpp::QoS & qos,
194  );
195 
197 
205  template<
206  typename MessageT,
207  typename CallbackT,
208  typename AllocatorT = std::allocator<void>,
209  typename CallbackMessageT =
212  typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
213  CallbackMessageT,
214  AllocatorT
215  >
216  >
219  const std::string & topic_name,
220  const rclcpp::QoS & qos,
221  CallbackT && callback,
224  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
225  MessageMemoryStrategyT::create_default()
226  )
227  );
228 
230 
235  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
239  CallbackT callback,
240  rclcpp::CallbackGroup::SharedPtr group = nullptr);
241 
243 
249  template<typename ServiceT>
252  const std::string & service_name,
253  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
254  rclcpp::CallbackGroup::SharedPtr group = nullptr);
255 
257 
264  template<typename ServiceT, typename CallbackT>
267  const std::string & service_name,
268  CallbackT && callback,
269  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
270  rclcpp::CallbackGroup::SharedPtr group = nullptr);
271 
273 
285  template<typename AllocatorT = std::allocator<void>>
287  const std::string & topic_name,
288  const std::string & topic_type,
289  const rclcpp::QoS & qos,
292  )
293  );
294 
296 
310  template<typename AllocatorT = std::allocator<void>>
312  const std::string & topic_name,
313  const std::string & topic_type,
314  const rclcpp::QoS & qos,
318  )
319  );
320 
322 
364  const rclcpp::ParameterValue &
366  const std::string & name,
367  const rclcpp::ParameterValue & default_value,
368  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
369  rcl_interfaces::msg::ParameterDescriptor(),
370  bool ignore_override = false);
371 
373 
389  const rclcpp::ParameterValue &
391  const std::string & name,
393  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
394  rcl_interfaces::msg::ParameterDescriptor{},
395  bool ignore_override = false);
396 
398  [[deprecated(
399  "declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \
400  "If you want to declare a parameter that won't change type without a default value use:\n" \
401  "`node->declare_parameter<ParameterT>(name)`, where e.g. ParameterT=int64_t.\n\n" \
402  "If you want to declare a parameter that can dynamically change type use:\n" \
403  "```\n" \
404  "rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
405  "descriptor.dynamic_typing = true;\n" \
406  "node->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \
407  "```"
408  )]]
410  const rclcpp::ParameterValue &
411  declare_parameter(const std::string & name);
412 
414 
434  template<typename ParameterT>
435  auto
437  const std::string & name,
438  const ParameterT & default_value,
439  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
440  rcl_interfaces::msg::ParameterDescriptor(),
441  bool ignore_override = false);
442 
444 
447  template<typename ParameterT>
448  auto
450  const std::string & name,
451  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
452  rcl_interfaces::msg::ParameterDescriptor(),
453  bool ignore_override = false);
454 
456 
491  template<typename ParameterT>
494  const std::string & namespace_,
495  const std::map<std::string, ParameterT> & parameters,
496  bool ignore_overrides = false);
497 
499 
505  template<typename ParameterT>
508  const std::string & namespace_,
509  const std::map<
510  std::string,
512  > & parameters,
513  bool ignore_overrides = false);
514 
516 
527  void
528  undeclare_parameter(const std::string & name);
529 
531 
536  bool
537  has_parameter(const std::string & name) const;
538 
540 
569  rcl_interfaces::msg::SetParametersResult
570  set_parameter(const rclcpp::Parameter & parameter);
571 
573 
609 
611 
641  rcl_interfaces::msg::SetParametersResult
643 
645 
662  get_parameter(const std::string & name) const;
663 
665 
680  bool
681  get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
682 
684 
696  template<typename ParameterT>
697  bool
698  get_parameter(const std::string & name, ParameterT & parameter) const;
699 
701 
715  template<typename ParameterT>
716  bool
718  const std::string & name,
719  ParameterT & parameter,
720  const ParameterT & alternative_value) const;
721 
723 
742  get_parameters(const std::vector<std::string> & names) const;
743 
745 
781  template<typename ParameterT>
782  bool
784  const std::string & prefix,
785  std::map<std::string, ParameterT> & values) const;
786 
788 
805  rcl_interfaces::msg::ParameterDescriptor
806  describe_parameter(const std::string & name) const;
807 
809 
829  describe_parameters(const std::vector<std::string> & names) const;
830 
832 
849  get_parameter_types(const std::vector<std::string> & names) const;
850 
852 
856  rcl_interfaces::msg::ListParametersResult
857  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
858 
863 
865 
930  OnSetParametersCallbackHandle::SharedPtr
932 
934 
957  void
959 
961 
967  get_node_names() const;
968 
970 
977 
979 
986 
988 
997  const std::string & node_name,
998  const std::string & namespace_) const;
999 
1001 
1007  size_t
1008  count_publishers(const std::string & topic_name) const;
1009 
1011 
1017  size_t
1018  count_subscribers(const std::string & topic_name) const;
1019 
1021 
1044  get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
1045 
1047 
1070  get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
1071 
1073  /* The graph Event object is a loan which must be returned.
1074  * The Event object is scoped and therefore to return the loan just let it go
1075  * out of scope.
1076  */
1078  rclcpp::Event::SharedPtr
1079  get_graph_event();
1080 
1082 
1093  void
1095  rclcpp::Event::SharedPtr event,
1096  std::chrono::nanoseconds timeout);
1097 
1099 
1103  rclcpp::Clock::SharedPtr
1104  get_clock();
1105 
1107 
1111  rclcpp::Clock::ConstSharedPtr
1112  get_clock() const;
1113 
1115 
1119  Time
1120  now() const;
1121 
1124  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
1126 
1129  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
1131 
1134  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
1136 
1139  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
1141 
1144  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
1146 
1149  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
1151 
1154  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
1156 
1159  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
1161 
1164  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
1166 
1169  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
1171 
1173 
1201  const std::string &
1202  get_sub_namespace() const;
1203 
1205 
1229  const std::string &
1230  get_effective_namespace() const;
1231 
1233 
1271  rclcpp::Node::SharedPtr
1272  create_sub_node(const std::string & sub_namespace);
1273 
1276  const rclcpp::NodeOptions &
1277  get_node_options() const;
1278 
1279 protected:
1281 
1288  Node(
1289  const Node & other,
1290  const std::string & sub_namespace);
1291 
1292 private:
1294 
1295  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
1296  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
1297  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
1298  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
1299  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
1300  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
1301  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
1302  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
1303  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
1304  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1305 
1306  const rclcpp::NodeOptions node_options_;
1307  const std::string sub_namespace_;
1308  const std::string effective_namespace_;
1309 };
1310 
1311 } // namespace rclcpp
1312 
1313 #ifndef RCLCPP__NODE_IMPL_HPP_
1314 // Template implementations
1315 #include "node_impl.hpp"
1316 #endif
1317 
1318 #endif // RCLCPP__NODE_HPP_
rclcpp::Node::set_parameters_atomically
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, all at once.
rclcpp::Node::get_effective_namespace
const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
node_graph_interface.hpp
node_impl.hpp
generic_publisher.hpp
callback_group.hpp
rclcpp::Node::now
Time now() const
Returns current time from the time source specified by clock_type.
client.hpp
node_time_source_interface.hpp
rclcpp::ParameterValue
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
rclcpp::Publisher
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:53
std::string
std::shared_ptr
rclcpp::Node::get_callback_groups
const std::vector< rclcpp::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
RCLCPP_DISABLE_COPY
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
rclcpp::Node::get_node_clock_interface
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
rclcpp::Node::get_publishers_info_by_topic
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.
node_waitables_interface.hpp
rclcpp::Node::list_parameters
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::pair
rclcpp::Node::create_wall_timer
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create a timer.
Definition: node_impl.hpp:111
rclcpp::Node::describe_parameter
rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
std::vector< rclcpp::CallbackGroup::WeakPtr >
std::chrono::duration
rclcpp::Service
Definition: service.hpp:144
context.hpp
rclcpp::Node::get_node_waitables_interface
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
rclcpp::Node::create_subscription
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.
Definition: node_impl.hpp:93
rclcpp::Time
Definition: time.hpp:31
event.hpp
rclcpp::Node::count_publishers
size_t count_publishers(const std::string &topic_name) const
Return the number of publishers created for a given topic.
rclcpp::Node::create_client
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
rclcpp::SubscriptionOptionsWithAllocator
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:87
clock.hpp
rclcpp::Node::get_clock
rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
rclcpp::Node::get_namespace
const char * get_namespace() const
Get the namespace of the node.
std::function
rclcpp::CallbackGroupType
CallbackGroupType
Definition: callback_group.hpp:43
rclcpp::Node::get_parameter
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
publisher.hpp
rclcpp::subscription_traits::extract_message_type< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > >::type
typename std::remove_cv_t< std::remove_reference_t< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > > > type
Definition: subscription_traits.hpp:67
qos.hpp
rclcpp::Node::create_publisher
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.
Definition: node_impl.hpp:73
timer.hpp
rclcpp::Subscription
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
node_topics_interface.hpp
rclcpp::Node::has_parameter
bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::node_interfaces::OnSetParametersCallbackHandle
Definition: node_parameters_interface.hpp:36
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
rclcpp::Node::get_name
const char * get_name() const
Get the name of the node.
rclcpp::Node::get_node_options
const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
rclcpp::Node::get_logger
rclcpp::Logger get_logger() const
Get the logger of the node.
rclcpp::Node::get_node_logging_interface
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
RCLCPP_SMART_PTR_DEFINITIONS
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
subscription_traits.hpp
macros.hpp
rclcpp::Node::create_generic_subscription
std::shared_ptr< rclcpp::GenericSubscription > create_generic_subscription(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, std::function< void(std::shared_ptr< rclcpp::SerializedMessage >)> callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
Definition: node_impl.hpp:176
rclcpp::Node
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:77
rclcpp::Node::get_graph_event
rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
rclcpp::Node::create_callback_group
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::Node::set_parameters
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, one at a time.
publisher_options.hpp
node_base_interface.hpp
rclcpp::Logger
Definition: logger.hpp:91
rclcpp::Node::get_parameters
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
rclcpp::Node::create_service
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::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
Definition: node_impl.hpp:142
rclcpp::Node::create_generic_publisher
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.
Definition: node_impl.hpp:159
rclcpp::Node::get_node_base_interface
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
node_services_interface.hpp
rclcpp::Node::get_node_timers_interface
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
rclcpp::Node::get_service_names_and_types
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.
std::enable_shared_from_this
rclcpp::Node::get_parameter_or
bool get_parameter_or(const std::string &name, ParameterT &parameter, const ParameterT &alternative_value) const
Get the parameter value, or the "alternative_value" if not set, and assign it to "parameter".
Definition: node_impl.hpp:299
rclcpp::Node::remove_on_set_parameters_callback
void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
rclcpp::Node::count_subscribers
size_t count_subscribers(const std::string &topic_name) const
Return the number of subscribers created for a given topic.
RCUTILS_WARN_UNUSED
#define RCUTILS_WARN_UNUSED
rclcpp::Node::get_node_graph_interface
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
std::map
rclcpp::Node::Node
Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
rclcpp::Node::declare_parameter
const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
rclcpp::Node::declare_parameters
std::vector< ParameterT > declare_parameters(const std::string &namespace_, const std::map< std::string, ParameterT > &parameters, bool ignore_overrides=false)
Declare and initialize several parameters with the same namespace and type.
Definition: node_impl.hpp:234
node_clock_interface.hpp
rclcpp::ParameterType
ParameterType
Definition: parameter_value.hpp:32
parameter.hpp
subscription_options.hpp
rclcpp::PublisherOptionsWithAllocator
Structure containing optional configuration for Publishers.
Definition: publisher_options.hpp:65
rclcpp::Client
Definition: client.hpp:178
rclcpp::Node::get_topic_names_and_types
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::Node::get_fully_qualified_name
const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
visibility_control.hpp
rclcpp::message_memory_strategy::MessageMemoryStrategy
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:41
rclcpp::Node::get_node_services_interface
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
node.h
rclcpp::Node::get_sub_namespace
const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
rclcpp::Node::get_parameter_types
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.
logger.hpp
rclcpp::Node::get_node_parameters_interface
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
node_timers_interface.hpp
rmw_qos_profile_t
rclcpp::NodeOptions
Encapsulation of options for node initialization.
Definition: node_options.hpp:34
rclcpp::WallTimer
Definition: timer.hpp:259
std::allocator
rclcpp::Node::get_node_time_source_interface
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeTimeSourceInterface implementation.
rclcpp::Node::wait_for_graph_change
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::Node::get_node_topics_interface
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
rclcpp::Parameter
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:52
rclcpp::Node::create_sub_node
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.
message_memory_strategy.hpp
time.hpp
rclcpp::Node::get_subscriptions_info_by_topic
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.
rclcpp::Node::set_parameter
rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)
Set a single parameter.
rclcpp::Node::get_service_names_and_types_by_node
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 the number of publishers that are advertised on a given topic.
macros.h
rclcpp::Node::~Node
virtual ~Node()
service.hpp
generic_subscription.hpp
rclcpp::Node::add_on_set_parameters_callback
RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)
Add a callback for when parameters are being set.
rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType
OnSetParametersCallbackHandle::OnParametersSetCallbackType OnParametersSetCallbackType
Definition: node_parameters_interface.hpp:208
subscription.hpp
node_parameters_interface.hpp
rclcpp::Node::describe_parameters
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.
node_logging_interface.hpp
node_options.hpp
rclcpp::Node::undeclare_parameter
void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
rclcpp::Node::get_node_names
std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.