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 
174  template<
175  typename MessageT,
176  typename AllocatorT = std::allocator<void>,
177  typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
180  const std::string & topic_name,
181  const rclcpp::QoS & qos,
184  );
185 
187 
195  template<
196  typename MessageT,
197  typename CallbackT,
198  typename AllocatorT = std::allocator<void>,
199  typename CallbackMessageT =
202  typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
203  CallbackMessageT,
204  AllocatorT
205  >
206  >
209  const std::string & topic_name,
210  const rclcpp::QoS & qos,
211  CallbackT && callback,
214  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
215  MessageMemoryStrategyT::create_default()
216  )
217  );
218 
220 
225  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
229  CallbackT callback,
230  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
231 
232  /* Create and return a Client. */
233  template<typename ServiceT>
236  const std::string & service_name,
237  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
238  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
239 
240  /* Create and return a Service. */
241  template<typename ServiceT, typename CallbackT>
244  const std::string & service_name,
245  CallbackT && callback,
246  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
247  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
248 
250 
290  const rclcpp::ParameterValue &
292  const std::string & name,
293  const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
294  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
295  rcl_interfaces::msg::ParameterDescriptor(),
296  bool ignore_override = false);
297 
299 
319  template<typename ParameterT>
320  auto
322  const std::string & name,
323  const ParameterT & default_value,
324  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
325  rcl_interfaces::msg::ParameterDescriptor(),
326  bool ignore_override = false);
327 
329 
364  template<typename ParameterT>
367  const std::string & namespace_,
368  const std::map<std::string, ParameterT> & parameters,
369  bool ignore_overrides = false);
370 
372 
378  template<typename ParameterT>
381  const std::string & namespace_,
382  const std::map<
383  std::string,
385  > & parameters,
386  bool ignore_overrides = false);
387 
389 
400  void
401  undeclare_parameter(const std::string & name);
402 
404 
409  bool
410  has_parameter(const std::string & name) const;
411 
413 
442  rcl_interfaces::msg::SetParametersResult
443  set_parameter(const rclcpp::Parameter & parameter);
444 
446 
482 
484 
514  rcl_interfaces::msg::SetParametersResult
516 
518 
535  get_parameter(const std::string & name) const;
536 
538 
553  bool
554  get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
555 
557 
569  template<typename ParameterT>
570  bool
571  get_parameter(const std::string & name, ParameterT & parameter) const;
572 
574 
588  template<typename ParameterT>
589  bool
591  const std::string & name,
592  ParameterT & parameter,
593  const ParameterT & alternative_value) const;
594 
596 
615  get_parameters(const std::vector<std::string> & names) const;
616 
618 
654  template<typename ParameterT>
655  bool
657  const std::string & prefix,
658  std::map<std::string, ParameterT> & values) const;
659 
661 
677  rcl_interfaces::msg::ParameterDescriptor
678  describe_parameter(const std::string & name) const;
679 
681 
700  describe_parameters(const std::vector<std::string> & names) const;
701 
703 
720  get_parameter_types(const std::vector<std::string> & names) const;
721 
723 
727  rcl_interfaces::msg::ListParametersResult
728  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
729 
734 
736 
799 
801 
824  void
826 
828 
844 
846 
852  get_node_names() const;
853 
857 
861 
863  size_t
864  count_publishers(const std::string & topic_name) const;
865 
867  size_t
868  count_subscribers(const std::string & topic_name) const;
869 
871  /* The graph Event object is a loan which must be returned.
872  * The Event object is scoped and therefore to return the loan just let it go
873  * out of scope.
874  */
877  get_graph_event();
878 
880 
888  void
891  std::chrono::nanoseconds timeout);
892 
895  get_clock();
896 
898  Time
899  now();
900 
903  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
905 
908  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
910 
913  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
915 
918  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
920 
923  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
925 
928  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
930 
933  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
935 
938  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
940 
943  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
945 
948  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
950 
952 
980  const std::string &
981  get_sub_namespace() const;
982 
984 
1008  const std::string &
1009  get_effective_namespace() const;
1010 
1012 
1051  create_sub_node(const std::string & sub_namespace);
1052 
1055  const rclcpp::NodeOptions &
1056  get_node_options() const;
1057 
1059 
1068  bool
1069  assert_liveliness() const;
1070 
1071 protected:
1073 
1080  Node(
1081  const Node & other,
1082  const std::string & sub_namespace);
1083 
1084 private:
1085  RCLCPP_DISABLE_COPY(Node)
1086 
1088  bool
1089  group_in_node(callback_group::CallbackGroup::SharedPtr group);
1090 
1091  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
1092  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
1093  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
1094  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
1095  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
1096  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
1097  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
1098  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
1099  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
1100  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1101 
1102  const rclcpp::NodeOptions node_options_;
1103  const std::string sub_namespace_;
1104  const std::string effective_namespace_;
1105 };
1106 
1107 } // namespace rclcpp
1108 
1109 #ifndef RCLCPP__NODE_IMPL_HPP_
1110 // Template implementations
1111 #include "node_impl.hpp"
1112 #endif
1113 
1114 #endif // RCLCPP__NODE_HPP_
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.
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:171
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:236
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:214
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.
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:89
OnParametersSetCallbackType set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback)
Register a callback to be called anytime a parameter is about to be changed.
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_base_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:89
Definition: client.hpp:119
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:67
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node&#39;s internal NodeLoggingInterface implementation.
typename std::remove_cv< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > >::type type
Definition: subscription_traits.hpp:65
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(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
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.
OnSetParametersCallbackHandle::OnParametersSetCallbackType OnParametersSetCallbackType
Definition: node_parameters_interface.hpp:174
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:51
void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
RCUTILS_WARN_UNUSED bool assert_liveliness() const
Manually assert that this Node is alive (for RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE).
Definition: node_parameters_interface.hpp:36
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.
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node&#39;s internal NodeTopicsInterface implementation.
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:107
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Set the data type used in the intra-process buffer as std::shared_ptr<MessageT>
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
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.
OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)
Add a callback for when parameters are being set.
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:138
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node&#39;s internal NodeWaitablesInterface implementation.