ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
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_client.hpp"
46 #include "rclcpp/generic_publisher.hpp"
47 #include "rclcpp/generic_service.hpp"
48 #include "rclcpp/generic_subscription.hpp"
49 #include "rclcpp/logger.hpp"
50 #include "rclcpp/macros.hpp"
51 #include "rclcpp/message_memory_strategy.hpp"
52 #include "rclcpp/node_interfaces/node_base_interface.hpp"
53 #include "rclcpp/node_interfaces/node_clock_interface.hpp"
54 #include "rclcpp/node_interfaces/node_graph_interface.hpp"
55 #include "rclcpp/node_interfaces/node_logging_interface.hpp"
56 #include "rclcpp/node_interfaces/node_parameters_interface.hpp"
57 #include "rclcpp/node_interfaces/node_services_interface.hpp"
58 #include "rclcpp/node_interfaces/node_time_source_interface.hpp"
59 #include "rclcpp/node_interfaces/node_timers_interface.hpp"
60 #include "rclcpp/node_interfaces/node_topics_interface.hpp"
61 #include "rclcpp/node_interfaces/node_type_descriptions_interface.hpp"
62 #include "rclcpp/node_interfaces/node_waitables_interface.hpp"
63 #include "rclcpp/node_options.hpp"
64 #include "rclcpp/parameter.hpp"
65 #include "rclcpp/publisher.hpp"
66 #include "rclcpp/publisher_options.hpp"
67 #include "rclcpp/qos.hpp"
68 #include "rclcpp/service.hpp"
69 #include "rclcpp/subscription.hpp"
70 #include "rclcpp/subscription_options.hpp"
71 #include "rclcpp/subscription_traits.hpp"
72 #include "rclcpp/time.hpp"
73 #include "rclcpp/timer.hpp"
74 #include "rclcpp/visibility_control.hpp"
75 
76 namespace rclcpp
77 {
78 
80 class Node : public std::enable_shared_from_this<Node>
81 {
82 public:
83  RCLCPP_SMART_PTR_DEFINITIONS(Node)
84 
85 
91  RCLCPP_PUBLIC
92  explicit Node(
93  const std::string & node_name,
94  const NodeOptions & options = NodeOptions());
95 
97 
103  RCLCPP_PUBLIC
104  explicit Node(
105  const std::string & node_name,
106  const std::string & namespace_,
107  const NodeOptions & options = NodeOptions());
108 
109  RCLCPP_PUBLIC
110  virtual ~Node();
111 
113 
114  RCLCPP_PUBLIC
115  const char *
116  get_name() const;
117 
119 
128  RCLCPP_PUBLIC
129  const char *
130  get_namespace() const;
131 
133 
137  RCLCPP_PUBLIC
138  const char *
139  get_fully_qualified_name() const;
140 
142 
143  RCLCPP_PUBLIC
145  get_logger() const;
146 
148  RCLCPP_PUBLIC
149  rclcpp::CallbackGroup::SharedPtr
151  rclcpp::CallbackGroupType group_type,
152  bool automatically_add_to_executor_with_node = true);
153 
155 
161  RCLCPP_PUBLIC
162  void
163  for_each_callback_group(const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func);
164 
166 
193  template<
194  typename MessageT,
195  typename AllocatorT = std::allocator<void>,
196  typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
197  std::shared_ptr<PublisherT>
199  const std::string & topic_name,
200  const rclcpp::QoS & qos,
203  );
204 
206 
214  template<
215  typename MessageT,
216  typename CallbackT,
217  typename AllocatorT = std::allocator<void>,
218  typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
219  typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType
220  >
221  std::shared_ptr<SubscriptionT>
223  const std::string & topic_name,
224  const rclcpp::QoS & qos,
225  CallbackT && callback,
228  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
229  MessageMemoryStrategyT::create_default()
230  )
231  );
232 
234 
240  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
243  std::chrono::duration<DurationRepT, DurationT> period,
244  CallbackT callback,
245  rclcpp::CallbackGroup::SharedPtr group = nullptr,
246  bool autostart = true);
247 
249 
254  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
256  create_timer(
257  std::chrono::duration<DurationRepT, DurationT> period,
258  CallbackT callback,
259  rclcpp::CallbackGroup::SharedPtr group = nullptr);
260 
262 
268  template<typename ServiceT>
271  const std::string & service_name,
272  const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
273  rclcpp::CallbackGroup::SharedPtr group = nullptr);
274 
276 
283  template<typename ServiceT, typename CallbackT>
286  const std::string & service_name,
287  CallbackT && callback,
288  const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
289  rclcpp::CallbackGroup::SharedPtr group = nullptr);
290 
292 
299  RCLCPP_PUBLIC
300  rclcpp::GenericClient::SharedPtr
302  const std::string & service_name,
303  const std::string & service_type,
304  const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
305  rclcpp::CallbackGroup::SharedPtr group = nullptr);
306 
308 
316  template<typename CallbackT>
317  typename rclcpp::GenericService::SharedPtr
319  const std::string & service_name,
320  const std::string & service_type,
321  CallbackT && callback,
322  const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
323  rclcpp::CallbackGroup::SharedPtr group = nullptr);
324 
326 
338  template<typename AllocatorT = std::allocator<void>>
339  std::shared_ptr<rclcpp::GenericPublisher> create_generic_publisher(
340  const std::string & topic_name,
341  const std::string & topic_type,
342  const rclcpp::QoS & qos,
345  )
346  );
347 
349 
363  template<
364  typename CallbackT,
365  typename AllocatorT = std::allocator<void>>
366  std::shared_ptr<rclcpp::GenericSubscription> create_generic_subscription(
367  const std::string & topic_name,
368  const std::string & topic_type,
369  const rclcpp::QoS & qos,
370  CallbackT && callback,
373  )
374  );
375 
377 
428  RCLCPP_PUBLIC
429  const rclcpp::ParameterValue &
431  const std::string & name,
432  const rclcpp::ParameterValue & default_value,
433  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
434  rcl_interfaces::msg::ParameterDescriptor(),
435  bool ignore_override = false);
436 
438 
453  RCLCPP_PUBLIC
454  const rclcpp::ParameterValue &
456  const std::string & name,
457  rclcpp::ParameterType type,
458  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
459  rcl_interfaces::msg::ParameterDescriptor{},
460  bool ignore_override = false);
461 
463 
483  template<typename ParameterT>
484  auto
486  const std::string & name,
487  const ParameterT & default_value,
488  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
489  rcl_interfaces::msg::ParameterDescriptor(),
490  bool ignore_override = false);
491 
493 
496  template<typename ParameterT>
497  auto
499  const std::string & name,
500  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
501  rcl_interfaces::msg::ParameterDescriptor(),
502  bool ignore_override = false);
503 
505 
551  template<typename ParameterT>
552  std::vector<ParameterT>
554  const std::string & namespace_,
555  const std::map<std::string, ParameterT> & parameters,
556  bool ignore_overrides = false);
557 
559 
565  template<typename ParameterT>
566  std::vector<ParameterT>
568  const std::string & namespace_,
569  const std::map<
570  std::string,
571  std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
572  > & parameters,
573  bool ignore_overrides = false);
574 
576 
587  RCLCPP_PUBLIC
588  void
589  undeclare_parameter(const std::string & name);
590 
592 
596  RCLCPP_PUBLIC
597  bool
598  has_parameter(const std::string & name) const;
599 
601 
642  RCLCPP_PUBLIC
643  rcl_interfaces::msg::SetParametersResult
644  set_parameter(const rclcpp::Parameter & parameter);
645 
647 
694  RCLCPP_PUBLIC
695  std::vector<rcl_interfaces::msg::SetParametersResult>
696  set_parameters(const std::vector<rclcpp::Parameter> & parameters);
697 
699 
742  RCLCPP_PUBLIC
743  rcl_interfaces::msg::SetParametersResult
744  set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
745 
747 
766  RCLCPP_PUBLIC
768  get_parameter(const std::string & name) const;
769 
771 
785  RCLCPP_PUBLIC
786  bool
787  get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
788 
790 
802  template<typename ParameterT>
803  bool
804  get_parameter(const std::string & name, ParameterT & parameter) const;
805 
807 
821  template<typename ParameterT>
822  bool
824  const std::string & name,
825  ParameterT & parameter,
826  const ParameterT & alternative_value) const;
827 
829 
840  template<typename ParameterT>
841  ParameterT
843  const std::string & name,
844  const ParameterT & alternative_value) const;
845 
847 
866  RCLCPP_PUBLIC
867  std::vector<rclcpp::Parameter>
868  get_parameters(const std::vector<std::string> & names) const;
869 
871 
907  template<typename ParameterT>
908  bool
910  const std::string & prefix,
911  std::map<std::string, ParameterT> & values) const;
912 
914 
930  RCLCPP_PUBLIC
931  rcl_interfaces::msg::ParameterDescriptor
932  describe_parameter(const std::string & name) const;
933 
935 
953  RCLCPP_PUBLIC
954  std::vector<rcl_interfaces::msg::ParameterDescriptor>
955  describe_parameters(const std::vector<std::string> & names) const;
956 
958 
973  RCLCPP_PUBLIC
974  std::vector<uint8_t>
975  get_parameter_types(const std::vector<std::string> & names) const;
976 
978 
990  RCLCPP_PUBLIC
991  rcl_interfaces::msg::ListParametersResult
992  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
993 
996  using PreSetParametersCallbackType =
997  rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType;
998 
1001  using OnSetParametersCallbackType =
1002  rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType;
1003 
1006  using PostSetParametersCallbackType =
1007  rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType;
1008 
1010 
1065  RCLCPP_PUBLIC
1066  RCUTILS_WARN_UNUSED
1067  PreSetParametersCallbackHandle::SharedPtr
1068  add_pre_set_parameters_callback(PreSetParametersCallbackType callback);
1069 
1071 
1139  RCLCPP_PUBLIC
1140  RCUTILS_WARN_UNUSED
1141  OnSetParametersCallbackHandle::SharedPtr
1142  add_on_set_parameters_callback(OnSetParametersCallbackType callback);
1143 
1145 
1200  RCLCPP_PUBLIC
1201  RCUTILS_WARN_UNUSED
1202  PostSetParametersCallbackHandle::SharedPtr
1203  add_post_set_parameters_callback(PostSetParametersCallbackType callback);
1204 
1206 
1213  RCLCPP_PUBLIC
1214  void
1216 
1218 
1240  RCLCPP_PUBLIC
1241  void
1243 
1245 
1252  RCLCPP_PUBLIC
1253  void
1255 
1257 
1261  RCLCPP_PUBLIC
1262  std::vector<std::string>
1263  get_node_names() const;
1264 
1266 
1270  RCLCPP_PUBLIC
1271  std::map<std::string, std::vector<std::string>>
1272  get_topic_names_and_types() const;
1273 
1275 
1279  RCLCPP_PUBLIC
1280  std::map<std::string, std::vector<std::string>>
1282 
1284 
1293  RCLCPP_PUBLIC
1294  std::map<std::string, std::vector<std::string>>
1296  const std::string & node_name,
1297  const std::string & namespace_) const;
1298 
1300 
1305  RCLCPP_PUBLIC
1306  size_t
1307  count_publishers(const std::string & topic_name) const;
1308 
1310 
1315  RCLCPP_PUBLIC
1316  size_t
1317  count_subscribers(const std::string & topic_name) const;
1318 
1320 
1325  RCLCPP_PUBLIC
1326  size_t
1327  count_clients(const std::string & service_name) const;
1328 
1330 
1335  RCLCPP_PUBLIC
1336  size_t
1337  count_services(const std::string & service_name) const;
1338 
1340 
1361  RCLCPP_PUBLIC
1362  std::vector<rclcpp::TopicEndpointInfo>
1363  get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
1364 
1366 
1387  RCLCPP_PUBLIC
1388  std::vector<rclcpp::TopicEndpointInfo>
1389  get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
1390 
1392  /* The graph Event object is a loan which must be returned.
1393  * The Event object is scoped and therefore to return the loan just let it go
1394  * out of scope.
1395  */
1396  RCLCPP_PUBLIC
1397  rclcpp::Event::SharedPtr
1398  get_graph_event();
1399 
1401 
1411  RCLCPP_PUBLIC
1412  void
1414  rclcpp::Event::SharedPtr event,
1415  std::chrono::nanoseconds timeout);
1416 
1418 
1421  RCLCPP_PUBLIC
1422  rclcpp::Clock::SharedPtr
1423  get_clock();
1424 
1426 
1429  RCLCPP_PUBLIC
1430  rclcpp::Clock::ConstSharedPtr
1431  get_clock() const;
1432 
1434 
1437  RCLCPP_PUBLIC
1438  Time
1439  now() const;
1440 
1442  RCLCPP_PUBLIC
1443  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
1445 
1447  RCLCPP_PUBLIC
1448  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
1450 
1452  RCLCPP_PUBLIC
1453  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
1455 
1457  RCLCPP_PUBLIC
1458  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
1460 
1462  RCLCPP_PUBLIC
1463  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
1465 
1467  RCLCPP_PUBLIC
1468  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
1470 
1472  RCLCPP_PUBLIC
1473  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
1475 
1477  RCLCPP_PUBLIC
1478  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
1480 
1482  RCLCPP_PUBLIC
1483  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
1485 
1487  RCLCPP_PUBLIC
1488  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
1490 
1492  RCLCPP_PUBLIC
1493  rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr
1495 
1497 
1524  RCLCPP_PUBLIC
1525  const std::string &
1526  get_sub_namespace() const;
1527 
1529 
1552  RCLCPP_PUBLIC
1553  const std::string &
1554  get_effective_namespace() const;
1555 
1557 
1598  RCLCPP_PUBLIC
1599  rclcpp::Node::SharedPtr
1600  create_sub_node(const std::string & sub_namespace);
1601 
1603  RCLCPP_PUBLIC
1604  const rclcpp::NodeOptions &
1605  get_node_options() const;
1606 
1607 protected:
1609 
1615  RCLCPP_PUBLIC
1616  Node(
1617  const Node & other,
1618  const std::string & sub_namespace);
1619 
1620 private:
1621  RCLCPP_DISABLE_COPY(Node)
1622 
1623  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
1624  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
1625  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
1626  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
1627  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
1628  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
1629  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
1630  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
1631  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
1632  rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr node_type_descriptions_;
1633  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1634 
1635  const rclcpp::NodeOptions node_options_;
1636  const std::string sub_namespace_;
1637  const std::string effective_namespace_;
1638 
1639  class NodeImpl;
1640  // This member is meant to be a place to backport features into stable distributions,
1641  // and new features targeting Rolling should not use this.
1642  // See the comment in node.cpp for more information.
1643  std::shared_ptr<NodeImpl> hidden_impl_{nullptr};
1644 };
1645 
1646 } // namespace rclcpp
1647 
1648 #ifndef RCLCPP__NODE_IMPL_HPP_
1649 // Template implementations
1650 #include "node_impl.hpp"
1651 #endif
1652 
1653 #endif // RCLCPP__NODE_HPP_
Generic timer. Periodically executes a user-specified callback.
Definition: timer.hpp:226
Encapsulation of options for node initialization.
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:81
RCLCPP_PUBLIC rclcpp::Logger get_logger() const
Get the logger of the node.
Definition: node.cpp:330
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
Definition: node.cpp:650
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
Definition: node.cpp:626
rclcpp::GenericService::SharedPtr create_generic_service(const std::string &service_name, const std::string &service_type, CallbackT &&callback, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a GenericService.
Definition: node_impl.hpp:177
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:414
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnSetParametersCallbackType callback)
Add a callback to validate parameters before they are set.
Definition: node.cpp:458
RCLCPP_PUBLIC bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
Definition: node.cpp:378
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:668
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)
Set a single parameter.
Definition: node.cpp:384
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:572
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
Definition: node.cpp:620
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
Definition: node.cpp:644
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:539
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:344
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
Definition: node.cpp:608
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:338
RCLCPP_PUBLIC const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
Definition: node.cpp:662
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:515
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.
Definition: node_impl.hpp:128
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:500
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:521
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:275
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:434
RCLCPP_PUBLIC Time now() const
Returns current time from the node clock.
Definition: node.cpp:584
RCLCPP_PUBLIC rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
Definition: node.cpp:558
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:551
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:421
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:476
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:494
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.
Definition: node.cpp:402
RCLCPP_PUBLIC Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
Definition: node.cpp:130
RCLCPP_PUBLIC size_t count_services(const std::string &service_name) const
Return the number of services created for a given service.
Definition: node.cpp:533
RCLCPP_PUBLIC const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
Definition: node.cpp:676
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
Definition: node.cpp:590
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.
Definition: node.cpp:682
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:396
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:564
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
Definition: node.cpp:596
RCLCPP_PUBLIC void remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle *const handler)
Remove a callback registered with add_pre_set_parameters_callback.
Definition: node.cpp:470
RCLCPP_PUBLIC const char * get_name() const
Get the name of the node.
Definition: node.cpp:312
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:390
rclcpp::Service< ServiceT >::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
Definition: node_impl.hpp:160
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr get_node_type_descriptions_interface()
Return the Node's internal NodeTypeDescriptionsInterface implementation.
Definition: node.cpp:632
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
Definition: node.cpp:638
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:506
RCLCPP_PUBLIC void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
Definition: node.cpp:372
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:440
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:545
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.
Definition: node_impl.hpp:213
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:336
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeTimeSourceInterface implementation.
Definition: node.cpp:614
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED PreSetParametersCallbackHandle::SharedPtr add_pre_set_parameters_callback(PreSetParametersCallbackType callback)
Add a callback that gets triggered before parameters are validated.
Definition: node.cpp:452
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:446
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_PUBLIC size_t count_clients(const std::string &service_name) const
Return the number of clients created for a given service.
Definition: node.cpp:527
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:74
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.
Definition: node_impl.hpp:111
RCLCPP_PUBLIC const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
Definition: node.cpp:324
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:656
RCLCPP_PUBLIC std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.
Definition: node.cpp:488
RCLCPP_PUBLIC const char * get_namespace() const
Get the namespace of the node.
Definition: node.cpp:318
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.
Definition: node.cpp:464
RCLCPP_PUBLIC rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
Definition: node.cpp:602
RCLCPP_PUBLIC void remove_post_set_parameters_callback(const PostSetParametersCallbackHandle *const handler)
Remove a callback registered with add_post_set_parameters_callback.
Definition: node.cpp:482
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:196
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:81
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
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.