ROS 2 rclcpp + rcl - humble  humble
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 {
116  period,
117  std::move(callback),
118  group,
119  this->node_base_.get(),
120  this->node_timers_.get());
121 }
122 
123 template<typename ServiceT>
126  const std::string & service_name,
127  const rmw_qos_profile_t & qos_profile,
128  rclcpp::CallbackGroup::SharedPtr group)
129 {
130  return rclcpp::create_client<ServiceT>(
131  node_base_,
132  node_graph_,
133  node_services_,
134  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
135  qos_profile,
136  group);
137 }
138 
139 template<typename ServiceT, typename CallbackT>
142  const std::string & service_name,
143  CallbackT && callback,
144  const rmw_qos_profile_t & qos_profile,
145  rclcpp::CallbackGroup::SharedPtr group)
146 {
147  return rclcpp::create_service<ServiceT, CallbackT>(
148  node_base_,
149  node_services_,
150  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
151  std::forward<CallbackT>(callback),
152  qos_profile,
153  group);
154 }
155 
156 template<typename AllocatorT>
157 std::shared_ptr<rclcpp::GenericPublisher>
159  const std::string & topic_name,
160  const std::string & topic_type,
161  const rclcpp::QoS & qos,
163 {
165  node_topics_,
166  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
167  topic_type,
168  qos,
169  options
170  );
171 }
172 
173 template<typename AllocatorT>
174 std::shared_ptr<rclcpp::GenericSubscription>
176  const std::string & topic_name,
177  const std::string & topic_type,
178  const rclcpp::QoS & qos,
179  std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> callback,
181 {
183  node_topics_,
184  extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
185  topic_type,
186  qos,
187  std::move(callback),
188  options
189  );
190 }
191 
192 
193 template<typename ParameterT>
194 auto
196  const std::string & name,
197  const ParameterT & default_value,
198  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
199  bool ignore_override)
200 {
201  try {
202  return this->declare_parameter(
203  name,
204  rclcpp::ParameterValue(default_value),
205  parameter_descriptor,
206  ignore_override
207  ).get<ParameterT>();
208  } catch (const ParameterTypeException & ex) {
209  throw exceptions::InvalidParameterTypeException(name, ex.what());
210  }
211 }
212 
213 template<typename ParameterT>
214 auto
216  const std::string & name,
217  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
218  bool ignore_override)
219 {
220  // get advantage of parameter value template magic to get
221  // the correct rclcpp::ParameterType from ParameterT
222  rclcpp::ParameterValue value{ParameterT{}};
223  try {
224  return this->declare_parameter(
225  name,
226  value.get_type(),
227  parameter_descriptor,
228  ignore_override
229  ).get<ParameterT>();
230  } catch (const ParameterTypeException &) {
232  }
233 }
234 
235 template<typename ParameterT>
236 std::vector<ParameterT>
238  const std::string & namespace_,
239  const std::map<std::string, ParameterT> & parameters,
240  bool ignore_overrides)
241 {
242  std::vector<ParameterT> result;
243  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
244  std::transform(
245  parameters.begin(), parameters.end(), std::back_inserter(result),
246  [this, &normalized_namespace, ignore_overrides](auto element) {
247  return this->declare_parameter(
248  normalized_namespace + element.first,
249  element.second,
250  rcl_interfaces::msg::ParameterDescriptor(),
251  ignore_overrides);
252  }
253  );
254  return result;
255 }
256 
257 template<typename ParameterT>
258 std::vector<ParameterT>
260  const std::string & namespace_,
261  const std::map<
262  std::string,
263  std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
264  > & parameters,
265  bool ignore_overrides)
266 {
267  std::vector<ParameterT> result;
268  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
269  std::transform(
270  parameters.begin(), parameters.end(), std::back_inserter(result),
271  [this, &normalized_namespace, ignore_overrides](auto element) {
272  return static_cast<ParameterT>(
273  this->declare_parameter(
274  normalized_namespace + element.first,
275  element.second.first,
276  element.second.second,
277  ignore_overrides)
278  );
279  }
280  );
281  return result;
282 }
283 
284 template<typename ParameterT>
285 bool
286 Node::get_parameter(const std::string & name, ParameterT & parameter) const
287 {
288  std::string sub_name = extend_name_with_sub_namespace(name, this->get_sub_namespace());
289 
290  rclcpp::Parameter parameter_variant;
291 
292  bool result = get_parameter(sub_name, parameter_variant);
293  if (result) {
294  parameter = static_cast<ParameterT>(parameter_variant.get_value<ParameterT>());
295  }
296 
297  return result;
298 }
299 
300 template<typename ParameterT>
301 bool
303  const std::string & name,
304  ParameterT & parameter,
305  const ParameterT & alternative_value) const
306 {
307  std::string sub_name = extend_name_with_sub_namespace(name, this->get_sub_namespace());
308 
309  bool got_parameter = get_parameter(sub_name, parameter);
310  if (!got_parameter) {
311  parameter = alternative_value;
312  }
313  return got_parameter;
314 }
315 
316 template<typename ParameterT>
317 ParameterT
319  const std::string & name,
320  const ParameterT & alternative_value) const
321 {
322  ParameterT parameter;
323  get_parameter_or(name, parameter, alternative_value);
324  return parameter;
325 }
326 
327 // this is a partially-specialized version of get_parameter above,
328 // where our concrete type for ParameterT is std::map, but the to-be-determined
329 // type is the value in the map.
330 template<typename ParameterT>
331 bool
333  const std::string & prefix,
334  std::map<std::string, ParameterT> & values) const
335 {
336  std::map<std::string, rclcpp::Parameter> params;
337  bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
338  if (result) {
339  for (const auto & param : params) {
340  values[param.first] = static_cast<ParameterT>(param.second.get_value<ParameterT>());
341  }
342  }
343 
344  return result;
345 }
346 
347 } // namespace rclcpp
348 
349 #endif // RCLCPP__NODE_IMPL_HPP_
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:384
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::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
Definition: node_impl.hpp:141
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:314
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:302
std::shared_ptr< rclcpp::GenericSubscription > create_generic_subscription(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, std::function< void(std::shared_ptr< rclcpp::SerializedMessage >)> callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
Definition: node_impl.hpp:175
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:237
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
Definition: node.cpp:372
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)
Create a timer.
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:584
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
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:158
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:111
Thrown if requested parameter type is invalid.
Definition: exceptions.hpp:246
Thrown if user attempts to create an uninitialized statically typed parameter.
Definition: exceptions.hpp:264
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
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, std::function< void(std::shared_ptr< rclcpp::SerializedMessage >)> callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
Create and return a GenericSubscription.
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.
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)
Convenience method to create a timer with node resources.
Structure containing optional configuration for Publishers.
Structure containing optional configuration for Subscriptions.