rclcpp  master
C++ ROS Client Library API
qos_parameters.hpp
Go to the documentation of this file.
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"
30 
31 #include "rclcpp/duration.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  {
57  };
58  }
59 };
60 
63 {
64  static constexpr const char * entity_type() {return "subscription";}
65  static constexpr auto allowed_policies()
66  {
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
89  rclcpp::QosPolicyKind policy, rclcpp::ParameterValue value, rclcpp::QoS & qos);
90 
91 inline
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 
108 
119 template<typename NodeT, typename EntityQosParametersTraits>
120 std::enable_if_t<
122  decltype(std::declval<typename rcpputils::remove_pointer<NodeT>::type>())>::value ||
124  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value,
125  rclcpp::QoS>
127  const ::rclcpp::QosOverridingOptions & options,
128  NodeT & node,
129  const std::string & topic_name,
130  const ::rclcpp::QoS & default_qos,
131  EntityQosParametersTraits)
132 {
133  auto & parameters_interface = *rclcpp::node_interfaces::get_node_parameters_interface(node);
134  std::string param_prefix;
135  const auto & id = options.get_id();
136  {
137  std::ostringstream oss{"qos_overrides.", std::ios::ate};
138  oss << topic_name << "." << EntityQosParametersTraits::entity_type();
139  if (!id.empty()) {
140  oss << "_" << id;
141  }
142  oss << ".";
143  param_prefix = oss.str();
144  }
145  std::string param_description_suffix;
146  {
147  std::ostringstream oss{"} for ", std::ios::ate};
148  oss << EntityQosParametersTraits::entity_type() << " {" << topic_name << "}";
149  if (!id.empty()) {
150  oss << " with id {" << id << "}";
151  }
152  param_description_suffix = oss.str();
153  }
154  rclcpp::QoS qos = default_qos;
155  for (auto policy : EntityQosParametersTraits::allowed_policies()) {
156  if (
157  std::count(options.get_policy_kinds().begin(), options.get_policy_kinds().end(), policy))
158  {
159  std::ostringstream param_name{param_prefix, std::ios::ate};
160  param_name << qos_policy_kind_to_cstr(policy);
161  std::ostringstream param_desciption{"qos policy {", std::ios::ate};
162  param_desciption << qos_policy_kind_to_cstr(policy) << param_description_suffix;
163  rcl_interfaces::msg::ParameterDescriptor descriptor{};
164  descriptor.description = param_desciption.str();
165  descriptor.read_only = true;
166  auto value = declare_parameter_or_get(
167  parameters_interface, param_name.str(),
168  get_default_qos_param_value(policy, qos), descriptor);
169  ::rclcpp::detail::apply_qos_override(policy, value, qos);
170  }
171  }
172  const auto & validation_callback = options.get_validation_callback();
173  if (validation_callback) {
174  auto result = validation_callback(qos);
175  if (!result.successful) {
177  "validation callback failed: " + result.reason};
178  }
179  }
180  return qos;
181 }
182 
183 // TODO(ivanpauno): This overload cannot declare the QoS parameters, as a node parameters interface
184 // was not provided.
185 template<typename NodeT, typename EntityQosParametersTraits>
186 std::enable_if_t<
188  decltype(std::declval<typename rcpputils::remove_pointer<NodeT>::type>())>::value ||
190  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value),
191  rclcpp::QoS>
193  const ::rclcpp::QosOverridingOptions & options,
194  NodeT &,
195  const std::string &,
196  const ::rclcpp::QoS & default_qos,
197  EntityQosParametersTraits)
198 {
199  if (options.get_policy_kinds().size()) {
200  std::runtime_error exc{
201  "passed non-default qos overriding options without providing a parameters interface"};
202  throw exc;
203  }
204  return default_qos;
205 }
206 
208 #define RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING( \
209  kind_lower, kind_upper, parameter_value, rclcpp_qos) \
210  do { \
211  auto policy_string = (parameter_value).get<std::string>(); \
212  auto policy_value = rmw_qos_ ## kind_lower ## _policy_from_str(policy_string.c_str()); \
213  if (RMW_QOS_POLICY_ ## kind_upper ## _UNKNOWN == policy_value) { \
214  throw std::invalid_argument{"unknown QoS policy " #kind_lower " value: " + policy_string}; \
215  } \
216  ((rclcpp_qos).kind_lower)(policy_value); \
217  } while (0)
218 
219 inline
220 void
222  rclcpp::QosPolicyKind policy, rclcpp::ParameterValue value, rclcpp::QoS & qos)
223 {
224  switch (policy) {
226  qos.avoid_ros_namespace_conventions(value.get<bool>());
227  break;
229  qos.deadline(::rclcpp::Duration::from_nanoseconds(value.get<int64_t>()));
230  break;
233  durability, DURABILITY, value, qos);
234  break;
237  history, HISTORY, value, qos);
238  break;
240  qos.get_rmw_qos_profile().depth = static_cast<size_t>(value.get<int64_t>());
241  break;
243  qos.lifespan(::rclcpp::Duration::from_nanoseconds(value.get<int64_t>()));
244  break;
247  liveliness, LIVELINESS, value, qos);
248  break;
251  break;
254  reliability, RELIABILITY, value, qos);
255  break;
256  default:
257  throw std::invalid_argument{"unknown QosPolicyKind"};
258  }
259 }
260 
262 inline
263 int64_t
265 {
266  return ::rclcpp::Duration(
267  static_cast<int32_t>(rmw_duration.sec),
268  static_cast<uint32_t>(rmw_duration.nsec)
269  ).nanoseconds();
270 }
271 
273 inline
274 const char *
275 check_if_stringified_policy_is_null(const char * policy_value_stringified, QosPolicyKind kind)
276 {
277  if (!policy_value_stringified) {
278  std::ostringstream oss{"unknown value for policy kind {", std::ios::ate};
279  oss << kind << "}";
280  throw std::invalid_argument{oss.str()};
281  }
282  return policy_value_stringified;
283 }
284 
285 inline
286 ::rclcpp::ParameterValue
287 get_default_qos_param_value(rclcpp::QosPolicyKind kind, const rclcpp::QoS & qos)
288 {
290  const auto & rmw_qos = qos.get_rmw_qos_profile();
291  switch (kind) {
293  return ParameterValue(rmw_qos.avoid_ros_namespace_conventions);
295  return ParameterValue(rmw_duration_to_int64_t(rmw_qos.deadline));
297  return ParameterValue(
299  rmw_qos_durability_policy_to_str(rmw_qos.durability), kind));
301  return ParameterValue(
303  rmw_qos_history_policy_to_str(rmw_qos.history), kind));
305  return ParameterValue(static_cast<int64_t>(rmw_qos.depth));
307  return ParameterValue(rmw_duration_to_int64_t(rmw_qos.lifespan));
309  return ParameterValue(
311  rmw_qos_liveliness_policy_to_str(rmw_qos.liveliness), kind));
313  return ParameterValue(rmw_duration_to_int64_t(rmw_qos.liveliness_lease_duration));
315  return ParameterValue(
317  rmw_qos_reliability_policy_to_str(rmw_qos.reliability), kind));
318  default:
319  throw std::invalid_argument{"unknown QoS policy kind"};
320  }
321 }
322 
323 } // namespace detail
324 } // namespace rclcpp
325 
326 #endif // RCLCPP__DETAIL__QOS_PARAMETERS_HPP_
std::is_same
rmw_qos_reliability_policy_to_str
const char * rmw_qos_reliability_policy_to_str(enum rmw_qos_reliability_policy_t value)
rmw_time_t::nsec
uint64_t nsec
LivelinessLeaseDuration
LivelinessLeaseDuration
Definition: qos_overriding_options.hpp:43
rclcpp::ParameterValue
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
std::string
rclcpp::qos_policy_kind_to_cstr
const char * qos_policy_kind_to_cstr(const QosPolicyKind &qpk)
Depth
Depth
Definition: qos_overriding_options.hpp:38
rmw_time_t
History
History
Definition: qos_overriding_options.hpp:40
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL, const bool & >::type get() const
Definition: parameter_value.hpp:148
rclcpp::QoS::get_rmw_qos_profile
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
rclcpp::detail::rmw_duration_to_int64_t
int64_t rmw_duration_to_int64_t(rmw_time_t rmw_duration)
Convert rmw_time_t to int64_t that can be used as a parameter value.
Definition: qos_parameters.hpp:264
rclcpp::QoS::avoid_ros_namespace_conventions
QoS & avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions)
Set the avoid_ros_namespace_conventions setting.
Deadline
Deadline
Definition: qos_overriding_options.hpp:37
rclcpp::node_interfaces::NodeParametersInterface::get_parameter
virtual rclcpp::Parameter get_parameter(const std::string &name) const =0
Get the description of one parameter given a name.
rclcpp::QoS::lifespan
QoS & lifespan(rmw_time_t lifespan)
Set the lifespan setting.
Liveliness
Liveliness
Definition: qos_overriding_options.hpp:42
rclcpp::detail::declare_qos_parameters
std::enable_if_t< rclcpp::node_interfaces::has_node_parameters_interface< decltype(std::declval< typename rcpputils::remove_pointer< NodeT >::type >))>::value||std::is_same< typename std::decay_t< NodeT >, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr >::value, rclcpp::QoS > declare_qos_parameters(const ::rclcpp::QosOverridingOptions &options, NodeT &node, const std::string &topic_name, const ::rclcpp::QoS &default_qos, EntityQosParametersTraits)
Definition: qos_parameters.hpp:126
RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING
#define RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(kind_lower, kind_upper, parameter_value, rclcpp_qos)
Definition: qos_parameters.hpp:208
rclcpp::detail::check_if_stringified_policy_is_null
const char * check_if_stringified_policy_is_null(const char *policy_value_stringified, QosPolicyKind kind)
Definition: qos_parameters.hpp:275
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
rclcpp::node_interfaces::NodeParametersInterface::declare_parameter
virtual const rclcpp::ParameterValue & declare_parameter(const std::string &name)=0
Declare a parameter.
get_node_parameters_interface.hpp
rmw_qos_history_policy_to_str
const char * rmw_qos_history_policy_to_str(enum rmw_qos_history_policy_t value)
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
rclcpp::detail::get_default_qos_param_value
inline ::rclcpp::ParameterValue get_default_qos_param_value(rclcpp::QosPolicyKind policy, const rclcpp::QoS &qos)
Definition: qos_parameters.hpp:287
rclcpp::node_interfaces::NodeParametersInterface
Pure virtual interface class for the NodeParameters part of the Node API.
Definition: node_parameters_interface.hpp:60
rclcpp::detail::PublisherQosParametersTraits::entity_type
static constexpr const char * entity_type()
Definition: qos_parameters.hpp:44
rclcpp::exceptions::ParameterAlreadyDeclaredException
Thrown if parameter is already declared.
Definition: exceptions.hpp:258
std::array
rclcpp::detail::PublisherQosParametersTraits::allowed_policies
static constexpr auto allowed_policies()
Definition: qos_parameters.hpp:45
rclcpp::Parameter::get_parameter_value
const rclcpp::ParameterValue & get_parameter_value() const
Get the internal storage for the parameter value.
rclcpp::detail::SubscriptionQosParametersTraits::entity_type
static constexpr const char * entity_type()
Definition: qos_parameters.hpp:64
std::runtime_error
qos_overriding_options.hpp
std::invalid_argument
Durability
Durability
Definition: qos_overriding_options.hpp:39
rmw_time_t::sec
uint64_t sec
rclcpp::detail::SubscriptionQosParametersTraits
Definition: qos_parameters.hpp:62
rmw_qos_durability_policy_to_str
const char * rmw_qos_durability_policy_to_str(enum rmw_qos_durability_policy_t value)
Reliability
Reliability
Definition: qos_overriding_options.hpp:44
rclcpp::QoS::deadline
QoS & deadline(rmw_time_t deadline)
Set the deadline setting.
rclcpp::Duration::from_nanoseconds
static Duration from_nanoseconds(rcl_duration_value_t nanoseconds)
Create a duration object from an integer number representing nanoseconds.
std::ostringstream
Lifespan
Lifespan
Definition: qos_overriding_options.hpp:41
rclcpp::node_interfaces::get_node_parameters_interface
std::shared_ptr< rclcpp::node_interfaces::NodeParametersInterface > get_node_parameters_interface(NodeType &&node)
Get the NodeParametersInterface as a shared pointer from a pointer to a "Node like" object.
Definition: get_node_parameters_interface.hpp:72
AvoidRosNamespaceConventions
AvoidRosNamespaceConventions
Definition: qos_overriding_options.hpp:36
std::count
T count(T... args)
rclcpp::detail::declare_parameter_or_get
rclcpp::ParameterValue declare_parameter_or_get(rclcpp::node_interfaces::NodeParametersInterface &parameters_interface, const std::string &param_name, rclcpp::ParameterValue param_value, rcl_interfaces::msg::ParameterDescriptor descriptor)
Definition: qos_parameters.hpp:93
rclcpp::detail::SubscriptionQosParametersTraits::allowed_policies
static constexpr auto allowed_policies()
Definition: qos_parameters.hpp:65
rclcpp::detail::PublisherQosParametersTraits
Definition: qos_parameters.hpp:42
rclcpp::exceptions::InvalidQosOverridesException
Thrown if the QoS overrides provided aren't valid.
Definition: exceptions.hpp:300
rmw_qos_liveliness_policy_to_str
const char * rmw_qos_liveliness_policy_to_str(enum rmw_qos_liveliness_policy_t value)
qos_string_conversions.h
rclcpp::QoS::liveliness_lease_duration
QoS & liveliness_lease_duration(rmw_time_t liveliness_lease_duration)
Set the liveliness_lease_duration setting.
rclcpp::detail::apply_qos_override
void apply_qos_override(rclcpp::QosPolicyKind policy, rclcpp::ParameterValue value, rclcpp::QoS &qos)
Definition: qos_parameters.hpp:221
duration.hpp
rmw_qos_profile_t::depth
size_t depth
std::declval
T declval(T... args)
node_parameters_interface.hpp
rclcpp::node_interfaces::has_node_parameters_interface
Definition: node_parameters_interface_traits.hpp:29