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)
104 param_name, param_value, descriptor);
123 template<
typename NodeT,
typename EntityQosParametersTraits>
125 declare_qos_parameters(
126 const ::rclcpp::QosOverridingOptions & options,
128 const std::string & topic_name,
129 const ::rclcpp::QoS & default_qos,
130 EntityQosParametersTraits);
134 template<
typename NodeT,
typename EntityQosParametersTraits>
136 (rclcpp::node_interfaces::has_node_parameters_interface<
137 decltype(std::declval<
typename rcpputils::remove_pointer<NodeT>::type>())>::value ||
138 std::is_same<typename std::decay_t<NodeT>,
139 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value),
141 declare_qos_parameters(
142 const ::rclcpp::QosOverridingOptions & options,
144 const std::string & topic_name,
145 const ::rclcpp::QoS & default_qos,
146 EntityQosParametersTraits)
148 auto & parameters_interface = *rclcpp::node_interfaces::get_node_parameters_interface(node);
149 std::string param_prefix;
150 const auto &
id = options.get_id();
152 std::ostringstream oss{
"qos_overrides.", std::ios::ate};
153 oss << topic_name <<
"." << EntityQosParametersTraits::entity_type();
158 param_prefix = oss.str();
160 std::string param_description_suffix;
162 std::ostringstream oss{
"} for ", std::ios::ate};
163 oss << EntityQosParametersTraits::entity_type() <<
" {" << topic_name <<
"}";
165 oss <<
" with id {" <<
id <<
"}";
167 param_description_suffix = oss.str();
170 for (
auto policy : EntityQosParametersTraits::allowed_policies()) {
172 std::count(options.get_policy_kinds().begin(), options.get_policy_kinds().end(), policy))
174 std::ostringstream param_name{param_prefix, std::ios::ate};
175 param_name << qos_policy_kind_to_cstr(policy);
176 std::ostringstream param_desciption{
"qos policy {", std::ios::ate};
177 param_desciption << qos_policy_kind_to_cstr(policy) << param_description_suffix;
178 rcl_interfaces::msg::ParameterDescriptor descriptor{};
179 descriptor.description = param_desciption.str();
180 descriptor.read_only =
true;
181 auto value = declare_parameter_or_get(
182 parameters_interface, param_name.str(),
183 get_default_qos_param_value(policy, qos), descriptor);
184 ::rclcpp::detail::apply_qos_override(policy, value, qos);
187 const auto & validation_callback = options.get_validation_callback();
188 if (validation_callback) {
189 auto result = validation_callback(qos);
190 if (!result.successful) {
192 "validation callback failed: " + result.reason};
200 template<
typename NodeT,
typename EntityQosParametersTraits>
202 !(rclcpp::node_interfaces::has_node_parameters_interface<
203 decltype(std::declval<
typename rcpputils::remove_pointer<NodeT>::type>())>::value ||
204 std::is_same<typename std::decay_t<NodeT>,
205 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value),
207 declare_qos_parameters(
208 const ::rclcpp::QosOverridingOptions & options,
211 const ::rclcpp::QoS & default_qos,
212 EntityQosParametersTraits)
214 if (options.get_policy_kinds().size()) {
215 std::runtime_error exc{
216 "passed non-default qos overriding options without providing a parameters interface"};
225 #define RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING( \
226 kind_lower, kind_upper, parameter_value, rclcpp_qos) \
228 auto policy_string = (parameter_value).get<std::string>(); \
229 auto policy_value = rmw_qos_ ## kind_lower ## _policy_from_str(policy_string.c_str()); \
230 if (RMW_QOS_POLICY_ ## kind_upper ## _UNKNOWN == policy_value) { \
231 throw std::invalid_argument{"unknown QoS policy " #kind_lower " value: " + policy_string}; \
233 ((rclcpp_qos).kind_lower)(policy_value); \
242 case QosPolicyKind::AvoidRosNamespaceConventions:
245 case QosPolicyKind::Deadline:
248 case QosPolicyKind::Durability:
249 RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
250 durability, DURABILITY, value, qos);
252 case QosPolicyKind::History:
253 RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
254 history, HISTORY, value, qos);
256 case QosPolicyKind::Depth:
259 case QosPolicyKind::Lifespan:
262 case QosPolicyKind::Liveliness:
263 RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
264 liveliness, LIVELINESS, value, qos);
266 case QosPolicyKind::LivelinessLeaseDuration:
269 case QosPolicyKind::Reliability:
270 RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING(
271 reliability, RELIABILITY, value, qos);
274 throw std::invalid_argument{
"unknown QosPolicyKind"};
281 rmw_duration_to_int64_t(rmw_time_t rmw_duration)
283 return ::rclcpp::Duration(
284 static_cast<int32_t
>(rmw_duration.sec),
285 static_cast<uint32_t
>(rmw_duration.nsec)
292 check_if_stringified_policy_is_null(
const char * policy_value_stringified, QosPolicyKind kind)
294 if (!policy_value_stringified) {
295 std::ostringstream oss{
"unknown value for policy kind {", std::ios::ate};
297 throw std::invalid_argument{oss.str()};
299 return policy_value_stringified;
303 ::rclcpp::ParameterValue
304 get_default_qos_param_value(rclcpp::QosPolicyKind kind,
const rclcpp::QoS & qos)
309 case QosPolicyKind::AvoidRosNamespaceConventions:
310 return ParameterValue(rmw_qos.avoid_ros_namespace_conventions);
311 case QosPolicyKind::Deadline:
312 return ParameterValue(rmw_duration_to_int64_t(rmw_qos.deadline));
313 case QosPolicyKind::Durability:
314 return ParameterValue(
315 check_if_stringified_policy_is_null(
316 rmw_qos_durability_policy_to_str(rmw_qos.durability), kind));
317 case QosPolicyKind::History:
318 return ParameterValue(
319 check_if_stringified_policy_is_null(
320 rmw_qos_history_policy_to_str(rmw_qos.history), kind));
321 case QosPolicyKind::Depth:
322 return ParameterValue(
static_cast<int64_t
>(rmw_qos.depth));
323 case QosPolicyKind::Lifespan:
324 return ParameterValue(rmw_duration_to_int64_t(rmw_qos.lifespan));
325 case QosPolicyKind::Liveliness:
326 return ParameterValue(
327 check_if_stringified_policy_is_null(
328 rmw_qos_liveliness_policy_to_str(rmw_qos.liveliness), kind));
329 case QosPolicyKind::LivelinessLeaseDuration:
330 return ParameterValue(rmw_duration_to_int64_t(rmw_qos.liveliness_lease_duration));
331 case QosPolicyKind::Reliability:
332 return ParameterValue(
333 check_if_stringified_policy_is_null(
334 rmw_qos_reliability_policy_to_str(rmw_qos.reliability), kind));
336 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.
virtual RCLCPP_PUBLIC void enable_parameter_modification()=0
Enable parameter modification recursively during parameter callbacks.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.