rclcpp  master
C++ ROS Client Library API
node_impl.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_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 
38 #include "rclcpp/create_client.hpp"
44 #include "rclcpp/create_timer.hpp"
46 #include "rclcpp/parameter.hpp"
47 #include "rclcpp/qos.hpp"
48 #include "rclcpp/timer.hpp"
51 
52 #ifndef RCLCPP__NODE_HPP_
53 #include "node.hpp"
54 #endif
55 
56 namespace rclcpp
57 {
58 
60 inline
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>
74  const std::string & topic_name,
75  const rclcpp::QoS & qos,
77 {
78  return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
79  *this,
81  qos,
82  options);
83 }
84 
85 template<
86  typename MessageT,
87  typename CallbackT,
88  typename AllocatorT,
89  typename CallbackMessageT,
90  typename SubscriptionT,
91  typename MessageMemoryStrategyT>
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,
103  qos,
104  std::forward<CallbackT>(callback),
105  options,
106  msg_mem_strat);
107 }
108 
109 template<typename DurationRepT, typename DurationT, typename CallbackT>
113  CallbackT callback,
114  rclcpp::CallbackGroup::SharedPtr group)
115 {
117  period,
118  std::move(callback),
119  group,
120  this->node_base_.get(),
121  this->node_timers_.get());
122 }
123 
124 template<typename ServiceT>
127  const std::string & service_name,
128  const rmw_qos_profile_t & qos_profile,
129  rclcpp::CallbackGroup::SharedPtr group)
130 {
131  return rclcpp::create_client<ServiceT>(
132  node_base_,
133  node_graph_,
134  node_services_,
135  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
136  qos_profile,
137  group);
138 }
139 
140 template<typename ServiceT, typename CallbackT>
143  const std::string & service_name,
144  CallbackT && callback,
145  const rmw_qos_profile_t & qos_profile,
146  rclcpp::CallbackGroup::SharedPtr group)
147 {
148  return rclcpp::create_service<ServiceT, CallbackT>(
149  node_base_,
150  node_services_,
151  extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
152  std::forward<CallbackT>(callback),
153  qos_profile,
154  group);
155 }
156 
157 template<typename AllocatorT>
160  const std::string & topic_name,
161  const std::string & topic_type,
162  const rclcpp::QoS & qos,
164 {
166  node_topics_,
168  topic_type,
169  qos,
170  options
171  );
172 }
173 
174 template<typename AllocatorT>
177  const std::string & topic_name,
178  const std::string & topic_type,
179  const rclcpp::QoS & qos,
182 {
184  node_topics_,
186  topic_type,
187  qos,
188  std::move(callback),
189  options
190  );
191 }
192 
193 
194 template<typename ParameterT>
195 auto
197  const std::string & name,
198  const ParameterT & default_value,
199  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
200  bool ignore_override)
201 {
202  try {
203  return this->declare_parameter(
204  name,
205  rclcpp::ParameterValue(default_value),
206  parameter_descriptor,
207  ignore_override
208  ).get<ParameterT>();
209  } catch (const ParameterTypeException & ex) {
211  }
212 }
213 
214 template<typename ParameterT>
215 auto
217  const std::string & name,
218  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
219  bool ignore_override)
220 {
221  // get advantage of parameter value template magic to get
222  // the correct rclcpp::ParameterType from ParameterT
223  rclcpp::ParameterValue value{ParameterT{}};
224  return this->declare_parameter(
225  name,
226  value.get_type(),
227  parameter_descriptor,
228  ignore_override
229  ).get<ParameterT>();
230 }
231 
232 template<typename ParameterT>
235  const std::string & namespace_,
236  const std::map<std::string, ParameterT> & parameters,
237  bool ignore_overrides)
238 {
240  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
242  parameters.begin(), parameters.end(), std::back_inserter(result),
243  [this, &normalized_namespace, ignore_overrides](auto element) {
244  return this->declare_parameter(
245  normalized_namespace + element.first,
246  element.second,
247  rcl_interfaces::msg::ParameterDescriptor(),
248  ignore_overrides);
249  }
250  );
251  return result;
252 }
253 
254 template<typename ParameterT>
257  const std::string & namespace_,
258  const std::map<
259  std::string,
261  > & parameters,
262  bool ignore_overrides)
263 {
265  std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
267  parameters.begin(), parameters.end(), std::back_inserter(result),
268  [this, &normalized_namespace, ignore_overrides](auto element) {
269  return static_cast<ParameterT>(
270  this->declare_parameter(
271  normalized_namespace + element.first,
272  element.second.first,
273  element.second.second,
274  ignore_overrides)
275  );
276  }
277  );
278  return result;
279 }
280 
281 template<typename ParameterT>
282 bool
283 Node::get_parameter(const std::string & name, ParameterT & parameter) const
284 {
286 
287  rclcpp::Parameter parameter_variant;
288 
289  bool result = get_parameter(sub_name, parameter_variant);
290  if (result) {
291  parameter = static_cast<ParameterT>(parameter_variant.get_value<ParameterT>());
292  }
293 
294  return result;
295 }
296 
297 template<typename ParameterT>
298 bool
300  const std::string & name,
301  ParameterT & parameter,
302  const ParameterT & alternative_value) const
303 {
305 
306  bool got_parameter = get_parameter(sub_name, parameter);
307  if (!got_parameter) {
308  parameter = alternative_value;
309  }
310  return got_parameter;
311 }
312 
313 // this is a partially-specialized version of get_parameter above,
314 // where our concrete type for ParameterT is std::map, but the to-be-determined
315 // type is the value in the map.
316 template<typename ParameterT>
317 bool
319  const std::string & prefix,
320  std::map<std::string, ParameterT> & values) const
321 {
323  bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
324  if (result) {
325  for (const auto & param : params) {
326  values[param.first] = static_cast<ParameterT>(param.second.get_value<ParameterT>());
327  }
328  }
329 
330  return result;
331 }
332 
333 } // namespace rclcpp
334 
335 #endif // RCLCPP__NODE_IMPL_HPP_
rclcpp::ParameterValue
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
rclcpp::create_wall_timer
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.
Definition: create_timer.hpp:90
std::string
create_generic_publisher.hpp
std::shared_ptr
rclcpp::create_generic_publisher
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.
Definition: create_generic_publisher.hpp:45
RCLCPP_LOCAL
#define RCLCPP_LOCAL
Definition: visibility_control.hpp:51
std::move
T move(T... args)
rmw.h
std::pair
rclcpp::Node::create_wall_timer
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:111
std::vector
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL, const bool & >::type get() const
Definition: parameter_value.hpp:148
node.hpp
std::back_inserter
T back_inserter(T... args)
error_handling.h
rclcpp::Parameter::get_value
decltype(auto) get_value() const
Get value of parameter using rclcpp::ParameterType as template argument.
Definition: parameter.hpp:117
std::chrono::duration
rclcpp::Service
Definition: service.hpp:144
rclcpp::Node::create_subscription
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
create_generic_subscription.hpp
create_client.hpp
rclcpp::Node::create_client
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.
rclcpp::SubscriptionOptionsWithAllocator
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:87
std::function
subscription.h
rclcpp::ParameterTypeException
Indicate the parameter type does not match the expected type.
Definition: parameter_value.hpp:56
rclcpp::extend_name_with_sub_namespace
RCLCPP_LOCAL std::string extend_name_with_sub_namespace(const std::string &name, const std::string &sub_namespace)
Definition: node_impl.hpp:62
std::string::front
T front(T... args)
rclcpp::Node::get_parameter
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
publisher.h
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
qos.hpp
rclcpp::Node::create_publisher
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
timer.hpp
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
rclcpp::Node::create_generic_subscription
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:176
rclcpp::Node::get_parameters
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
rclcpp::Node::create_service
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:142
rclcpp::Node::create_generic_publisher
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:159
create_service.hpp
create_subscription.hpp
rclcpp::Node::get_parameter_or
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:299
std::map
std::transform
T transform(T... args)
rclcpp::Node::declare_parameter
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.
rclcpp::Node::declare_parameters
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:234
create_timer.hpp
parameter.hpp
default_context.hpp
rclcpp::PublisherOptionsWithAllocator
Structure containing optional configuration for Publishers.
Definition: publisher_options.hpp:65
rclcpp::Client
Definition: client.hpp:178
type_support_decl.hpp
std::map::begin
T begin(T... args)
visibility_control.hpp
rclcpp::Node::get_sub_namespace
const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
rmw_qos_profile_t
std::string::empty
T empty(T... args)
rclcpp::WallTimer
Definition: timer.hpp:259
rclcpp::Parameter
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:52
std::map::end
T end(T... args)
rclcpp::exceptions::InvalidParameterTypeException
Thrown if requested parameter type is invalid.
Definition: exceptions.hpp:243
resolve_enable_topic_statistics.hpp
std::runtime_error::what
T what(T... args)
rclcpp::create_generic_subscription
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.
Definition: create_generic_subscription.hpp:49
create_publisher.hpp