ROS 2 rclcpp + rcl - jazzy  jazzy
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_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"
74 
75 namespace rclcpp
76 {
77 
79 class Node : public std::enable_shared_from_this<Node>
80 {
81 public:
82  RCLCPP_SMART_PTR_DEFINITIONS(Node)
83 
84 
90  RCLCPP_PUBLIC
91  explicit Node(
92  const std::string & node_name,
93  const NodeOptions & options = NodeOptions());
94 
96 
102  RCLCPP_PUBLIC
103  explicit Node(
104  const std::string & node_name,
105  const std::string & namespace_,
106  const NodeOptions & options = NodeOptions());
107 
108  RCLCPP_PUBLIC
109  virtual ~Node();
110 
112 
113  RCLCPP_PUBLIC
114  const char *
115  get_name() const;
116 
118 
127  RCLCPP_PUBLIC
128  const char *
129  get_namespace() const;
130 
132 
136  RCLCPP_PUBLIC
137  const char *
138  get_fully_qualified_name() const;
139 
141 
142  RCLCPP_PUBLIC
144  get_logger() const;
145 
147  RCLCPP_PUBLIC
148  rclcpp::CallbackGroup::SharedPtr
150  rclcpp::CallbackGroupType group_type,
151  bool automatically_add_to_executor_with_node = true);
152 
154 
160  RCLCPP_PUBLIC
161  void
162  for_each_callback_group(const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func);
163 
165 
192  template<
193  typename MessageT,
194  typename AllocatorT = std::allocator<void>,
195  typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
196  std::shared_ptr<PublisherT>
198  const std::string & topic_name,
199  const rclcpp::QoS & qos,
202  );
203 
205 
213  template<
214  typename MessageT,
215  typename CallbackT,
216  typename AllocatorT = std::allocator<void>,
217  typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
218  typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType
219  >
220  std::shared_ptr<SubscriptionT>
222  const std::string & topic_name,
223  const rclcpp::QoS & qos,
224  CallbackT && callback,
227  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
228  MessageMemoryStrategyT::create_default()
229  )
230  );
231 
233 
239  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
242  std::chrono::duration<DurationRepT, DurationT> period,
243  CallbackT callback,
244  rclcpp::CallbackGroup::SharedPtr group = nullptr,
245  bool autostart = true);
246 
248 
253  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
255  create_timer(
256  std::chrono::duration<DurationRepT, DurationT> period,
257  CallbackT callback,
258  rclcpp::CallbackGroup::SharedPtr group = nullptr);
259 
261 
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);
275 
277 
283  template<typename ServiceT>
286  const std::string & service_name,
287  const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
288  rclcpp::CallbackGroup::SharedPtr group = nullptr);
289 
291 
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);
307 
309 
316  template<typename ServiceT, typename CallbackT>
319  const std::string & service_name,
320  CallbackT && callback,
321  const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
322  rclcpp::CallbackGroup::SharedPtr group = nullptr);
323 
325 
332  RCLCPP_PUBLIC
333  rclcpp::GenericClient::SharedPtr
335  const std::string & service_name,
336  const std::string & service_type,
337  const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
338  rclcpp::CallbackGroup::SharedPtr group = nullptr);
339 
341 
353  template<typename AllocatorT = std::allocator<void>>
354  std::shared_ptr<rclcpp::GenericPublisher> create_generic_publisher(
355  const std::string & topic_name,
356  const std::string & topic_type,
357  const rclcpp::QoS & qos,
360  )
361  );
362 
364 
378  template<
379  typename CallbackT,
380  typename AllocatorT = std::allocator<void>>
381  std::shared_ptr<rclcpp::GenericSubscription> create_generic_subscription(
382  const std::string & topic_name,
383  const std::string & topic_type,
384  const rclcpp::QoS & qos,
385  CallbackT && callback,
388  )
389  );
390 
392 
443  RCLCPP_PUBLIC
444  const rclcpp::ParameterValue &
446  const std::string & name,
447  const rclcpp::ParameterValue & default_value,
448  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
449  rcl_interfaces::msg::ParameterDescriptor(),
450  bool ignore_override = false);
451 
453 
468  RCLCPP_PUBLIC
469  const rclcpp::ParameterValue &
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);
476 
478 
498  template<typename ParameterT>
499  auto
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);
506 
508 
511  template<typename ParameterT>
512  auto
514  const std::string & name,
515  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
516  rcl_interfaces::msg::ParameterDescriptor(),
517  bool ignore_override = false);
518 
520 
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);
572 
574 
580  template<typename ParameterT>
581  std::vector<ParameterT>
583  const std::string & namespace_,
584  const std::map<
585  std::string,
586  std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
587  > & parameters,
588  bool ignore_overrides = false);
589 
591 
602  RCLCPP_PUBLIC
603  void
604  undeclare_parameter(const std::string & name);
605 
607 
611  RCLCPP_PUBLIC
612  bool
613  has_parameter(const std::string & name) const;
614 
616 
657  RCLCPP_PUBLIC
658  rcl_interfaces::msg::SetParametersResult
659  set_parameter(const rclcpp::Parameter & parameter);
660 
662 
709  RCLCPP_PUBLIC
710  std::vector<rcl_interfaces::msg::SetParametersResult>
711  set_parameters(const std::vector<rclcpp::Parameter> & parameters);
712 
714 
757  RCLCPP_PUBLIC
758  rcl_interfaces::msg::SetParametersResult
759  set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
760 
762 
781  RCLCPP_PUBLIC
783  get_parameter(const std::string & name) const;
784 
786 
800  RCLCPP_PUBLIC
801  bool
802  get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
803 
805 
817  template<typename ParameterT>
818  bool
819  get_parameter(const std::string & name, ParameterT & parameter) const;
820 
822 
836  template<typename ParameterT>
837  bool
839  const std::string & name,
840  ParameterT & parameter,
841  const ParameterT & alternative_value) const;
842 
844 
855  template<typename ParameterT>
856  ParameterT
858  const std::string & name,
859  const ParameterT & alternative_value) const;
860 
862 
881  RCLCPP_PUBLIC
882  std::vector<rclcpp::Parameter>
883  get_parameters(const std::vector<std::string> & names) const;
884 
886 
922  template<typename ParameterT>
923  bool
925  const std::string & prefix,
926  std::map<std::string, ParameterT> & values) const;
927 
929 
945  RCLCPP_PUBLIC
946  rcl_interfaces::msg::ParameterDescriptor
947  describe_parameter(const std::string & name) const;
948 
950 
968  RCLCPP_PUBLIC
969  std::vector<rcl_interfaces::msg::ParameterDescriptor>
970  describe_parameters(const std::vector<std::string> & names) const;
971 
973 
988  RCLCPP_PUBLIC
989  std::vector<uint8_t>
990  get_parameter_types(const std::vector<std::string> & names) const;
991 
993 
1005  RCLCPP_PUBLIC
1006  rcl_interfaces::msg::ListParametersResult
1007  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
1008 
1011  using PreSetParametersCallbackType =
1012  rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType;
1013 
1016  using OnSetParametersCallbackType =
1017  rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType;
1018  using OnParametersSetCallbackType [[deprecated("use OnSetParametersCallbackType instead")]] =
1019  OnSetParametersCallbackType;
1020 
1023  using PostSetParametersCallbackType =
1024  rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType;
1025 
1027 
1082  RCLCPP_PUBLIC
1083  RCUTILS_WARN_UNUSED
1084  PreSetParametersCallbackHandle::SharedPtr
1085  add_pre_set_parameters_callback(PreSetParametersCallbackType callback);
1086 
1088 
1156  RCLCPP_PUBLIC
1157  RCUTILS_WARN_UNUSED
1158  OnSetParametersCallbackHandle::SharedPtr
1159  add_on_set_parameters_callback(OnSetParametersCallbackType callback);
1160 
1162 
1217  RCLCPP_PUBLIC
1218  RCUTILS_WARN_UNUSED
1219  PostSetParametersCallbackHandle::SharedPtr
1220  add_post_set_parameters_callback(PostSetParametersCallbackType callback);
1221 
1223 
1230  RCLCPP_PUBLIC
1231  void
1233 
1235 
1257  RCLCPP_PUBLIC
1258  void
1260 
1262 
1269  RCLCPP_PUBLIC
1270  void
1272 
1274 
1278  RCLCPP_PUBLIC
1279  std::vector<std::string>
1280  get_node_names() const;
1281 
1283 
1287  RCLCPP_PUBLIC
1288  std::map<std::string, std::vector<std::string>>
1289  get_topic_names_and_types() const;
1290 
1292 
1296  RCLCPP_PUBLIC
1297  std::map<std::string, std::vector<std::string>>
1299 
1301 
1310  RCLCPP_PUBLIC
1311  std::map<std::string, std::vector<std::string>>
1313  const std::string & node_name,
1314  const std::string & namespace_) const;
1315 
1317 
1322  RCLCPP_PUBLIC
1323  size_t
1324  count_publishers(const std::string & topic_name) const;
1325 
1327 
1332  RCLCPP_PUBLIC
1333  size_t
1334  count_subscribers(const std::string & topic_name) const;
1335 
1337 
1342  RCLCPP_PUBLIC
1343  size_t
1344  count_clients(const std::string & service_name) const;
1345 
1347 
1352  RCLCPP_PUBLIC
1353  size_t
1354  count_services(const std::string & service_name) const;
1355 
1357 
1378  RCLCPP_PUBLIC
1379  std::vector<rclcpp::TopicEndpointInfo>
1380  get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
1381 
1383 
1404  RCLCPP_PUBLIC
1405  std::vector<rclcpp::TopicEndpointInfo>
1406  get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
1407 
1409  /* The graph Event object is a loan which must be returned.
1410  * The Event object is scoped and therefore to return the loan just let it go
1411  * out of scope.
1412  */
1413  RCLCPP_PUBLIC
1414  rclcpp::Event::SharedPtr
1415  get_graph_event();
1416 
1418 
1428  RCLCPP_PUBLIC
1429  void
1431  rclcpp::Event::SharedPtr event,
1432  std::chrono::nanoseconds timeout);
1433 
1435 
1438  RCLCPP_PUBLIC
1439  rclcpp::Clock::SharedPtr
1440  get_clock();
1441 
1443 
1446  RCLCPP_PUBLIC
1447  rclcpp::Clock::ConstSharedPtr
1448  get_clock() const;
1449 
1451 
1454  RCLCPP_PUBLIC
1455  Time
1456  now() const;
1457 
1459  RCLCPP_PUBLIC
1460  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
1462 
1464  RCLCPP_PUBLIC
1465  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
1467 
1469  RCLCPP_PUBLIC
1470  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
1472 
1474  RCLCPP_PUBLIC
1475  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
1477 
1479  RCLCPP_PUBLIC
1480  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
1482 
1484  RCLCPP_PUBLIC
1485  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
1487 
1489  RCLCPP_PUBLIC
1490  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
1492 
1494  RCLCPP_PUBLIC
1495  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
1497 
1499  RCLCPP_PUBLIC
1500  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
1502 
1504  RCLCPP_PUBLIC
1505  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
1507 
1509  RCLCPP_PUBLIC
1510  rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr
1512 
1514 
1541  RCLCPP_PUBLIC
1542  const std::string &
1543  get_sub_namespace() const;
1544 
1546 
1569  RCLCPP_PUBLIC
1570  const std::string &
1571  get_effective_namespace() const;
1572 
1574 
1611  RCLCPP_PUBLIC
1612  rclcpp::Node::SharedPtr
1613  create_sub_node(const std::string & sub_namespace);
1614 
1616  RCLCPP_PUBLIC
1617  const rclcpp::NodeOptions &
1618  get_node_options() const;
1619 
1620 protected:
1622 
1628  RCLCPP_PUBLIC
1629  Node(
1630  const Node & other,
1631  const std::string & sub_namespace);
1632 
1633 private:
1634  RCLCPP_DISABLE_COPY(Node)
1635 
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_;
1647 
1648  const rclcpp::NodeOptions node_options_;
1649  const std::string sub_namespace_;
1650  const std::string effective_namespace_;
1651 
1652  class NodeImpl;
1653  // This member is meant to be a place to backport features into stable distributions,
1654  // and new features targeting Rolling should not use this.
1655  // See the comment in node.cpp for more information.
1656  std::shared_ptr<NodeImpl> hidden_impl_{nullptr};
1657 };
1658 
1659 } // namespace rclcpp
1660 
1661 #ifndef RCLCPP__NODE_IMPL_HPP_
1662 // Template implementations
1663 #include "node_impl.hpp"
1664 #endif
1665 
1666 #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:80
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_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::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.
Definition: node_impl.hpp:192
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::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 &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:353
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:127
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:288
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 time source specified by clock_type.
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_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:226
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:92
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:73
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:110
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:209
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.