ROS 2 rclcpp + rcl - kilted  kilted
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_generic_service.hpp"
44 #include "rclcpp/create_subscription.hpp"
45 #include "rclcpp/create_timer.hpp"
46 #include "rclcpp/detail/resolve_enable_topic_statistics.hpp"
47 #include "rclcpp/parameter.hpp"
48 #include "rclcpp/qos.hpp"
49 #include "rclcpp/timer.hpp"
50 #include "rclcpp/type_support_decl.hpp"
51 #include "rclcpp/visibility_control.hpp"
52 
53 #ifndef RCLCPP__NODE_HPP_
54 #include "node.hpp"
55 #endif
56 
57 namespace rclcpp
58 {
59 
60 RCLCPP_LOCAL
61 inline
62 std::string
63 extend_name_with_sub_namespace(const std::string & name, const std::string & sub_namespace)
64 {
65  std::string name_with_sub_namespace(name);
66  if (sub_namespace != "" && name.front() != '/' && name.front() != '~') {
67  name_with_sub_namespace = sub_namespace + "/" + name;
68  }
69  return name_with_sub_namespace;
70 }
71 
72 template<typename MessageT, typename AllocatorT, typename PublisherT>
73 std::shared_ptr<PublisherT>
75  const std::string & topic_name,
76  const rclcpp::QoS & qos,
78 {
79  return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
80  *this,
81  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
82  qos,
83  options);
84 }
85 
86 template<
87  typename MessageT,
88  typename CallbackT,
89  typename AllocatorT,
90  typename SubscriptionT,
91  typename MessageMemoryStrategyT>
92 std::shared_ptr<SubscriptionT>
94  const std::string & topic_name,
95  const rclcpp::QoS & qos,
96  CallbackT && callback,
98  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
99 {
100  return rclcpp::create_subscription<MessageT>(
101  *this,
102  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
103  qos,
104  std::forward<CallbackT>(callback),
105  options,
106  msg_mem_strat);
107 }
108 
109 template<typename DurationRepT, typename DurationT, typename CallbackT>
112  std::chrono::duration<DurationRepT, DurationT> period,
113  CallbackT callback,
114  rclcpp::CallbackGroup::SharedPtr group,
115  bool autostart)
116 {
118  period,
119  std::move(callback),
120  group,
121  this->node_base_.get(),
122  this->node_timers_.get(),
123  autostart);
124 }
125 
126 template<typename DurationRepT, typename DurationT, typename CallbackT>
129  std::chrono::duration<DurationRepT, DurationT> period,
130  CallbackT callback,
131  rclcpp::CallbackGroup::SharedPtr group)
132 {
133  return rclcpp::create_timer(
134  this->get_clock(),
135  period,
136  std::move(callback),
137  group,
138  this->node_base_.get(),
139  this->node_timers_.get());
140 }
141 
142 template<typename ServiceT>
145  const std::string & service_name,
146  const rclcpp::QoS & qos,
147  rclcpp::CallbackGroup::SharedPtr group)
148 {
149  return rclcpp::create_client<ServiceT>(
150  node_base_,
151  node_graph_,
152  node_services_,
153  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
154  qos,
155  group);
156 }
157 
158 template<typename ServiceT, typename CallbackT>
161  const std::string & service_name,
162  CallbackT && callback,
163  const rclcpp::QoS & qos,
164  rclcpp::CallbackGroup::SharedPtr group)
165 {
166  return rclcpp::create_service<ServiceT, CallbackT>(
167  node_base_,
168  node_services_,
169  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
170  std::forward<CallbackT>(callback),
171  qos,
172  group);
173 }
174 
175 template<typename CallbackT>
176 typename rclcpp::GenericService::SharedPtr
178  const std::string & service_name,
179  const std::string & service_type,
180  CallbackT && callback,
181  const rclcpp::QoS & qos,
182  rclcpp::CallbackGroup::SharedPtr group)
183 {
184  return rclcpp::create_generic_service<CallbackT>(
185  node_base_,
186  node_services_,
187  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
188  service_type,
189  std::forward<CallbackT>(callback),
190  qos,
191  group);
192 }
193 
194 template<typename AllocatorT>
195 std::shared_ptr<rclcpp::GenericPublisher>
197  const std::string & topic_name,
198  const std::string & topic_type,
199  const rclcpp::QoS & qos,
201 {
203  node_topics_,
204  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
205  topic_type,
206  qos,
207  options
208  );
209 }
210 
211 template<typename CallbackT, typename AllocatorT>
212 std::shared_ptr<rclcpp::GenericSubscription>
214  const std::string & topic_name,
215  const std::string & topic_type,
216  const rclcpp::QoS & qos,
217  CallbackT && callback,
219 {
221  node_topics_,
222  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
223  topic_type,
224  qos,
225  std::forward<CallbackT>(callback),
226  options
227  );
228 }
229 
230 
231 template<typename ParameterT>
232 auto
234  const std::string & name,
235  const ParameterT & default_value,
236  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
237  bool ignore_override)
238 {
239  try {
240  return this->declare_parameter(
241  name,
242  rclcpp::ParameterValue(default_value),
243  parameter_descriptor,
244  ignore_override
245  ).get<ParameterT>();
246  } catch (const ParameterTypeException & ex) {
247  throw exceptions::InvalidParameterTypeException(name, ex.what());
248  }
249 }
250 
251 template<typename ParameterT>
252 auto
254  const std::string & name,
255  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
256  bool ignore_override)
257 {
258  // get advantage of parameter value template magic to get
259  // the correct rclcpp::ParameterType from ParameterT
260  rclcpp::ParameterValue value{ParameterT{}};
261  try {
262  return this->declare_parameter(
263  name,
264  value.get_type(),
265  parameter_descriptor,
266  ignore_override
267  ).get<ParameterT>();
268  } catch (const ParameterTypeException &) {
270  }
271 }
272 
273 template<typename ParameterT>
274 std::vector<ParameterT>
276  const std::string & namespace_,
277  const std::map<std::string, ParameterT> & parameters,
278  bool ignore_overrides)
279 {
280  std::vector<ParameterT> result;
281  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
282  std::transform(
283  parameters.begin(), parameters.end(), std::back_inserter(result),
284  [this, &normalized_namespace, ignore_overrides](auto element) {
285  return this->declare_parameter(
286  normalized_namespace + element.first,
287  element.second,
288  rcl_interfaces::msg::ParameterDescriptor(),
289  ignore_overrides);
290  }
291  );
292  return result;
293 }
294 
295 template<typename ParameterT>
296 std::vector<ParameterT>
298  const std::string & namespace_,
299  const std::map<
300  std::string,
301  std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
302  > & parameters,
303  bool ignore_overrides)
304 {
305  std::vector<ParameterT> result;
306  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
307  std::transform(
308  parameters.begin(), parameters.end(), std::back_inserter(result),
309  [this, &normalized_namespace, ignore_overrides](auto element) {
310  return static_cast<ParameterT>(
311  this->declare_parameter(
312  normalized_namespace + element.first,
313  element.second.first,
314  element.second.second,
315  ignore_overrides)
316  );
317  }
318  );
319  return result;
320 }
321 
322 template<typename ParameterT>
323 bool
324 Node::get_parameter(const std::string & name, ParameterT & parameter) const
325 {
326  rclcpp::Parameter parameter_variant;
327 
328  bool result = get_parameter(name, parameter_variant);
329  if (result) {
330  parameter = static_cast<ParameterT>(parameter_variant.get_value<ParameterT>());
331  }
332 
333  return result;
334 }
335 
336 template<typename ParameterT>
337 bool
339  const std::string & name,
340  ParameterT & parameter,
341  const ParameterT & alternative_value) const
342 {
343  bool got_parameter = get_parameter(name, parameter);
344  if (!got_parameter) {
345  parameter = alternative_value;
346  }
347  return got_parameter;
348 }
349 
350 template<typename ParameterT>
351 ParameterT
353  const std::string & name,
354  const ParameterT & alternative_value) const
355 {
356  ParameterT parameter;
357  get_parameter_or(name, parameter, alternative_value);
358  return parameter;
359 }
360 
361 // this is a partially-specialized version of get_parameter above,
362 // where our concrete type for ParameterT is std::map, but the to-be-determined
363 // type is the value in the map.
364 template<typename ParameterT>
365 bool
367  const std::string & prefix,
368  std::map<std::string, ParameterT> & values) const
369 {
370  std::map<std::string, rclcpp::Parameter> params;
371  bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
372  if (result) {
373  for (const auto & param : params) {
374  values[param.first] = static_cast<ParameterT>(param.second.get_value<ParameterT>());
375  }
376  }
377 
378  return result;
379 }
380 
381 } // namespace rclcpp
382 
383 #endif // RCLCPP__NODE_IMPL_HPP_
Generic timer. Periodically executes a user-specified callback.
Definition: timer.hpp:226
rclcpp::GenericService::SharedPtr create_generic_service(const std::string &service_name, const std::string &service_type, CallbackT &&callback, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a GenericService.
Definition: node_impl.hpp:177
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_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:338
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:128
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:275
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
Definition: node.cpp:402
rclcpp::Service< ServiceT >::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rclcpp::QoS &qos=rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
Definition: node_impl.hpp:160
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:213
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:93
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:74
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:111
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:196
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:271
Thrown if user attempts to create an uninitialized statically typed parameter.
Definition: exceptions.hpp:289
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.