rclcpp  beta1
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 
74  explicit Node(const std::string & node_name, bool use_intra_process_comms = false);
75 
77 
84  Node(
85  const std::string & node_name, rclcpp::context::Context::SharedPtr context,
86  bool use_intra_process_comms = false);
87 
89  virtual ~Node();
90 
92 
94  const char *
95  get_name() const;
96 
99  rclcpp::callback_group::CallbackGroup::SharedPtr
101 
105  get_callback_groups() const;
106 
108 
114  template<
115  typename MessageT, typename Alloc = std::allocator<void>,
119  const std::string & topic_name, size_t qos_history_depth,
120  std::shared_ptr<Alloc> allocator = nullptr);
121 
123 
129  template<
130  typename MessageT, typename Alloc = std::allocator<void>,
134  const std::string & topic_name,
135  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
136  std::shared_ptr<Alloc> allocator = nullptr);
137 
139 
149  /* TODO(jacquelinekay):
150  Windows build breaks when static member function passed as default
151  argument to msg_mem_strat, nullptr is a workaround.
152  */
153  template<
154  typename MessageT,
155  typename CallbackT,
156  typename Alloc = std::allocator<void>,
160  const std::string & topic_name,
161  CallbackT && callback,
162  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
163  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
164  bool ignore_local_publications = false,
166  msg_mem_strat = nullptr,
167  std::shared_ptr<Alloc> allocator = nullptr);
168 
170 
180  /* TODO(jacquelinekay):
181  Windows build breaks when static member function passed as default
182  argument to msg_mem_strat, nullptr is a workaround.
183  */
184  template<
185  typename MessageT,
186  typename CallbackT,
187  typename Alloc = std::allocator<void>,
191  const std::string & topic_name,
192  size_t qos_history_depth,
193  CallbackT && callback,
194  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
195  bool ignore_local_publications = false,
197  msg_mem_strat = nullptr,
198  std::shared_ptr<Alloc> allocator = nullptr);
199 
201 
206  template<typename DurationT = std::milli, typename CallbackT>
210  CallbackT callback,
211  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
212 
213  /* Create and return a Client. */
214  template<typename ServiceT>
217  const std::string & service_name,
218  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
219  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
220 
221  /* Create and return a Service. */
222  template<typename ServiceT, typename CallbackT>
225  const std::string & service_name,
226  CallbackT && callback,
227  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
228  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
229 
233 
235  rcl_interfaces::msg::SetParametersResult
237 
240  get_parameters(const std::vector<std::string> & names) const;
241 
244  get_parameter(const std::string & name) const;
245 
247  bool
249  const std::string & name,
250  rclcpp::parameter::ParameterVariant & parameter) const;
251 
252  template<typename ParameterT>
253  bool
254  get_parameter(const std::string & name, ParameterT & parameter) const;
255 
258  describe_parameters(const std::vector<std::string> & names) const;
259 
262  get_parameter_types(const std::vector<std::string> & names) const;
263 
265  rcl_interfaces::msg::ListParametersResult
266  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
267 
269 
274  template<typename CallbackT>
275  void
276  register_param_change_callback(CallbackT && callback);
277 
281 
283  size_t
284  count_publishers(const std::string & topic_name) const;
285 
287  size_t
288  count_subscribers(const std::string & topic_name) const;
289 
291  /* The graph Event object is a loan which must be returned.
292  * The Event object is scoped and therefore to return the load just let it go
293  * out of scope.
294  */
296  rclcpp::event::Event::SharedPtr
297  get_graph_event();
298 
300 
308  void
310  rclcpp::event::Event::SharedPtr event,
311  std::chrono::nanoseconds timeout);
312 
315  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
317 
320  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
322 
325  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
327 
330  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
332 
335  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
337 
340  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
342 
343 private:
344  RCLCPP_DISABLE_COPY(Node)
345 
347  bool
348  group_in_node(callback_group::CallbackGroup::SharedPtr group);
349 
350  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
351  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
352  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
353  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
354  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
355  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
356 
357  bool use_intra_process_comms_;
358 };
359 
360 } // namespace node
361 } // namespace rclcpp
362 
363 #ifndef RCLCPP__NODE_IMPL_HPP_
364 // Template implementations
365 #include "node_impl.hpp"
366 #endif
367 
368 #endif // RCLCPP__NODE_HPP_
const std::vector< rclcpp::callback_group::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node&#39;s internal NodeServicesInterface implementation.
Definition: client.hpp:111
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
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::parameter::ParameterVariant > &parameters)
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
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.
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
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node&#39;s internal NodeBaseInterface implementation.
CallbackGroupType
Definition: callback_group.hpp:43
Generic timer templated on the clock type. Periodically executes a user-specified callback...
Definition: timer.hpp:103
Node(const std::string &node_name, bool use_intra_process_comms=false)
Create a new node with the specified name.
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node&#39;s internal NodeGraphInterface implementation.
Definition: allocator_common.hpp:24
std::vector< rclcpp::parameter::ParameterVariant > get_parameters(const std::vector< std::string > &names) const
const char * get_name() const
Get the name of the node.
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:62
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:122
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
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
Definition: service.hpp:83
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::parameter::ParameterVariant > &parameters)
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)
void register_param_change_callback(CallbackT &&callback)
Register the callback for parameter changes.
Definition: node_impl.hpp:205
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:146
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:33
size_t count_subscribers(const std::string &topic_name) const
size_t count_publishers(const std::string &topic_name) const
std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
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::string > get_topic_names_and_types() const
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node&#39;s internal NodeTopicsInterface implementation.
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node&#39;s internal NodeTimersInterface implementation.
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
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.
Definition: parameter.hpp:45