15 #include "rclcpp/qos.hpp"
19 #include "rclcpp/logging.hpp"
21 #include "rmw/error_handling.h"
22 #include "rmw/types.h"
23 #include "rmw/qos_profiles.h"
28 std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind)
30 switch (policy_kind) {
31 case RMW_QOS_POLICY_DURABILITY:
32 return "DURABILITY_QOS_POLICY";
33 case RMW_QOS_POLICY_DEADLINE:
34 return "DEADLINE_QOS_POLICY";
35 case RMW_QOS_POLICY_LIVELINESS:
36 return "LIVELINESS_QOS_POLICY";
37 case RMW_QOS_POLICY_RELIABILITY:
38 return "RELIABILITY_QOS_POLICY";
39 case RMW_QOS_POLICY_HISTORY:
40 return "HISTORY_QOS_POLICY";
41 case RMW_QOS_POLICY_LIFESPAN:
42 return "LIFESPAN_QOS_POLICY";
44 return "INVALID_QOS_POLICY";
49 rmw_qos_history_policy_t history_policy_arg,
size_t depth_arg,
50 bool print_depth_warning)
51 : history_policy(history_policy_arg), depth(depth_arg)
53 if (history_policy == RMW_QOS_POLICY_HISTORY_KEEP_LAST && depth == 0 && print_depth_warning) {
57 "A zero depth with KEEP_LAST doesn't make sense; no data could be stored. "
58 "This will be interpreted as SYSTEM_DEFAULT");
65 switch (rmw_qos.history) {
66 case RMW_QOS_POLICY_HISTORY_KEEP_ALL:
68 case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT:
69 return KeepLast(rmw_qos.depth,
false);
70 case RMW_QOS_POLICY_HISTORY_KEEP_LAST:
71 case RMW_QOS_POLICY_HISTORY_UNKNOWN:
74 throw std::invalid_argument(
75 "Invalid history policy enum value passed to QoSInitialization::from_rmw");
83 KeepLast::KeepLast(
size_t depth,
bool print_depth_warning)
84 : QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth, print_depth_warning)
90 const rmw_qos_profile_t & initial_profile)
91 : rmw_qos_profile_(initial_profile)
93 rmw_qos_profile_.history = qos_initialization.history_policy;
94 rmw_qos_profile_.depth = qos_initialization.depth;
104 return rmw_qos_profile_;
107 const rmw_qos_profile_t &
110 return rmw_qos_profile_;
116 rmw_qos_profile_.history =
history;
123 rmw_qos_profile_.history =
static_cast<rmw_qos_history_policy_t
>(
history);
134 "A zero depth with KEEP_LAST doesn't make sense; no data could be stored."
135 "This will be interpreted as SYSTEM_DEFAULT");
138 rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
139 rmw_qos_profile_.depth =
depth;
146 rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
147 rmw_qos_profile_.depth = 0;
161 rmw_qos_profile_.reliability =
static_cast<rmw_qos_reliability_policy_t
>(
reliability);
168 return this->
reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE);
174 return this->
reliability(RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT);
180 return this->
reliability(RMW_QOS_POLICY_RELIABILITY_BEST_AVAILABLE);
193 rmw_qos_profile_.durability =
static_cast<rmw_qos_durability_policy_t
>(
durability);
200 return this->
durability(RMW_QOS_POLICY_DURABILITY_VOLATILE);
206 return this->
durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
212 return this->
durability(RMW_QOS_POLICY_DURABILITY_BEST_AVAILABLE);
218 rmw_qos_profile_.deadline =
deadline;
231 rmw_qos_profile_.lifespan =
lifespan;
251 rmw_qos_profile_.liveliness =
static_cast<rmw_qos_liveliness_policy_t
>(
liveliness);
279 return static_cast<HistoryPolicy
>(rmw_qos_profile_.history);
288 return static_cast<ReliabilityPolicy
>(rmw_qos_profile_.reliability);
294 return static_cast<DurabilityPolicy
>(rmw_qos_profile_.durability);
298 QoS::deadline()
const {
return Duration::from_rmw_time(rmw_qos_profile_.deadline);}
301 QoS::lifespan()
const {
return Duration::from_rmw_time(rmw_qos_profile_.lifespan);}
306 return static_cast<LivelinessPolicy
>(rmw_qos_profile_.liveliness);
312 return Duration::from_rmw_time(rmw_qos_profile_.liveliness_lease_duration);
318 return rmw_qos_profile_.avoid_ros_namespace_conventions;
324 bool operator==(
const rmw_time_t & left,
const rmw_time_t & right)
326 return left.sec == right.sec && left.nsec == right.nsec;
334 return pl.history == pr.history &&
335 pl.depth == pr.depth &&
336 pl.reliability == pr.reliability &&
337 pl.durability == pr.durability &&
338 pl.deadline == pr.deadline &&
339 pl.lifespan == pr.lifespan &&
340 pl.liveliness == pr.liveliness &&
341 pl.liveliness_lease_duration == pr.liveliness_lease_duration &&
342 pl.avoid_ros_namespace_conventions == pr.avoid_ros_namespace_conventions;
345 bool operator!=(
const QoS & left,
const QoS & right)
347 return !(left == right);
350 QoSCheckCompatibleResult
353 rmw_qos_compatibility_type_t compatible;
354 const size_t reason_size = 2048u;
355 char reason_c_str[reason_size] =
"";
356 rmw_ret_t ret = rmw_qos_profile_check_compatible(
362 if (RMW_RET_OK != ret) {
363 std::string error_str(rmw_get_error_string().str);
369 result.
reason = std::string(reason_c_str);
371 switch (compatible) {
372 case RMW_QOS_COMPATIBILITY_OK:
375 case RMW_QOS_COMPATIBILITY_WARNING:
378 case RMW_QOS_COMPATIBILITY_ERROR:
383 "Unexpected compatibility value returned by rmw '" + std::to_string(compatible) +
389 ClockQoS::ClockQoS(
const QoSInitialization & qos_initialization)
392 : QoS(qos_initialization, rmw_qos_profile_sensor_data)
395 SensorDataQoS::SensorDataQoS(
const QoSInitialization & qos_initialization)
396 : QoS(qos_initialization, rmw_qos_profile_sensor_data)
399 ParametersQoS::ParametersQoS(
const QoSInitialization & qos_initialization)
400 : QoS(qos_initialization, rmw_qos_profile_parameters)
403 ServicesQoS::ServicesQoS(
const QoSInitialization & qos_initialization)
404 : QoS(qos_initialization, rmw_qos_profile_services_default)
407 ParameterEventsQoS::ParameterEventsQoS(
const QoSInitialization & qos_initialization)
408 : QoS(qos_initialization, rmw_qos_profile_parameter_events)
411 RosoutQoS::RosoutQoS(
const QoSInitialization & rosout_initialization)
412 : QoS(rosout_initialization, rcl_qos_profile_rosout_default)
415 SystemDefaultsQoS::SystemDefaultsQoS(
const QoSInitialization & qos_initialization)
416 : QoS(qos_initialization, rmw_qos_profile_system_default)
419 BestAvailableQoS::BestAvailableQoS(
const QoSInitialization & qos_initialization)
420 : QoS(qos_initialization, rmw_qos_profile_best_available)
rmw_time_t to_rmw_time() const
Convert Duration into rmw_time_t.
Encapsulation of Quality of Service settings.
QoS & durability_best_available()
Set the durability setting to best available.
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 & reliability_best_available()
Set the reliability setting to best available.
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.
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.
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
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, bool print_depth_warning=true)
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.