ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
node_impl.hpp
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_IMPL_HPP_
16 #define RCLCPP__NODE_IMPL_HPP_
17 
18 #include <rmw/error_handling.h>
19 #include <rmw/rmw.h>
20 
21 #include <algorithm>
22 #include <chrono>
23 #include <cstdlib>
24 #include <iostream>
25 #include <limits>
26 #include <map>
27 #include <memory>
28 #include <sstream>
29 #include <stdexcept>
30 #include <string>
31 #include <utility>
32 #include <vector>
33 
34 #include "rcl/publisher.h"
35 #include "rcl/subscription.h"
36 
37 #include "rclcpp/contexts/default_context.hpp"
38 #include "rclcpp/create_client.hpp"
39 #include "rclcpp/create_generic_publisher.hpp"
40 #include "rclcpp/create_generic_subscription.hpp"
41 #include "rclcpp/create_publisher.hpp"
42 #include "rclcpp/create_service.hpp"
43 #include "rclcpp/create_subscription.hpp"
44 #include "rclcpp/create_timer.hpp"
45 #include "rclcpp/detail/resolve_enable_topic_statistics.hpp"
46 #include "rclcpp/parameter.hpp"
47 #include "rclcpp/qos.hpp"
48 #include "rclcpp/timer.hpp"
49 #include "rclcpp/type_support_decl.hpp"
50 #include "rclcpp/visibility_control.hpp"
51 
52 #ifndef RCLCPP__NODE_HPP_
53 #include "node.hpp"
54 #endif
55 
56 namespace rclcpp
57 {
58 
59 RCLCPP_LOCAL
60 inline
61 std::string
62 extend_name_with_sub_namespace(const std::string & name, const std::string & sub_namespace)
63 {
64  std::string name_with_sub_namespace(name);
65  if (sub_namespace != "" && name.front() != '/' && name.front() != '~') {
66  name_with_sub_namespace = sub_namespace + "/" + name;
67  }
68  return name_with_sub_namespace;
69 }
70 
71 template<typename MessageT, typename AllocatorT, typename PublisherT>
72 std::shared_ptr<PublisherT>
74  const std::string & topic_name,
75  const rclcpp::QoS & qos,
77 {
78  return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
79  *this,
80  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
81  qos,
82  options);
83 }
84 
85 template<
86  typename MessageT,
87  typename CallbackT,
88  typename AllocatorT,
89  typename SubscriptionT,
90  typename MessageMemoryStrategyT>
91 std::shared_ptr<SubscriptionT>
93  const std::string & topic_name,
94  const rclcpp::QoS & qos,
95  CallbackT && callback,
97  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
98 {
99  return rclcpp::create_subscription<MessageT>(
100  *this,
101  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
102  qos,
103  std::forward<CallbackT>(callback),
104  options,
105  msg_mem_strat);
106 }
107 
108 template<typename DurationRepT, typename DurationT, typename CallbackT>
111  std::chrono::duration<DurationRepT, DurationT> period,
112  CallbackT callback,
113  rclcpp::CallbackGroup::SharedPtr group,
114  bool autostart)
115 {
117  period,
118  std::move(callback),
119  group,
120  this->node_base_.get(),
121  this->node_timers_.get(),
122  autostart);
123 }
124 
125 template<typename DurationRepT, typename DurationT, typename CallbackT>
128  std::chrono::duration<DurationRepT, DurationT> period,
129  CallbackT callback,
130  rclcpp::CallbackGroup::SharedPtr group)
131 {
132  return rclcpp::create_timer(
133  this->get_clock(),
134  period,
135  std::move(callback),
136  group,
137  this->node_base_.get(),
138  this->node_timers_.get());
139 }
140 
141 template<typename ServiceT>
144  const std::string & service_name,
145  const rclcpp::QoS & qos,
146  rclcpp::CallbackGroup::SharedPtr group)
147 {
148  return rclcpp::create_client<ServiceT>(
149  node_base_,
150  node_graph_,
151  node_services_,
152  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
153  qos,
154  group);
155 }
156 
157 template<typename ServiceT>
158 typename Client<ServiceT>::SharedPtr
160  const std::string & service_name,
161  const rmw_qos_profile_t & qos_profile,
162  rclcpp::CallbackGroup::SharedPtr group)
163 {
164  return rclcpp::create_client<ServiceT>(
165  node_base_,
166  node_graph_,
167  node_services_,
168  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
169  qos_profile,
170  group);
171 }
172 
173 template<typename ServiceT, typename CallbackT>
176  const std::string & service_name,
177  CallbackT && callback,
178  const rclcpp::QoS & qos,
179  rclcpp::CallbackGroup::SharedPtr group)
180 {
181  return rclcpp::create_service<ServiceT, CallbackT>(
182  node_base_,
183  node_services_,
184  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
185  std::forward<CallbackT>(callback),
186  qos,
187  group);
188 }
189 
190 template<typename ServiceT, typename CallbackT>
193  const std::string & service_name,
194  CallbackT && callback,
195  const rmw_qos_profile_t & qos_profile,
196  rclcpp::CallbackGroup::SharedPtr group)
197 {
198  return rclcpp::create_service<ServiceT, CallbackT>(
199  node_base_,
200  node_services_,
201  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
202  std::forward<CallbackT>(callback),
203  qos_profile,
204  group);
205 }
206 
207 template<typename AllocatorT>
208 std::shared_ptr<rclcpp::GenericPublisher>
210  const std::string & topic_name,
211  const std::string & topic_type,
212  const rclcpp::QoS & qos,
214 {
216  node_topics_,
217  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
218  topic_type,
219  qos,
220  options
221  );
222 }
223 
224 template<typename CallbackT, typename AllocatorT>
225 std::shared_ptr<rclcpp::GenericSubscription>
227  const std::string & topic_name,
228  const std::string & topic_type,
229  const rclcpp::QoS & qos,
230  CallbackT && callback,
232 {
234  node_topics_,
235  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
236  topic_type,
237  qos,
238  std::forward<CallbackT>(callback),
239  options
240  );
241 }
242 
243 
244 template<typename ParameterT>
245 auto
247  const std::string & name,
248  const ParameterT & default_value,
249  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
250  bool ignore_override)
251 {
252  try {
253  return this->declare_parameter(
254  name,
255  rclcpp::ParameterValue(default_value),
256  parameter_descriptor,
257  ignore_override
258  ).get<ParameterT>();
259  } catch (const ParameterTypeException & ex) {
260  throw exceptions::InvalidParameterTypeException(name, ex.what());
261  }
262 }
263 
264 template<typename ParameterT>
265 auto
267  const std::string & name,
268  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
269  bool ignore_override)
270 {
271  // get advantage of parameter value template magic to get
272  // the correct rclcpp::ParameterType from ParameterT
273  rclcpp::ParameterValue value{ParameterT{}};
274  try {
275  return this->declare_parameter(
276  name,
277  value.get_type(),
278  parameter_descriptor,
279  ignore_override
280  ).get<ParameterT>();
281  } catch (const ParameterTypeException &) {
283  }
284 }
285 
286 template<typename ParameterT>
287 std::vector<ParameterT>
289  const std::string & namespace_,
290  const std::map<std::string, ParameterT> & parameters,
291  bool ignore_overrides)
292 {
293  std::vector<ParameterT> result;
294  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
295  std::transform(
296  parameters.begin(), parameters.end(), std::back_inserter(result),
297  [this, &normalized_namespace, ignore_overrides](auto element) {
298  return this->declare_parameter(
299  normalized_namespace + element.first,
300  element.second,
301  rcl_interfaces::msg::ParameterDescriptor(),
302  ignore_overrides);
303  }
304  );
305  return result;
306 }
307 
308 template<typename ParameterT>
309 std::vector<ParameterT>
311  const std::string & namespace_,
312  const std::map<
313  std::string,
314  std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
315  > & parameters,
316  bool ignore_overrides)
317 {
318  std::vector<ParameterT> result;
319  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
320  std::transform(
321  parameters.begin(), parameters.end(), std::back_inserter(result),
322  [this, &normalized_namespace, ignore_overrides](auto element) {
323  return static_cast<ParameterT>(
324  this->declare_parameter(
325  normalized_namespace + element.first,
326  element.second.first,
327  element.second.second,
328  ignore_overrides)
329  );
330  }
331  );
332  return result;
333 }
334 
335 template<typename ParameterT>
336 bool
337 Node::get_parameter(const std::string & name, ParameterT & parameter) const
338 {
339  std::string sub_name = extend_name_with_sub_namespace(name, this->get_sub_namespace());
340 
341  rclcpp::Parameter parameter_variant;
342 
343  bool result = get_parameter(sub_name, parameter_variant);
344  if (result) {
345  parameter = static_cast<ParameterT>(parameter_variant.get_value<ParameterT>());
346  }
347 
348  return result;
349 }
350 
351 template<typename ParameterT>
352 bool
354  const std::string & name,
355  ParameterT & parameter,
356  const ParameterT & alternative_value) const
357 {
358  std::string sub_name = extend_name_with_sub_namespace(name, this->get_sub_namespace());
359 
360  bool got_parameter = get_parameter(sub_name, parameter);
361  if (!got_parameter) {
362  parameter = alternative_value;
363  }
364  return got_parameter;
365 }
366 
367 template<typename ParameterT>
368 ParameterT
370  const std::string & name,
371  const ParameterT & alternative_value) const
372 {
373  ParameterT parameter;
374  get_parameter_or(name, parameter, alternative_value);
375  return parameter;
376 }
377 
378 // this is a partially-specialized version of get_parameter above,
379 // where our concrete type for ParameterT is std::map, but the to-be-determined
380 // type is the value in the map.
381 template<typename ParameterT>
382 bool
384  const std::string & prefix,
385  std::map<std::string, ParameterT> & values) const
386 {
387  std::map<std::string, rclcpp::Parameter> params;
388  bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
389  if (result) {
390  for (const auto & param : params) {
391  values[param.first] = static_cast<ParameterT>(param.second.get_value<ParameterT>());
392  }
393  }
394 
395  return result;
396 }
397 
398 } // namespace rclcpp
399 
400 #endif // RCLCPP__NODE_IMPL_HPP_
Generic timer. Periodically executes a user-specified callback.
Definition: timer.hpp:226
RCLCPP_PUBLIC std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
Definition: node.cpp:414
RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
Definition: node.cpp:572
rclcpp::Service< ServiceT >::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
Definition: node_impl.hpp:192
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
RCLCPP_PUBLIC const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
Definition: node.cpp:344
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:353
rclcpp::GenericTimer< CallbackT >::SharedPtr create_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create a timer that uses the node clock to drive the callback.
Definition: node_impl.hpp:127
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:288
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
Definition: node.cpp:402
std::shared_ptr< rclcpp::GenericSubscription > create_generic_subscription(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
Definition: node_impl.hpp:226
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:92
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:73
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr, bool autostart=true)
Create a wall timer that uses the wall clock to drive the callback.
Definition: node_impl.hpp:110
RCLCPP_PUBLIC const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
Definition: node.cpp:656
std::shared_ptr< rclcpp::GenericPublisher > create_generic_publisher(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=(rclcpp::PublisherOptionsWithAllocator< AllocatorT >()))
Create and return a GenericPublisher.
Definition: node_impl.hpp:209
Indicate the parameter type does not match the expected type.
Store the type and value of a parameter.
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:53
decltype(auto) get_value() const
Get value of parameter using rclcpp::ParameterType as template argument.
Definition: parameter.hpp:117
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
Thrown if requested parameter type is invalid.
Definition: exceptions.hpp:262
Thrown if user attempts to create an uninitialized statically typed parameter.
Definition: exceptions.hpp:280
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
rclcpp::TimerBase::SharedPtr create_timer(std::shared_ptr< node_interfaces::NodeBaseInterface > node_base, std::shared_ptr< node_interfaces::NodeTimersInterface > node_timers, rclcpp::Clock::SharedPtr clock, rclcpp::Duration period, CallbackT &&callback, rclcpp::CallbackGroup::SharedPtr group=nullptr, bool autostart=true)
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group, node_interfaces::NodeBaseInterface *node_base, node_interfaces::NodeTimersInterface *node_timers, bool autostart=true)
Convenience method to create a wall timer with node resources.
std::shared_ptr< GenericPublisher > create_generic_publisher(rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=(rclcpp::PublisherOptionsWithAllocator< AllocatorT >()))
Create and return a GenericPublisher.
std::shared_ptr< GenericSubscription > create_generic_subscription(rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
Structure containing optional configuration for Publishers.
Structure containing optional configuration for Subscriptions.