ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
node.hpp
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 
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_publisher.hpp"
46 #include "rclcpp/generic_subscription.hpp"
47 #include "rclcpp/logger.hpp"
48 #include "rclcpp/macros.hpp"
49 #include "rclcpp/message_memory_strategy.hpp"
50 #include "rclcpp/node_interfaces/node_base_interface.hpp"
51 #include "rclcpp/node_interfaces/node_clock_interface.hpp"
52 #include "rclcpp/node_interfaces/node_graph_interface.hpp"
53 #include "rclcpp/node_interfaces/node_logging_interface.hpp"
54 #include "rclcpp/node_interfaces/node_parameters_interface.hpp"
55 #include "rclcpp/node_interfaces/node_services_interface.hpp"
56 #include "rclcpp/node_interfaces/node_time_source_interface.hpp"
57 #include "rclcpp/node_interfaces/node_timers_interface.hpp"
58 #include "rclcpp/node_interfaces/node_topics_interface.hpp"
59 #include "rclcpp/node_interfaces/node_waitables_interface.hpp"
60 #include "rclcpp/node_options.hpp"
61 #include "rclcpp/parameter.hpp"
62 #include "rclcpp/publisher.hpp"
63 #include "rclcpp/publisher_options.hpp"
64 #include "rclcpp/qos.hpp"
65 #include "rclcpp/service.hpp"
66 #include "rclcpp/subscription.hpp"
67 #include "rclcpp/subscription_options.hpp"
68 #include "rclcpp/subscription_traits.hpp"
69 #include "rclcpp/time.hpp"
70 #include "rclcpp/timer.hpp"
71 #include "rclcpp/visibility_control.hpp"
72 
73 namespace rclcpp
74 {
75 
77 class Node : public std::enable_shared_from_this<Node>
78 {
79 public:
80  RCLCPP_SMART_PTR_DEFINITIONS(Node)
81 
82 
88  RCLCPP_PUBLIC
89  explicit Node(
90  const std::string & node_name,
91  const NodeOptions & options = NodeOptions());
92 
94 
100  RCLCPP_PUBLIC
101  explicit Node(
102  const std::string & node_name,
103  const std::string & namespace_,
104  const NodeOptions & options = NodeOptions());
105 
106  RCLCPP_PUBLIC
107  virtual ~Node();
108 
110 
111  RCLCPP_PUBLIC
112  const char *
113  get_name() const;
114 
116 
125  RCLCPP_PUBLIC
126  const char *
127  get_namespace() const;
128 
130 
134  RCLCPP_PUBLIC
135  const char *
136  get_fully_qualified_name() const;
137 
139 
140  RCLCPP_PUBLIC
142  get_logger() const;
143 
145  RCLCPP_PUBLIC
146  rclcpp::CallbackGroup::SharedPtr
148  rclcpp::CallbackGroupType group_type,
149  bool automatically_add_to_executor_with_node = true);
150 
152 
158  RCLCPP_PUBLIC
159  void
160  for_each_callback_group(const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func);
161 
163 
190  template<
191  typename MessageT,
192  typename AllocatorT = std::allocator<void>,
193  typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
194  std::shared_ptr<PublisherT>
196  const std::string & topic_name,
197  const rclcpp::QoS & qos,
200  );
201 
203 
211  template<
212  typename MessageT,
213  typename CallbackT,
214  typename AllocatorT = std::allocator<void>,
215  typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
216  typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType
217  >
218  std::shared_ptr<SubscriptionT>
220  const std::string & topic_name,
221  const rclcpp::QoS & qos,
222  CallbackT && callback,
225  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
226  MessageMemoryStrategyT::create_default()
227  )
228  );
229 
231 
236  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
239  std::chrono::duration<DurationRepT, DurationT> period,
240  CallbackT callback,
241  rclcpp::CallbackGroup::SharedPtr group = nullptr);
242 
244 
250  template<typename ServiceT>
253  const std::string & service_name,
254  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
255  rclcpp::CallbackGroup::SharedPtr group = nullptr);
256 
258 
265  template<typename ServiceT, typename CallbackT>
268  const std::string & service_name,
269  CallbackT && callback,
270  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
271  rclcpp::CallbackGroup::SharedPtr group = nullptr);
272 
274 
286  template<typename AllocatorT = std::allocator<void>>
287  std::shared_ptr<rclcpp::GenericPublisher> create_generic_publisher(
288  const std::string & topic_name,
289  const std::string & topic_type,
290  const rclcpp::QoS & qos,
293  )
294  );
295 
297 
311  template<typename AllocatorT = std::allocator<void>>
312  std::shared_ptr<rclcpp::GenericSubscription> create_generic_subscription(
313  const std::string & topic_name,
314  const std::string & topic_type,
315  const rclcpp::QoS & qos,
316  std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> callback,
319  )
320  );
321 
323 
364  RCLCPP_PUBLIC
365  const rclcpp::ParameterValue &
367  const std::string & name,
368  const rclcpp::ParameterValue & default_value,
369  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
370  rcl_interfaces::msg::ParameterDescriptor(),
371  bool ignore_override = false);
372 
374 
389  RCLCPP_PUBLIC
390  const rclcpp::ParameterValue &
392  const std::string & name,
393  rclcpp::ParameterType type,
394  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
395  rcl_interfaces::msg::ParameterDescriptor{},
396  bool ignore_override = false);
397 
399 
419  template<typename ParameterT>
420  auto
422  const std::string & name,
423  const ParameterT & default_value,
424  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
425  rcl_interfaces::msg::ParameterDescriptor(),
426  bool ignore_override = false);
427 
429 
432  template<typename ParameterT>
433  auto
435  const std::string & name,
436  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
437  rcl_interfaces::msg::ParameterDescriptor(),
438  bool ignore_override = false);
439 
441 
476  template<typename ParameterT>
477  std::vector<ParameterT>
479  const std::string & namespace_,
480  const std::map<std::string, ParameterT> & parameters,
481  bool ignore_overrides = false);
482 
484 
490  template<typename ParameterT>
491  std::vector<ParameterT>
493  const std::string & namespace_,
494  const std::map<
495  std::string,
496  std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
497  > & parameters,
498  bool ignore_overrides = false);
499 
501 
511  RCLCPP_PUBLIC
512  void
513  undeclare_parameter(const std::string & name);
514 
516 
520  RCLCPP_PUBLIC
521  bool
522  has_parameter(const std::string & name) const;
523 
525 
553  RCLCPP_PUBLIC
554  rcl_interfaces::msg::SetParametersResult
555  set_parameter(const rclcpp::Parameter & parameter);
556 
558 
591  RCLCPP_PUBLIC
592  std::vector<rcl_interfaces::msg::SetParametersResult>
593  set_parameters(const std::vector<rclcpp::Parameter> & parameters);
594 
596 
625  RCLCPP_PUBLIC
626  rcl_interfaces::msg::SetParametersResult
627  set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
628 
630 
645  RCLCPP_PUBLIC
647  get_parameter(const std::string & name) const;
648 
650 
664  RCLCPP_PUBLIC
665  bool
666  get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
667 
669 
681  template<typename ParameterT>
682  bool
683  get_parameter(const std::string & name, ParameterT & parameter) const;
684 
686 
700  template<typename ParameterT>
701  bool
703  const std::string & name,
704  ParameterT & parameter,
705  const ParameterT & alternative_value) const;
706 
708 
719  template<typename ParameterT>
720  ParameterT
722  const std::string & name,
723  const ParameterT & alternative_value) const;
724 
726 
743  RCLCPP_PUBLIC
744  std::vector<rclcpp::Parameter>
745  get_parameters(const std::vector<std::string> & names) const;
746 
748 
784  template<typename ParameterT>
785  bool
787  const std::string & prefix,
788  std::map<std::string, ParameterT> & values) const;
789 
791 
807  RCLCPP_PUBLIC
808  rcl_interfaces::msg::ParameterDescriptor
809  describe_parameter(const std::string & name) const;
810 
812 
830  RCLCPP_PUBLIC
831  std::vector<rcl_interfaces::msg::ParameterDescriptor>
832  describe_parameters(const std::vector<std::string> & names) const;
833 
835 
850  RCLCPP_PUBLIC
851  std::vector<uint8_t>
852  get_parameter_types(const std::vector<std::string> & names) const;
853 
855 
858  RCLCPP_PUBLIC
859  rcl_interfaces::msg::ListParametersResult
860  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
861 
864  using OnParametersSetCallbackType =
865  rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType;
866 
868 
931  RCLCPP_PUBLIC
932  RCUTILS_WARN_UNUSED
933  OnSetParametersCallbackHandle::SharedPtr
934  add_on_set_parameters_callback(OnParametersSetCallbackType callback);
935 
937 
959  RCLCPP_PUBLIC
960  void
962 
964 
968  RCLCPP_PUBLIC
969  std::vector<std::string>
970  get_node_names() const;
971 
973 
977  RCLCPP_PUBLIC
978  std::map<std::string, std::vector<std::string>>
980 
982 
986  RCLCPP_PUBLIC
987  std::map<std::string, std::vector<std::string>>
989 
991 
1000  RCLCPP_PUBLIC
1001  std::map<std::string, std::vector<std::string>>
1003  const std::string & node_name,
1004  const std::string & namespace_) const;
1005 
1007 
1012  RCLCPP_PUBLIC
1013  size_t
1014  count_publishers(const std::string & topic_name) const;
1015 
1017 
1022  RCLCPP_PUBLIC
1023  size_t
1024  count_subscribers(const std::string & topic_name) const;
1025 
1027 
1048  RCLCPP_PUBLIC
1049  std::vector<rclcpp::TopicEndpointInfo>
1050  get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
1051 
1053 
1074  RCLCPP_PUBLIC
1075  std::vector<rclcpp::TopicEndpointInfo>
1076  get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
1077 
1079  /* The graph Event object is a loan which must be returned.
1080  * The Event object is scoped and therefore to return the loan just let it go
1081  * out of scope.
1082  */
1083  RCLCPP_PUBLIC
1084  rclcpp::Event::SharedPtr
1085  get_graph_event();
1086 
1088 
1098  RCLCPP_PUBLIC
1099  void
1101  rclcpp::Event::SharedPtr event,
1102  std::chrono::nanoseconds timeout);
1103 
1105 
1108  RCLCPP_PUBLIC
1109  rclcpp::Clock::SharedPtr
1110  get_clock();
1111 
1113 
1116  RCLCPP_PUBLIC
1117  rclcpp::Clock::ConstSharedPtr
1118  get_clock() const;
1119 
1121 
1124  RCLCPP_PUBLIC
1125  Time
1126  now() const;
1127 
1129  RCLCPP_PUBLIC
1130  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
1132 
1134  RCLCPP_PUBLIC
1135  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
1137 
1139  RCLCPP_PUBLIC
1140  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
1142 
1144  RCLCPP_PUBLIC
1145  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
1147 
1149  RCLCPP_PUBLIC
1150  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
1152 
1154  RCLCPP_PUBLIC
1155  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
1157 
1159  RCLCPP_PUBLIC
1160  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
1162 
1164  RCLCPP_PUBLIC
1165  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
1167 
1169  RCLCPP_PUBLIC
1170  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
1172 
1174  RCLCPP_PUBLIC
1175  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
1177 
1179 
1206  RCLCPP_PUBLIC
1207  const std::string &
1208  get_sub_namespace() const;
1209 
1211 
1234  RCLCPP_PUBLIC
1235  const std::string &
1236  get_effective_namespace() const;
1237 
1239 
1276  RCLCPP_PUBLIC
1277  rclcpp::Node::SharedPtr
1278  create_sub_node(const std::string & sub_namespace);
1279 
1281  RCLCPP_PUBLIC
1282  const rclcpp::NodeOptions &
1283  get_node_options() const;
1284 
1285 protected:
1287 
1293  RCLCPP_PUBLIC
1294  Node(
1295  const Node & other,
1296  const std::string & sub_namespace);
1297 
1298 private:
1299  RCLCPP_DISABLE_COPY(Node)
1300 
1301  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
1302  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
1303  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
1304  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
1305  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
1306  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
1307  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
1308  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
1309  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
1310  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1311 
1312  const rclcpp::NodeOptions node_options_;
1313  const std::string sub_namespace_;
1314  const std::string effective_namespace_;
1315 };
1316 
1317 } // namespace rclcpp
1318 
1319 #ifndef RCLCPP__NODE_IMPL_HPP_
1320 // Template implementations
1321 #include "node_impl.hpp"
1322 #endif
1323 
1324 #endif // RCLCPP__NODE_HPP_
Encapsulation of options for node initialization.
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:78
RCLCPP_PUBLIC rclcpp::Logger get_logger() const
Get the logger of the node.
Definition: node.cpp:300
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
Definition: node.cpp:578
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
Definition: node.cpp:560
RCLCPP_PUBLIC std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
Definition: node.cpp:384
RCLCPP_PUBLIC bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
Definition: node.cpp:348
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.
Definition: node.cpp:596
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)
Set a single parameter.
Definition: node.cpp:354
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:141
RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
Definition: node.cpp:506
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
Definition: node.cpp:554
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
Definition: node.cpp:572
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.
Definition: node.cpp:473
RCLCPP_PUBLIC 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.
Definition: node.cpp:314
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
Definition: node.cpp:542
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:302
RCLCPP_PUBLIC const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
Definition: node.cpp:590
RCLCPP_PUBLIC size_t count_publishers(const std::string &topic_name) const
Return the number of publishers created for a given topic.
Definition: node.cpp:461
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:175
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.
Definition: node.cpp:446
RCLCPP_PUBLIC size_t count_subscribers(const std::string &topic_name) const
Return the number of subscribers created for a given topic.
Definition: node.cpp:467
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:237
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.
Definition: node.cpp:404
RCLCPP_PUBLIC Time now() const
Returns current time from the time source specified by clock_type.
Definition: node.cpp:518
RCLCPP_PUBLIC rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
Definition: node.cpp:492
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.
Definition: node.cpp:485
RCLCPP_PUBLIC rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
Definition: node.cpp:391
RCLCPP_PUBLIC void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
Definition: node.cpp:428
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.
Definition: node.cpp:440
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
Definition: node.cpp:372
RCLCPP_PUBLIC Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
Definition: node.cpp:112
RCLCPP_PUBLIC const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
Definition: node.cpp:604
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
Definition: node.cpp:524
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, all at once.
Definition: node.cpp:366
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.
Definition: node.cpp:498
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
Definition: node.cpp:530
RCLCPP_PUBLIC const char * get_name() const
Get the name of the node.
Definition: node.cpp:282
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)
Add a callback for when parameters are being set.
Definition: node.cpp:422
RCLCPP_PUBLIC std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, one at a time.
Definition: node.cpp:360
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
Definition: node.cpp:566
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.
Definition: node.cpp:452
RCLCPP_PUBLIC void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
Definition: node.cpp:342
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.
Definition: node.cpp:410
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.
Definition: node.cpp:479
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.
Definition: node.cpp:306
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeTimeSourceInterface implementation.
Definition: node.cpp:548
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.
Definition: node.cpp:416
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:92
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
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:110
RCLCPP_PUBLIC const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
Definition: node.cpp:294
RCLCPP_PUBLIC const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
Definition: node.cpp:584
RCLCPP_PUBLIC std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.
Definition: node.cpp:434
RCLCPP_PUBLIC const char * get_namespace() const
Get the namespace of the node.
Definition: node.cpp:288
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
Definition: node.cpp:536
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.
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:158
Store the type and value of a parameter.
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:53
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:78
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
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.