15 #include "rclcpp/qos.hpp"
19 #include "rmw/error_handling.h"
20 #include "rmw/types.h"
21 #include "rmw/qos_profiles.h"
26 std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind)
28 switch (policy_kind) {
29 case RMW_QOS_POLICY_DURABILITY:
30 return "DURABILITY_QOS_POLICY";
31 case RMW_QOS_POLICY_DEADLINE:
32 return "DEADLINE_QOS_POLICY";
33 case RMW_QOS_POLICY_LIVELINESS:
34 return "LIVELINESS_QOS_POLICY";
35 case RMW_QOS_POLICY_RELIABILITY:
36 return "RELIABILITY_QOS_POLICY";
37 case RMW_QOS_POLICY_HISTORY:
38 return "HISTORY_QOS_POLICY";
39 case RMW_QOS_POLICY_LIFESPAN:
40 return "LIFESPAN_QOS_POLICY";
42 return "INVALID_QOS_POLICY";
47 : history_policy(history_policy_arg), depth(depth_arg)
53 switch (rmw_qos.history) {
54 case RMW_QOS_POLICY_HISTORY_KEEP_ALL:
56 case RMW_QOS_POLICY_HISTORY_KEEP_LAST:
57 case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT:
58 case RMW_QOS_POLICY_HISTORY_UNKNOWN:
61 throw std::invalid_argument(
62 "Invalid history policy enum value passed to QoSInitialization::from_rmw");
70 KeepLast::KeepLast(
size_t depth)
71 : QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth)
76 const rmw_qos_profile_t & initial_profile)
77 : rmw_qos_profile_(initial_profile)
79 rmw_qos_profile_.history = qos_initialization.history_policy;
80 rmw_qos_profile_.depth = qos_initialization.depth;
90 return rmw_qos_profile_;
93 const rmw_qos_profile_t &
96 return rmw_qos_profile_;
102 rmw_qos_profile_.history =
history;
109 rmw_qos_profile_.history =
static_cast<rmw_qos_history_policy_t
>(
history);
116 rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
117 rmw_qos_profile_.depth =
depth;
124 rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
125 rmw_qos_profile_.depth = 0;
139 rmw_qos_profile_.reliability =
static_cast<rmw_qos_reliability_policy_t
>(
reliability);
146 return this->
reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE);
152 return this->
reliability(RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT);
165 rmw_qos_profile_.durability =
static_cast<rmw_qos_durability_policy_t
>(
durability);
172 return this->
durability(RMW_QOS_POLICY_DURABILITY_VOLATILE);
178 return this->
durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
184 rmw_qos_profile_.deadline =
deadline;
197 rmw_qos_profile_.lifespan =
lifespan;
217 rmw_qos_profile_.liveliness =
static_cast<rmw_qos_liveliness_policy_t
>(
liveliness);
245 return static_cast<HistoryPolicy
>(rmw_qos_profile_.history);
254 return static_cast<ReliabilityPolicy
>(rmw_qos_profile_.reliability);
260 return static_cast<DurabilityPolicy
>(rmw_qos_profile_.durability);
264 QoS::deadline()
const {
return Duration::from_rmw_time(rmw_qos_profile_.deadline);}
267 QoS::lifespan()
const {
return Duration::from_rmw_time(rmw_qos_profile_.lifespan);}
272 return static_cast<LivelinessPolicy
>(rmw_qos_profile_.liveliness);
278 return Duration::from_rmw_time(rmw_qos_profile_.liveliness_lease_duration);
284 return rmw_qos_profile_.avoid_ros_namespace_conventions;
290 bool operator==(
const rmw_time_t & left,
const rmw_time_t & right)
292 return left.sec == right.sec && left.nsec == right.nsec;
300 return pl.history == pr.history &&
301 pl.depth == pr.depth &&
302 pl.reliability == pr.reliability &&
303 pl.durability == pr.durability &&
304 pl.deadline == pr.deadline &&
305 pl.lifespan == pr.lifespan &&
306 pl.liveliness == pr.liveliness &&
307 pl.liveliness_lease_duration == pr.liveliness_lease_duration &&
308 pl.avoid_ros_namespace_conventions == pr.avoid_ros_namespace_conventions;
311 bool operator!=(
const QoS & left,
const QoS & right)
313 return !(left == right);
316 QoSCheckCompatibleResult
319 rmw_qos_compatibility_type_t compatible;
320 const size_t reason_size = 2048u;
321 char reason_c_str[reason_size] =
"";
322 rmw_ret_t ret = rmw_qos_profile_check_compatible(
328 if (RMW_RET_OK != ret) {
329 std::string error_str(rmw_get_error_string().str);
335 result.
reason = std::string(reason_c_str);
337 switch (compatible) {
338 case RMW_QOS_COMPATIBILITY_OK:
341 case RMW_QOS_COMPATIBILITY_WARNING:
344 case RMW_QOS_COMPATIBILITY_ERROR:
349 "Unexpected compatibility value returned by rmw '" + std::to_string(compatible) +
355 ClockQoS::ClockQoS(
const QoSInitialization & qos_initialization)
358 : QoS(qos_initialization, rmw_qos_profile_sensor_data)
361 SensorDataQoS::SensorDataQoS(
const QoSInitialization & qos_initialization)
362 : QoS(qos_initialization, rmw_qos_profile_sensor_data)
365 ParametersQoS::ParametersQoS(
const QoSInitialization & qos_initialization)
366 : QoS(qos_initialization, rmw_qos_profile_parameters)
369 ServicesQoS::ServicesQoS(
const QoSInitialization & qos_initialization)
370 : QoS(qos_initialization, rmw_qos_profile_services_default)
373 ParameterEventsQoS::ParameterEventsQoS(
const QoSInitialization & qos_initialization)
374 : QoS(qos_initialization, rmw_qos_profile_parameter_events)
377 RosoutQoS::RosoutQoS(
const QoSInitialization & rosout_initialization)
378 : QoS(rosout_initialization, rcl_qos_profile_rosout_default)
381 SystemDefaultsQoS::SystemDefaultsQoS(
const QoSInitialization & qos_initialization)
382 : QoS(qos_initialization, rmw_qos_profile_system_default)
rmw_time_t to_rmw_time() const
Convert Duration into rmw_time_t.
Encapsulation of Quality of Service settings.
QoS & best_effort()
Set the reliability setting to best effort.
bool avoid_ros_namespace_conventions() const
Get the avoid ros namespace convention setting.
QoS & reliable()
Set the reliability setting to reliable.
QoS & keep_all()
Set the history to keep all.
rclcpp::Duration deadline() const
Get the deadline duration setting.
DurabilityPolicy durability() const
Get the durability policy.
rclcpp::Duration lifespan() const
Get the lifespan duration setting.
QoS & durability_volatile()
Set the durability setting to volatile.
ReliabilityPolicy reliability() const
Get the reliability policy.
LivelinessPolicy liveliness() const
Get the liveliness policy.
HistoryPolicy history() const
Get the history qos policy.
QoS(const QoSInitialization &qos_initialization, const rmw_qos_profile_t &initial_profile=rmw_qos_profile_default)
Create a QoS by specifying only the history policy and history depth.
QoS & transient_local()
Set the durability setting to transient local.
rmw_qos_profile_t & get_rmw_qos_profile()
Return the rmw qos profile.
size_t depth() const
Get the history depth.
rclcpp::Duration liveliness_lease_duration() const
Get the liveliness lease duration setting.
QoS & keep_last(size_t depth)
Set the history to keep last.
QoS & liveliness_lease_duration(const rclcpp::Duration &liveliness_lease_duration)
Set the liveliness_lease_duration setting, rclcpp::Duration.
Thrown if a QoS compatibility check fails.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC QoSCheckCompatibleResult qos_check_compatible(const QoS &publisher_qos, const QoS &subscription_qos)
Check if two QoS profiles are compatible.
RCLCPP_PUBLIC bool operator==(const NetworkFlowEndpoint &left, const NetworkFlowEndpoint &right)
Check if two NetworkFlowEndpoint instances are equal.
RCLCPP_PUBLIC bool operator!=(const NetworkFlowEndpoint &left, const NetworkFlowEndpoint &right)
Check if two NetworkFlowEndpoint instances are not equal.
Use to initialize the QoS with the keep_all history setting.
Use to initialize the QoS with the keep_last history setting and the given depth.
Result type for checking QoS compatibility.
QoSCompatibility compatibility
Compatibility result.
std::string reason
Reason for a (possible) incompatibility.
QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg)
Constructor which takes both a history policy and a depth (even if it would be unused).
static QoSInitialization from_rmw(const rmw_qos_profile_t &rmw_qos)
Create a QoSInitialization from an existing rmw_qos_profile_t, using its history and depth.