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/context.hpp"
39 #include "rclcpp/event.hpp"
40 #include "rclcpp/macros.hpp"
48 #include "rclcpp/parameter.hpp"
49 #include "rclcpp/publisher.hpp"
50 #include "rclcpp/service.hpp"
51 #include "rclcpp/subscription.hpp"
52 #include "rclcpp/timer.hpp"
54 
55 namespace rclcpp
56 {
57 
58 namespace node
59 {
60 
62 class Node : public std::enable_shared_from_this<Node>
63 {
64 public:
66 
67 
68 
75  explicit Node(
76  const std::string & node_name,
77  const std::string & namespace_ = "",
78  bool use_intra_process_comms = false);
79 
81 
89  Node(
90  const std::string & node_name,
91  const std::string & namespace_,
92  rclcpp::context::Context::SharedPtr context,
93  bool use_intra_process_comms = false);
94 
96  virtual ~Node();
97 
99 
101  const char *
102  get_name() const;
103 
105 
107  const char *
108  get_namespace() const;
109 
112  rclcpp::callback_group::CallbackGroup::SharedPtr
114 
117  const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr> &
118  get_callback_groups() const;
119 
121 
127  template<
128  typename MessageT, typename Alloc = std::allocator<void>,
130  std::shared_ptr<PublisherT>
132  const std::string & topic_name, size_t qos_history_depth,
133  std::shared_ptr<Alloc> allocator = nullptr);
134 
136 
142  template<
143  typename MessageT, typename Alloc = std::allocator<void>,
145  std::shared_ptr<PublisherT>
147  const std::string & topic_name,
148  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
149  std::shared_ptr<Alloc> allocator = nullptr);
150 
152 
162  /* TODO(jacquelinekay):
163  Windows build breaks when static member function passed as default
164  argument to msg_mem_strat, nullptr is a workaround.
165  */
166  template<
167  typename MessageT,
168  typename CallbackT,
169  typename Alloc = std::allocator<void>,
171  std::shared_ptr<SubscriptionT>
173  const std::string & topic_name,
174  CallbackT && callback,
175  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
176  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
177  bool ignore_local_publications = false,
179  msg_mem_strat = nullptr,
180  std::shared_ptr<Alloc> allocator = nullptr);
181 
183 
193  /* TODO(jacquelinekay):
194  Windows build breaks when static member function passed as default
195  argument to msg_mem_strat, nullptr is a workaround.
196  */
197  template<
198  typename MessageT,
199  typename CallbackT,
200  typename Alloc = std::allocator<void>,
202  std::shared_ptr<SubscriptionT>
204  const std::string & topic_name,
205  size_t qos_history_depth,
206  CallbackT && callback,
207  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
208  bool ignore_local_publications = false,
210  msg_mem_strat = nullptr,
211  std::shared_ptr<Alloc> allocator = nullptr);
212 
214 
219  template<typename DurationT = std::milli, typename CallbackT>
222  std::chrono::duration<int64_t, DurationT> period,
223  CallbackT callback,
224  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
225 
226  /* Create and return a Client. */
227  template<typename ServiceT>
230  const std::string & service_name,
231  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
232  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
233 
234  /* Create and return a Service. */
235  template<typename ServiceT, typename CallbackT>
238  const std::string & service_name,
239  CallbackT && callback,
240  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
241  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
242 
244  std::vector<rcl_interfaces::msg::SetParametersResult>
245  set_parameters(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
246 
248  rcl_interfaces::msg::SetParametersResult
249  set_parameters_atomically(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
250 
251  template<typename ParameterT>
252  void
254  const std::string & name,
255  const ParameterT & value);
256 
258  std::vector<rclcpp::parameter::ParameterVariant>
259  get_parameters(const std::vector<std::string> & names) const;
260 
263  get_parameter(const std::string & name) const;
264 
266  bool
268  const std::string & name,
269  rclcpp::parameter::ParameterVariant & parameter) const;
270 
272 
279  template<typename ParameterT>
280  bool
281  get_parameter(const std::string & name, ParameterT & parameter) const;
282 
284 
294  template<typename ParameterT>
295  bool
297  const std::string & name,
298  ParameterT & value,
299  const ParameterT & alternative_value) const;
300 
302  std::vector<rcl_interfaces::msg::ParameterDescriptor>
303  describe_parameters(const std::vector<std::string> & names) const;
304 
306  std::vector<uint8_t>
307  get_parameter_types(const std::vector<std::string> & names) const;
308 
310  rcl_interfaces::msg::ListParametersResult
311  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
312 
314 
319  template<typename CallbackT>
320  void
321  register_param_change_callback(CallbackT && callback);
322 
324  std::map<std::string, std::vector<std::string>>
326 
328  std::map<std::string, std::vector<std::string>>
330 
332  size_t
333  count_publishers(const std::string & topic_name) const;
334 
336  size_t
337  count_subscribers(const std::string & topic_name) const;
338 
340  /* The graph Event object is a loan which must be returned.
341  * The Event object is scoped and therefore to return the load just let it go
342  * out of scope.
343  */
345  rclcpp::event::Event::SharedPtr
346  get_graph_event();
347 
349 
357  void
359  rclcpp::event::Event::SharedPtr event,
360  std::chrono::nanoseconds timeout);
361 
364  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
366 
369  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
371 
374  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
376 
379  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
381 
384  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
386 
389  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
391 
392 private:
393  RCLCPP_DISABLE_COPY(Node)
394 
396  bool
397  group_in_node(callback_group::CallbackGroup::SharedPtr group);
398 
399  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
400  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
401  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
402  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
403  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
404  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
405 
406  bool use_intra_process_comms_;
407 };
408 
409 } // namespace node
410 } // namespace rclcpp
411 
412 #ifndef RCLCPP__NODE_IMPL_HPP_
413 // Template implementations
414 #include "node_impl.hpp"
415 #endif
416 
417 #endif // RCLCPP__NODE_HPP_
void set_parameter_if_not_set(const std::string &name, const ParameterT &value)
Definition: node_impl.hpp:212
rclcpp::timer::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:145
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::parameter::ParameterVariant > &parameters)
rclcpp::callback_group::CallbackGroup::SharedPtr create_callback_group(rclcpp::callback_group::CallbackGroupType group_type)
Create and return a callback group.
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:33
size_t count_subscribers(const std::string &topic_name) const
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:124
Definition: service.hpp:89
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
std::vector< rclcpp::parameter::ParameterVariant > get_parameters(const std::vector< std::string > &names) const
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:57
CallbackGroupType
Definition: callback_group.hpp:43
rclcpp::client::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)
const std::vector< rclcpp::callback_group::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
Definition: allocator_common.hpp:24
rclcpp::parameter::ParameterVariant get_parameter(const std::string &name) const
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node&#39;s internal NodeParametersInterface implementation.
rclcpp::event::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
size_t count_publishers(const std::string &topic_name) const
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::parameter::ParameterVariant > &parameters)
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node&#39;s internal NodeBaseInterface implementation.
std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:62
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node&#39;s internal NodeGraphInterface implementation.
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:239
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node&#39;s internal NodeTopicsInterface implementation.
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node&#39;s internal NodeTimersInterface implementation.
rclcpp::service::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:183
Node(const std::string &node_name, const std::string &namespace_="", bool use_intra_process_comms=false)
Create a new node with the specified name.
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const
Generic timer templated on the clock type. Periodically executes a user-specified callback...
Definition: timer.hpp:107
const char * get_name() const
Get the name of the node.
Definition: parameter.hpp:45
Definition: client.hpp:113
std::map< std::string, std::vector< std::string > > get_service_names_and_types() const
void wait_for_graph_change(rclcpp::event::Event::SharedPtr event, std::chrono::nanoseconds timeout)
Wait for a graph event to occur by waiting on an Event to become set.
void register_param_change_callback(CallbackT &&callback)
Register the callback for parameter changes.
Definition: node_impl.hpp:205
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node&#39;s internal NodeServicesInterface implementation.
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:146
std::map< std::string, std::vector< std::string > > get_topic_names_and_types() const
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< MessageT, Alloc >::SharedPtr msg_mem_strat=nullptr, std::shared_ptr< Alloc > allocator=nullptr)
Create and return a Subscription.
Definition: node_impl.hpp:88
const char * get_namespace() const
Get the namespace of the node.