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 <list>
21 #include <map>
22 #include <memory>
23 #include <mutex>
24 #include <string>
25 #include <tuple>
26 #include <utility>
27 #include <vector>
28 
29 #include "rcl/error_handling.h"
30 #include "rcl/node.h"
31 
32 #include "rcl_interfaces/msg/list_parameters_result.hpp"
33 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
34 #include "rcl_interfaces/msg/parameter_event.hpp"
35 #include "rcl_interfaces/msg/set_parameters_result.hpp"
36 
38 #include "rclcpp/client.hpp"
39 #include "rclcpp/clock.hpp"
40 #include "rclcpp/context.hpp"
41 #include "rclcpp/event.hpp"
42 #include "rclcpp/logger.hpp"
43 #include "rclcpp/macros.hpp"
55 #include "rclcpp/node_options.hpp"
56 #include "rclcpp/parameter.hpp"
57 #include "rclcpp/publisher.hpp"
59 #include "rclcpp/qos.hpp"
60 #include "rclcpp/service.hpp"
61 #include "rclcpp/subscription.hpp"
64 #include "rclcpp/time.hpp"
65 #include "rclcpp/timer.hpp"
67 
68 namespace rclcpp
69 {
70 
72 class Node : public std::enable_shared_from_this<Node>
73 {
74 public:
76 
77 
78 
83  explicit Node(
84  const std::string & node_name,
85  const NodeOptions & options = NodeOptions());
86 
88 
94  explicit Node(
95  const std::string & node_name,
96  const std::string & namespace_,
97  const NodeOptions & options = NodeOptions());
98 
100  virtual ~Node();
101 
103 
105  const char *
106  get_name() const;
107 
109 
119  const char *
120  get_namespace() const;
121 
123 
127  const char *
128  get_fully_qualified_name() const;
129 
131 
134  get_logger() const;
135 
138  rclcpp::callback_group::CallbackGroup::SharedPtr
140 
144  get_callback_groups() const;
145 
147 
172  template<
173  typename MessageT,
174  typename AllocatorT = std::allocator<void>,
175  typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>>
178  const std::string & topic_name,
179  const rclcpp::QoS & qos,
182  );
183 
185 
191  template<
192  typename MessageT,
193  typename AllocatorT = std::allocator<void>,
194  typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>>
195  // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
196  [[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]]
199  const std::string & topic_name,
200  size_t qos_history_depth,
201  std::shared_ptr<AllocatorT> allocator);
202 
204 
210  template<
211  typename MessageT,
212  typename AllocatorT = std::allocator<void>,
213  typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>>
214  // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
215  [[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]]
218  const std::string & topic_name,
219  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
220  std::shared_ptr<AllocatorT> allocator = nullptr);
221 
223 
231  /* TODO(jacquelinekay):
232  Windows build breaks when static member function passed as default
233  argument to msg_mem_strat, nullptr is a workaround.
234  */
235  template<
236  typename MessageT,
237  typename CallbackT,
238  typename AllocatorT = std::allocator<void>,
239  typename SubscriptionT = rclcpp::Subscription<
243  const std::string & topic_name,
244  const rclcpp::QoS & qos,
245  CallbackT && callback,
249  typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, AllocatorT
250  >::SharedPtr
251  msg_mem_strat = nullptr);
252 
254 
264  /* TODO(jacquelinekay):
265  Windows build breaks when static member function passed as default
266  argument to msg_mem_strat, nullptr is a workaround.
267  */
268  template<
269  typename MessageT,
270  typename CallbackT,
271  typename Alloc = std::allocator<void>,
272  typename SubscriptionT = rclcpp::Subscription<
273  typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>>
274  // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
275  [[deprecated(
276  "use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead"
277  )]]
280  const std::string & topic_name,
281  CallbackT && callback,
282  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
283  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
284  bool ignore_local_publications = false,
286  typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
287  msg_mem_strat = nullptr,
288  std::shared_ptr<Alloc> allocator = nullptr);
289 
291 
301  /* TODO(jacquelinekay):
302  Windows build breaks when static member function passed as default
303  argument to msg_mem_strat, nullptr is a workaround.
304  */
305  template<
306  typename MessageT,
307  typename CallbackT,
308  typename Alloc = std::allocator<void>,
309  typename SubscriptionT = rclcpp::Subscription<
310  typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>>
311  // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
312  [[deprecated(
313  "use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead"
314  )]]
317  const std::string & topic_name,
318  CallbackT && callback,
319  size_t qos_history_depth,
320  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
321  bool ignore_local_publications = false,
323  typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
324  msg_mem_strat = nullptr,
325  std::shared_ptr<Alloc> allocator = nullptr);
326 
328 
333  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
337  CallbackT callback,
338  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
339 
340  /* Create and return a Client. */
341  template<typename ServiceT>
344  const std::string & service_name,
345  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
346  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
347 
348  /* Create and return a Service. */
349  template<typename ServiceT, typename CallbackT>
352  const std::string & service_name,
353  CallbackT && callback,
354  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
355  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
356 
358 
394  const rclcpp::ParameterValue &
396  const std::string & name,
397  const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
398  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
399  rcl_interfaces::msg::ParameterDescriptor());
400 
402 
422  template<typename ParameterT>
423  auto
425  const std::string & name,
426  const ParameterT & default_value,
427  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
428  rcl_interfaces::msg::ParameterDescriptor());
429 
431 
463  template<typename ParameterT>
466  const std::string & namespace_,
467  const std::map<std::string, ParameterT> & parameters);
468 
470 
476  template<typename ParameterT>
479  const std::string & namespace_,
480  const std::map<
481  std::string,
483  > & parameters);
484 
486 
497  void
498  undeclare_parameter(const std::string & name);
499 
501 
506  bool
507  has_parameter(const std::string & name) const;
508 
510 
538  rcl_interfaces::msg::SetParametersResult
539  set_parameter(const rclcpp::Parameter & parameter);
540 
542 
578 
580 
610  rcl_interfaces::msg::SetParametersResult
612 
614 
622  template<typename ParameterT>
623  // cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
624  [[deprecated("use declare_parameter() instead")]]
625  void
626  set_parameter_if_not_set(const std::string & name, const ParameterT & value);
627 
629 
638  template<typename ParameterT>
639  [[deprecated("use declare_parameters() instead")]]
640  void
642  const std::string & name,
643  const std::map<std::string, ParameterT> & values);
644 
646 
663  get_parameter(const std::string & name) const;
664 
666 
681  bool
682  get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
683 
685 
697  template<typename ParameterT>
698  bool
699  get_parameter(const std::string & name, ParameterT & parameter) const;
700 
702 
716  template<typename ParameterT>
717  bool
719  const std::string & name,
720  ParameterT & parameter,
721  const ParameterT & alternative_value) const;
722 
724 
743  get_parameters(const std::vector<std::string> & names) const;
744 
746 
782  template<typename ParameterT>
783  bool
785  const std::string & prefix,
786  std::map<std::string, ParameterT> & values) const;
787 
789 
802  template<typename ParameterT>
803  [[deprecated("use declare_parameter() and it's return value instead")]]
804  void
806  const std::string & name,
807  ParameterT & value,
808  const ParameterT & alternative_value);
809 
811 
827  rcl_interfaces::msg::ParameterDescriptor
828  describe_parameter(const std::string & name) const;
829 
831 
850  describe_parameters(const std::vector<std::string> & names) const;
851 
853 
870  get_parameter_types(const std::vector<std::string> & names) const;
871 
873 
877  rcl_interfaces::msg::ListParametersResult
878  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
879 
882 
884 
931 
933 
938  template<typename CallbackT>
939  [[deprecated("use set_on_parameters_set_callback() instead")]]
940  void
941  register_param_change_callback(CallbackT && callback);
942 
944 
950  get_node_names() const;
951 
955 
959 
961  size_t
962  count_publishers(const std::string & topic_name) const;
963 
965  size_t
966  count_subscribers(const std::string & topic_name) const;
967 
969  /* The graph Event object is a loan which must be returned.
970  * The Event object is scoped and therefore to return the loan just let it go
971  * out of scope.
972  */
974  rclcpp::Event::SharedPtr
975  get_graph_event();
976 
978 
986  void
988  rclcpp::Event::SharedPtr event,
989  std::chrono::nanoseconds timeout);
990 
992  rclcpp::Clock::SharedPtr
993  get_clock();
994 
996  Time
997  now();
998 
1001  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
1003 
1006  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
1008 
1011  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
1013 
1016  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
1018 
1021  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
1023 
1026  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
1028 
1031  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
1033 
1036  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
1038 
1041  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
1043 
1046  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
1048 
1050 
1076  const std::string &
1077  get_sub_namespace() const;
1078 
1080 
1102  const std::string &
1103  get_effective_namespace() const;
1104 
1106 
1144  rclcpp::Node::SharedPtr
1145  create_sub_node(const std::string & sub_namespace);
1146 
1149  const rclcpp::NodeOptions &
1150  get_node_options() const;
1151 
1153 
1162  bool
1163  assert_liveliness() const;
1164 
1165 protected:
1167 
1174  Node(
1175  const Node & other,
1176  const std::string & sub_namespace);
1177 
1178 private:
1179  RCLCPP_DISABLE_COPY(Node)
1180 
1182  bool
1183  group_in_node(callback_group::CallbackGroup::SharedPtr group);
1184 
1185  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
1186  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
1187  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
1188  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
1189  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
1190  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
1191  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
1192  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
1193  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
1194  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1195 
1196  const rclcpp::NodeOptions node_options_;
1197  const std::string sub_namespace_;
1198  const std::string effective_namespace_;
1199 };
1200 
1201 } // namespace rclcpp
1202 
1203 #ifndef RCLCPP__NODE_IMPL_HPP_
1204 // Template implementations
1205 #include "node_impl.hpp"
1206 #endif
1207 
1208 #endif // RCLCPP__NODE_HPP_
void register_param_change_callback(CallbackT &&callback)
Register the callback for parameter changes.
Definition: node_impl.hpp:414
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node&#39;s internal NodeServicesInterface implementation.
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node&#39;s internal NodeTimersInterface implementation.
Definition: logger.hpp:77
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:40
std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const
Return a vector of parameter types, one for each of the given names.
rclcpp::callback_group::CallbackGroup::SharedPtr create_callback_group(rclcpp::callback_group::CallbackGroupType group_type)
Create and return a callback group.
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)
Set a single parameter.
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:360
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const
Return a vector of parameter descriptors, one for each of the given names.
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node&#39;s internal NodeBaseInterface implementation.
Encapsulation of Quality of Service settings.
Definition: qos.hpp:55
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:51
Definition: timer.hpp:202
Encapsulation of options for node initialization.
Definition: node_options.hpp:34
rclcpp::Clock::SharedPtr get_clock()
std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.
virtual ~Node()
CallbackGroupType
Definition: callback_group.hpp:46
bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
size_t count_subscribers(const std::string &topic_name) const
const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
This header provides the get_node_topics_interface() template function.
Definition: allocator_common.hpp:24
rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
Definition: service.hpp:88
std::vector< ParameterT > declare_parameters(const std::string &namespace_, const std::map< std::string, ParameterT > &parameters)
Declare and initialize several parameters with the same namespace and type.
Definition: node_impl.hpp:264
Definition: client.hpp:119
void get_parameter_or_set(const std::string &name, ParameterT &value, const ParameterT &alternative_value)
Get the parameter value; if not set, set the "alternative value" and store it in the node...
Definition: node_impl.hpp:396
rclcpp::Logger get_logger() const
Get the logger of the node.
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:59
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node&#39;s internal NodeLoggingInterface implementation.
std::function< rcl_interfaces::msg::SetParametersResult(const std::vector< rclcpp::Parameter > &) > OnParametersSetCallbackType
Definition: node_parameters_interface.hpp:162
typename std::remove_cv< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > >::type type
Definition: subscription_traits.hpp:65
const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, one at a time.
rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
void set_parameters_if_not_set(const std::string &name, const std::map< std::string, ParameterT > &values)
Set a map of parameters with the same prefix.
Definition: node_impl.hpp:323
rclcpp::Node::OnParametersSetCallbackType set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback)
Register a callback to be called anytime a parameter is about to be changed.
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:46
RCUTILS_WARN_UNUSED bool assert_liveliness() const
Manually assert that this Node is alive (for RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE).
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:69
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.
Structure containing optional configuration for Publishers.
Definition: publisher_options.hpp:47
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node&#39;s internal NodeTopicsInterface implementation.
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:46
void set_parameter_if_not_set(const std::string &name, const ParameterT &value)
Set one parameter, unless that parameter has already been set.
Definition: node_impl.hpp:306
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
Create a timer.
Definition: node_impl.hpp:194
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value=rclcpp::ParameterValue(), const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor())
Declare and initialize a parameter, return the effective value.
size_t count_publishers(const std::string &topic_name) const
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node&#39;s internal NodeParametersInterface implementation.
std::map< std::string, std::vector< std::string > > get_topic_names_and_types() const
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node&#39;s internal NodeClockInterface implementation.
#define RCUTILS_WARN_UNUSED
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node&#39;s internal NodeGraphInterface implementation.
void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node&#39;s internal NodeParametersInterface implementation.
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
std::shared_ptr< SubscriptionT > create_subscription(const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const SubscriptionOptionsWithAllocator< AllocatorT > &options=SubscriptionOptionsWithAllocator< AllocatorT >(), typename rclcpp::message_memory_strategy::MessageMemoryStrategy< typename rclcpp::subscription_traits::has_message_type< CallbackT >::type, AllocatorT >::SharedPtr msg_mem_strat=nullptr)
Create and return a Subscription.
Definition: node_impl.hpp:115
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
Definition: time.hpp:31
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, all at once.
const char * get_name() const
Get the name of the node.
const char * get_namespace() const
Get the namespace of the node.
const std::vector< rclcpp::callback_group::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
std::map< std::string, std::vector< std::string > > get_service_names_and_types() const
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:72
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.
const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
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.
Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
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::callback_group::CallbackGroup::SharedPtr group=nullptr)
Definition: node_impl.hpp:233
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node&#39;s internal NodeWaitablesInterface implementation.