ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
qos_parameters.hpp
1 // Copyright 2020 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__DETAIL__QOS_PARAMETERS_HPP_
16 #define RCLCPP__DETAIL__QOS_PARAMETERS_HPP_
17 
18 #include <algorithm>
19 #include <array>
20 #include <functional>
21 #include <initializer_list>
22 #include <map>
23 #include <string>
24 #include <type_traits>
25 #include <vector>
26 
27 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
28 #include "rcpputils/pointer_traits.hpp"
29 #include "rmw/qos_string_conversions.h"
30 
31 #include "rclcpp/duration.hpp"
32 #include "rclcpp/node_interfaces/get_node_parameters_interface.hpp"
33 #include "rclcpp/node_interfaces/node_parameters_interface.hpp"
34 #include "rclcpp/qos_overriding_options.hpp"
35 
36 namespace rclcpp
37 {
38 namespace detail
39 {
40 
43 {
44  static constexpr const char * entity_type() {return "publisher";}
45  static constexpr auto allowed_policies()
46  {
47  return std::array<::rclcpp::QosPolicyKind, 9> {
48  QosPolicyKind::AvoidRosNamespaceConventions,
49  QosPolicyKind::Deadline,
50  QosPolicyKind::Durability,
51  QosPolicyKind::History,
52  QosPolicyKind::Depth,
53  QosPolicyKind::Lifespan,
54  QosPolicyKind::Liveliness,
55  QosPolicyKind::LivelinessLeaseDuration,
56  QosPolicyKind::Reliability,
57  };
58  }
59 };
60 
63 {
64  static constexpr const char * entity_type() {return "subscription";}
65  static constexpr auto allowed_policies()
66  {
67  return std::array<::rclcpp::QosPolicyKind, 8> {
68  QosPolicyKind::AvoidRosNamespaceConventions,
69  QosPolicyKind::Deadline,
70  QosPolicyKind::Durability,
71  QosPolicyKind::History,
72  QosPolicyKind::Depth,
73  QosPolicyKind::Liveliness,
74  QosPolicyKind::LivelinessLeaseDuration,
75  QosPolicyKind::Reliability,
76  };
77  }
78 };
79 
81 inline
82 ::rclcpp::ParameterValue
83 get_default_qos_param_value(rclcpp::QosPolicyKind policy, const rclcpp::QoS & qos);
84 
86 inline
87 void
88 apply_qos_override(
89  rclcpp::QosPolicyKind policy, rclcpp::ParameterValue value, rclcpp::QoS & qos);
90 
91 inline
93 declare_parameter_or_get(
95  const std::string & param_name,
96  rclcpp::ParameterValue param_value,
97  rcl_interfaces::msg::ParameterDescriptor descriptor)
98 {
99  try {
100  return parameters_interface.declare_parameter(
101  param_name, param_value, descriptor);
103  return parameters_interface.get_parameter(param_name).get_parameter_value();
104  }
105 }
106 
107 #ifdef DOXYGEN_ONLY
109 
120 template<typename NodeT, typename EntityQosParametersTraits>
122  declare_qos_parameters(
123  const ::rclcpp::QosOverridingOptions & options,
124  NodeT & node,
125  const std::string & topic_name,
126  const ::rclcpp::QoS & default_qos,
127  EntityQosParametersTraits);
128 
129 #else
130 
131 template<typename NodeT, typename EntityQosParametersTraits>
132 std::enable_if_t<
133  (rclcpp::node_interfaces::has_node_parameters_interface<
134  decltype(std::declval<typename rcpputils::remove_pointer<NodeT>::type>())>::value ||
135  std::is_same<typename std::decay_t<NodeT>,
136  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value),
137  rclcpp::QoS>
138 declare_qos_parameters(
139  const ::rclcpp::QosOverridingOptions & options,
140  NodeT & node,
141  const std::string & topic_name,
142  const ::rclcpp::QoS & default_qos,
143  EntityQosParametersTraits)
144 {
145  auto & parameters_interface = *rclcpp::node_interfaces::get_node_parameters_interface(node);
146  std::string param_prefix;
147  const auto & id = options.get_id();
148  {
149  std::ostringstream oss{"qos_overrides.", std::ios::ate};
150  oss << topic_name << "." << EntityQosParametersTraits::entity_type();
151  if (!id.empty()) {
152  oss << "_" << id;
153  }
154  oss << ".";
155  param_prefix = oss.str();
156  }
157  std::string param_description_suffix;
158  {
159  std::ostringstream oss{"} for ", std::ios::ate};
160  oss << EntityQosParametersTraits::entity_type() << " {" << topic_name << "}";
161  if (!id.empty()) {
162  oss << " with id {" << id << "}";
163  }
164  param_description_suffix = oss.str();
165  }
166  rclcpp::QoS qos = default_qos;
167  for (auto policy : EntityQosParametersTraits::allowed_policies()) {
168  if (
169  std::count(options.get_policy_kinds().begin(), options.get_policy_kinds().end(), policy))
170  {
171  std::ostringstream param_name{param_prefix, std::ios::ate};
172  param_name << qos_policy_kind_to_cstr(policy);
173  std::ostringstream param_desciption{"qos policy {", std::ios::ate};
174  param_desciption << qos_policy_kind_to_cstr(policy) << param_description_suffix;
175  rcl_interfaces::msg::ParameterDescriptor descriptor{};
176  descriptor.description = param_desciption.str();
177  descriptor.read_only = true;
178  auto value = declare_parameter_or_get(
179  parameters_interface, param_name.str(),
180  get_default_qos_param_value(policy, qos), descriptor);
181  ::rclcpp::detail::apply_qos_override(policy, value, qos);
182  }
183  }
184  const auto & validation_callback = options.get_validation_callback();
185  if (validation_callback) {
186  auto result = validation_callback(qos);
187  if (!result.successful) {
189  "validation callback failed: " + result.reason};
190  }
191  }
192  return qos;
193 }
194 
195 // TODO(ivanpauno): This overload cannot declare the QoS parameters, as a node parameters interface
196 // was not provided.
197 template<typename NodeT, typename EntityQosParametersTraits>
198 std::enable_if_t<
199  !(rclcpp::node_interfaces::has_node_parameters_interface<
200  decltype(std::declval<typename rcpputils::remove_pointer<NodeT>::type>())>::value ||
201  std::is_same<typename std::decay_t<NodeT>,
202  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value),
203  rclcpp::QoS>
204 declare_qos_parameters(
205  const ::rclcpp::QosOverridingOptions & options,
206  NodeT &,
207  const std::string &,
208  const ::rclcpp::QoS & default_qos,
209  EntityQosParametersTraits)
210 {
211  if (options.get_policy_kinds().size()) {
212  std::runtime_error exc{
213  "passed non-default qos overriding options without providing a parameters interface"};
214  throw exc;
215  }
216  return default_qos;
217 }
218 
219 #endif
220 
222 #define RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING( \
223  kind_lower, kind_upper, parameter_value, rclcpp_qos) \
224  do { \
225  auto policy_string = (parameter_value).get<std::string>(); \
226  auto policy_value = rmw_qos_ ## kind_lower ## _policy_from_str(policy_string.c_str()); \
227  if (RMW_QOS_POLICY_ ## kind_upper ## _UNKNOWN == policy_value) { \
228  throw std::invalid_argument{"unknown QoS policy " #kind_lower " value: " + policy_string}; \
229  } \
230  ((rclcpp_qos).kind_lower)(policy_value); \
231  } while (0)
232 
233 inline
234 void
235 apply_qos_override(
236  rclcpp::QosPolicyKind policy, rclcpp::ParameterValue value, rclcpp::QoS & qos)
237 {
238  switch (policy) {
239  case QosPolicyKind::AvoidRosNamespaceConventions:
240  qos.avoid_ros_namespace_conventions(value.get<bool>());
241  break;
242  case QosPolicyKind::Deadline:
243  qos.deadline(::rclcpp::Duration::from_nanoseconds(value.get<int64_t>()));
244  break;
245  case QosPolicyKind::Durability:
246  RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
247  durability, DURABILITY, value, qos);
248  break;
249  case QosPolicyKind::History:
250  RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
251  history, HISTORY, value, qos);
252  break;
253  case QosPolicyKind::Depth:
254  qos.get_rmw_qos_profile().depth = static_cast<size_t>(value.get<int64_t>());
255  break;
256  case QosPolicyKind::Lifespan:
257  qos.lifespan(::rclcpp::Duration::from_nanoseconds(value.get<int64_t>()));
258  break;
259  case QosPolicyKind::Liveliness:
260  RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
261  liveliness, LIVELINESS, value, qos);
262  break;
263  case QosPolicyKind::LivelinessLeaseDuration:
265  break;
266  case QosPolicyKind::Reliability:
267  RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
268  reliability, RELIABILITY, value, qos);
269  break;
270  default:
271  throw std::invalid_argument{"unknown QosPolicyKind"};
272  }
273 }
274 
276 inline
277 int64_t
278 rmw_duration_to_int64_t(rmw_time_t rmw_duration)
279 {
280  return ::rclcpp::Duration(
281  static_cast<int32_t>(rmw_duration.sec),
282  static_cast<uint32_t>(rmw_duration.nsec)
283  ).nanoseconds();
284 }
285 
287 inline
288 const char *
289 check_if_stringified_policy_is_null(const char * policy_value_stringified, QosPolicyKind kind)
290 {
291  if (!policy_value_stringified) {
292  std::ostringstream oss{"unknown value for policy kind {", std::ios::ate};
293  oss << kind << "}";
294  throw std::invalid_argument{oss.str()};
295  }
296  return policy_value_stringified;
297 }
298 
299 inline
300 ::rclcpp::ParameterValue
301 get_default_qos_param_value(rclcpp::QosPolicyKind kind, const rclcpp::QoS & qos)
302 {
303  using ParameterValue = ::rclcpp::ParameterValue;
304  const auto & rmw_qos = qos.get_rmw_qos_profile();
305  switch (kind) {
306  case QosPolicyKind::AvoidRosNamespaceConventions:
307  return ParameterValue(rmw_qos.avoid_ros_namespace_conventions);
308  case QosPolicyKind::Deadline:
309  return ParameterValue(rmw_duration_to_int64_t(rmw_qos.deadline));
310  case QosPolicyKind::Durability:
311  return ParameterValue(
312  check_if_stringified_policy_is_null(
313  rmw_qos_durability_policy_to_str(rmw_qos.durability), kind));
314  case QosPolicyKind::History:
315  return ParameterValue(
316  check_if_stringified_policy_is_null(
317  rmw_qos_history_policy_to_str(rmw_qos.history), kind));
318  case QosPolicyKind::Depth:
319  return ParameterValue(static_cast<int64_t>(rmw_qos.depth));
320  case QosPolicyKind::Lifespan:
321  return ParameterValue(rmw_duration_to_int64_t(rmw_qos.lifespan));
322  case QosPolicyKind::Liveliness:
323  return ParameterValue(
324  check_if_stringified_policy_is_null(
325  rmw_qos_liveliness_policy_to_str(rmw_qos.liveliness), kind));
326  case QosPolicyKind::LivelinessLeaseDuration:
327  return ParameterValue(rmw_duration_to_int64_t(rmw_qos.liveliness_lease_duration));
328  case QosPolicyKind::Reliability:
329  return ParameterValue(
330  check_if_stringified_policy_is_null(
331  rmw_qos_reliability_policy_to_str(rmw_qos.reliability), kind));
332  default:
333  throw std::invalid_argument{"unknown QoS policy kind"};
334  }
335 }
336 
337 } // namespace detail
338 } // namespace rclcpp
339 
340 #endif // RCLCPP__DETAIL__QOS_PARAMETERS_HPP_
static Duration from_nanoseconds(rcl_duration_value_t nanoseconds)
Create a duration object from an integer number representing nanoseconds.
Definition: duration.cpp:314
Store the type and value of a parameter.
RCLCPP_PUBLIC const rclcpp::ParameterValue & get_parameter_value() const
Get the internal storage for the parameter value.
Definition: parameter.cpp:85
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
QoS & lifespan(rmw_time_t lifespan)
Set the lifespan setting.
Definition: qos.cpp:229
QoS & deadline(rmw_time_t deadline)
Set the deadline setting.
Definition: qos.cpp:216
QoS & liveliness_lease_duration(rmw_time_t liveliness_lease_duration)
Set the liveliness_lease_duration setting.
Definition: qos.cpp:257
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
Definition: qos.cpp:102
QoS & avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions)
Set the avoid_ros_namespace_conventions setting.
Definition: qos.cpp:270
Thrown if the QoS overrides provided aren't valid.
Definition: exceptions.hpp:335
Thrown if parameter is already declared.
Definition: exceptions.hpp:294
Pure virtual interface class for the NodeParameters part of the Node API.
virtual 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)=0
Declare and initialize a parameter.
virtual RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const =0
Get the description of one parameter given a name.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.