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 <vector>
27 
28 #include "rcl/error_handling.h"
29 #include "rcl/node.h"
30 
31 #include "rcl_interfaces/msg/list_parameters_result.hpp"
32 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
33 #include "rcl_interfaces/msg/parameter_event.hpp"
34 #include "rcl_interfaces/msg/set_parameters_result.hpp"
35 
37 #include "rclcpp/client.hpp"
38 #include "rclcpp/clock.hpp"
39 #include "rclcpp/context.hpp"
40 #include "rclcpp/event.hpp"
41 #include "rclcpp/logger.hpp"
42 #include "rclcpp/macros.hpp"
52 #include "rclcpp/parameter.hpp"
53 #include "rclcpp/publisher.hpp"
54 #include "rclcpp/service.hpp"
55 #include "rclcpp/subscription.hpp"
57 #include "rclcpp/time.hpp"
58 #include "rclcpp/timer.hpp"
60 
61 namespace rclcpp
62 {
63 
65 class Node : public std::enable_shared_from_this<Node>
66 {
67 public:
69 
70 
71 
78  explicit Node(
79  const std::string & node_name,
80  const std::string & namespace_ = "",
81  bool use_intra_process_comms = false);
82 
84 
96  Node(
97  const std::string & node_name,
98  const std::string & namespace_,
99  rclcpp::Context::SharedPtr context,
100  const std::vector<std::string> & arguments,
101  const std::vector<Parameter> & initial_parameters,
102  bool use_global_arguments = true,
103  bool use_intra_process_comms = false,
104  bool start_parameter_services = true);
105 
107  virtual ~Node();
108 
110 
112  const char *
113  get_name() const;
114 
116 
118  const char *
119  get_namespace() const;
120 
122 
125  get_logger() const;
126 
129  rclcpp::callback_group::CallbackGroup::SharedPtr
131 
135  get_callback_groups() const;
136 
138 
144  template<
145  typename MessageT, typename Alloc = std::allocator<void>,
146  typename PublisherT = ::rclcpp::Publisher<MessageT, Alloc>>
149  const std::string & topic_name, size_t qos_history_depth,
150  std::shared_ptr<Alloc> allocator = nullptr);
151 
153 
159  template<
160  typename MessageT, typename Alloc = std::allocator<void>,
161  typename PublisherT = ::rclcpp::Publisher<MessageT, Alloc>>
164  const std::string & topic_name,
165  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
166  std::shared_ptr<Alloc> allocator = nullptr);
167 
169 
179  /* TODO(jacquelinekay):
180  Windows build breaks when static member function passed as default
181  argument to msg_mem_strat, nullptr is a workaround.
182  */
183  template<
184  typename MessageT,
185  typename CallbackT,
186  typename Alloc = std::allocator<void>,
187  typename SubscriptionT = rclcpp::Subscription<
191  const std::string & topic_name,
192  CallbackT && callback,
193  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
194  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
195  bool ignore_local_publications = false,
198  msg_mem_strat = nullptr,
199  std::shared_ptr<Alloc> allocator = nullptr);
200 
202 
212  /* TODO(jacquelinekay):
213  Windows build breaks when static member function passed as default
214  argument to msg_mem_strat, nullptr is a workaround.
215  */
216  template<
217  typename MessageT,
218  typename CallbackT,
219  typename Alloc = std::allocator<void>,
220  typename SubscriptionT = rclcpp::Subscription<
224  const std::string & topic_name,
225  CallbackT && callback,
226  size_t qos_history_depth,
227  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
228  bool ignore_local_publications = false,
231  msg_mem_strat = nullptr,
232  std::shared_ptr<Alloc> allocator = nullptr);
233 
235 
240  template<typename DurationT = std::milli, typename CallbackT>
244  CallbackT callback,
245  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
246 
247  /* Create and return a Client. */
248  template<typename ServiceT>
251  const std::string & service_name,
252  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
253  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
254 
255  /* Create and return a Service. */
256  template<typename ServiceT, typename CallbackT>
259  const std::string & service_name,
260  CallbackT && callback,
261  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
262  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
263 
267 
269  rcl_interfaces::msg::SetParametersResult
271 
272  template<typename ParameterT>
273  void
275  const std::string & name,
276  const ParameterT & value);
277 
280  get_parameters(const std::vector<std::string> & names) const;
281 
284  get_parameter(const std::string & name) const;
285 
287  bool
289  const std::string & name,
290  rclcpp::Parameter & parameter) const;
291 
293 
300  template<typename ParameterT>
301  bool
302  get_parameter(const std::string & name, ParameterT & parameter) const;
303 
305 
315  template<typename ParameterT>
316  bool
318  const std::string & name,
319  ParameterT & value,
320  const ParameterT & alternative_value) const;
321 
324  describe_parameters(const std::vector<std::string> & names) const;
325 
328  get_parameter_types(const std::vector<std::string> & names) const;
329 
331  rcl_interfaces::msg::ListParametersResult
332  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
333 
335 
340  template<typename CallbackT>
341  void
342  register_param_change_callback(CallbackT && callback);
343 
347 
351 
353  size_t
354  count_publishers(const std::string & topic_name) const;
355 
357  size_t
358  count_subscribers(const std::string & topic_name) const;
359 
361  /* The graph Event object is a loan which must be returned.
362  * The Event object is scoped and therefore to return the loan just let it go
363  * out of scope.
364  */
366  rclcpp::Event::SharedPtr
367  get_graph_event();
368 
370 
378  void
380  rclcpp::Event::SharedPtr event,
381  std::chrono::nanoseconds timeout);
382 
384  rclcpp::Clock::SharedPtr
385  get_clock();
386 
388  Time
389  now();
390 
393  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
395 
398  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
400 
403  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
405 
408  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
410 
413  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
415 
418  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
420 
423  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
425 
426 private:
428 
430  bool
431  group_in_node(callback_group::CallbackGroup::SharedPtr group);
432 
433  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
434  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
435  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
436  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
437  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
438  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
439  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
440  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
441 
442  bool use_intra_process_comms_;
443 };
444 
445 } // namespace rclcpp
446 
447 #ifndef RCLCPP__NODE_IMPL_HPP_
448 // Template implementations
449 #include "node_impl.hpp"
450 #endif
451 
452 #endif // RCLCPP__NODE_HPP_
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node&#39;s internal NodeGraphInterface implementation.
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node&#39;s internal NodeServicesInterface implementation.
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:147
const char * get_name() const
Get the name of the node.
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:155
Generic timer templated on the clock type. Periodically executes a user-specified callback...
Definition: timer.hpp:105
rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< int64_t, DurationT > period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
Create a timer.
Definition: node_impl.hpp:156
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node&#39;s internal NodeTimersInterface implementation.
const char * get_namespace() const
Get the namespace of the node.
std::shared_ptr< PublisherT > create_publisher(const std::string &topic_name, size_t qos_history_depth, std::shared_ptr< Alloc > allocator=nullptr)
Create and return a Publisher.
Definition: node_impl.hpp:56
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node&#39;s internal NodeTopicsInterface implementation.
const std::vector< rclcpp::callback_group::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
size_t count_publishers(const std::string &topic_name) const
CallbackGroupType
Definition: callback_group.hpp:43
Definition: client.hpp:118
size_t count_subscribers(const std::string &topic_name) const
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters)
rclcpp::Clock::SharedPtr get_clock()
Definition: allocator_common.hpp:24
Definition: logger.hpp:63
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:32
bool get_parameter_or(const std::string &name, ParameterT &value, const ParameterT &alternative_value) const
Get the parameter value, or the "alternative value" if not set, and assign it to "value".
Definition: node_impl.hpp:241
void set_parameter_if_not_set(const std::string &name, const ParameterT &value)
Definition: node_impl.hpp:214
std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const
typename std::remove_cv< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > >::type type
Definition: subscription_traits.hpp:61
void register_param_change_callback(CallbackT &&callback)
Register the callback for parameter changes.
Definition: node_impl.hpp:207
std::shared_ptr< SubscriptionT > create_subscription(const std::string &topic_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_default, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr, bool ignore_local_publications=false, typename rclcpp::message_memory_strategy::MessageMemoryStrategy< typename rclcpp::subscription_traits::has_message_type< CallbackT >::type, Alloc >::SharedPtr msg_mem_strat=nullptr, std::shared_ptr< Alloc > allocator=nullptr)
Create and return a Subscription.
Definition: node_impl.hpp:91
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
std::map< std::string, std::vector< std::string > > get_topic_names_and_types() const
rclcpp::Logger get_logger() const
Get the logger of the node.
virtual ~Node()
Definition: service.hpp:88
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.
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:38
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:65
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node&#39;s internal NodeParametersInterface implementation.
Node(const std::string &node_name, const std::string &namespace_="", bool use_intra_process_comms=false)
Create a new node with the specified name.
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node&#39;s internal NodeBaseInterface implementation.
rclcpp::callback_group::CallbackGroup::SharedPtr create_callback_group(rclcpp::callback_group::CallbackGroupType group_type)
Create and return a callback group.
std::map< std::string, std::vector< std::string > > get_service_names_and_types() const
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)
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const
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:194
rclcpp::Parameter get_parameter(const std::string &name) const
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node&#39;s internal NodeClockInterface implementation.
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters)
Definition: time.hpp:31