15 #ifndef RCLCPP__DETAIL__QOS_PARAMETERS_HPP_
16 #define RCLCPP__DETAIL__QOS_PARAMETERS_HPP_
21 #include <initializer_list>
24 #include <type_traits>
27 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
28 #include "rcpputils/pointer_traits.hpp"
29 #include "rmw/qos_string_conversions.h"
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"
44 static constexpr
const char * entity_type() {
return "publisher";}
45 static constexpr
auto allowed_policies()
47 return std::array<::rclcpp::QosPolicyKind, 9> {
48 QosPolicyKind::AvoidRosNamespaceConventions,
49 QosPolicyKind::Deadline,
50 QosPolicyKind::Durability,
51 QosPolicyKind::History,
53 QosPolicyKind::Lifespan,
54 QosPolicyKind::Liveliness,
55 QosPolicyKind::LivelinessLeaseDuration,
56 QosPolicyKind::Reliability,
64 static constexpr
const char * entity_type() {
return "subscription";}
65 static constexpr
auto allowed_policies()
67 return std::array<::rclcpp::QosPolicyKind, 8> {
68 QosPolicyKind::AvoidRosNamespaceConventions,
69 QosPolicyKind::Deadline,
70 QosPolicyKind::Durability,
71 QosPolicyKind::History,
73 QosPolicyKind::Liveliness,
74 QosPolicyKind::LivelinessLeaseDuration,
75 QosPolicyKind::Reliability,
82 ::rclcpp::ParameterValue
83 get_default_qos_param_value(rclcpp::QosPolicyKind policy,
const rclcpp::QoS & qos);
93 declare_parameter_or_get(
95 const std::string & param_name,
97 rcl_interfaces::msg::ParameterDescriptor descriptor)
101 param_name, param_value, descriptor);
120 template<
typename NodeT,
typename EntityQosParametersTraits>
122 declare_qos_parameters(
123 const ::rclcpp::QosOverridingOptions & options,
125 const std::string & topic_name,
126 const ::rclcpp::QoS & default_qos,
127 EntityQosParametersTraits);
131 template<
typename NodeT,
typename EntityQosParametersTraits>
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),
138 declare_qos_parameters(
139 const ::rclcpp::QosOverridingOptions & options,
141 const std::string & topic_name,
142 const ::rclcpp::QoS & default_qos,
143 EntityQosParametersTraits)
145 auto & parameters_interface = *rclcpp::node_interfaces::get_node_parameters_interface(node);
146 std::string param_prefix;
147 const auto &
id = options.get_id();
149 std::ostringstream oss{
"qos_overrides.", std::ios::ate};
150 oss << topic_name <<
"." << EntityQosParametersTraits::entity_type();
155 param_prefix = oss.str();
157 std::string param_description_suffix;
159 std::ostringstream oss{
"} for ", std::ios::ate};
160 oss << EntityQosParametersTraits::entity_type() <<
" {" << topic_name <<
"}";
162 oss <<
" with id {" <<
id <<
"}";
164 param_description_suffix = oss.str();
167 for (
auto policy : EntityQosParametersTraits::allowed_policies()) {
169 std::count(options.get_policy_kinds().begin(), options.get_policy_kinds().end(), policy))
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);
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};
197 template<
typename NodeT,
typename EntityQosParametersTraits>
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),
204 declare_qos_parameters(
205 const ::rclcpp::QosOverridingOptions & options,
208 const ::rclcpp::QoS & default_qos,
209 EntityQosParametersTraits)
211 if (options.get_policy_kinds().size()) {
212 std::runtime_error exc{
213 "passed non-default qos overriding options without providing a parameters interface"};
222 #define RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING( \
223 kind_lower, kind_upper, parameter_value, rclcpp_qos) \
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}; \
230 ((rclcpp_qos).kind_lower)(policy_value); \
239 case QosPolicyKind::AvoidRosNamespaceConventions:
242 case QosPolicyKind::Deadline:
245 case QosPolicyKind::Durability:
246 RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
247 durability, DURABILITY, value, qos);
249 case QosPolicyKind::History:
250 RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
251 history, HISTORY, value, qos);
253 case QosPolicyKind::Depth:
256 case QosPolicyKind::Lifespan:
259 case QosPolicyKind::Liveliness:
260 RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
261 liveliness, LIVELINESS, value, qos);
263 case QosPolicyKind::LivelinessLeaseDuration:
266 case QosPolicyKind::Reliability:
267 RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
268 reliability, RELIABILITY, value, qos);
271 throw std::invalid_argument{
"unknown QosPolicyKind"};
278 rmw_duration_to_int64_t(rmw_time_t rmw_duration)
280 return ::rclcpp::Duration(
281 static_cast<int32_t
>(rmw_duration.sec),
282 static_cast<uint32_t
>(rmw_duration.nsec)
289 check_if_stringified_policy_is_null(
const char * policy_value_stringified, QosPolicyKind kind)
291 if (!policy_value_stringified) {
292 std::ostringstream oss{
"unknown value for policy kind {", std::ios::ate};
294 throw std::invalid_argument{oss.str()};
296 return policy_value_stringified;
300 ::rclcpp::ParameterValue
301 get_default_qos_param_value(rclcpp::QosPolicyKind kind,
const rclcpp::QoS & qos)
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));
333 throw std::invalid_argument{
"unknown QoS policy kind"};
static Duration from_nanoseconds(rcl_duration_value_t nanoseconds)
Create a duration object from an integer number representing nanoseconds.
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.
Encapsulation of Quality of Service settings.
QoS & lifespan(rmw_time_t lifespan)
Set the lifespan setting.
QoS & deadline(rmw_time_t deadline)
Set the deadline setting.
QoS & liveliness_lease_duration(rmw_time_t liveliness_lease_duration)
Set the liveliness_lease_duration setting.
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
QoS & avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions)
Set the avoid_ros_namespace_conventions setting.
Thrown if the QoS overrides provided aren't valid.
Thrown if parameter is already declared.
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 ¶meter_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.