15 #ifndef RCLCPP__QOS_HPP_
16 #define RCLCPP__QOS_HPP_
20 #include "rclcpp/duration.hpp"
21 #include "rclcpp/exceptions.hpp"
22 #include "rclcpp/visibility_control.hpp"
24 #include "rmw/incompatible_qos_events_statuses.h"
25 #include "rmw/qos_profiles.h"
26 #include "rmw/types.h"
32 std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind);
34 enum class HistoryPolicy
36 KeepLast = RMW_QOS_POLICY_HISTORY_KEEP_LAST,
37 KeepAll = RMW_QOS_POLICY_HISTORY_KEEP_ALL,
38 SystemDefault = RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT,
39 Unknown = RMW_QOS_POLICY_HISTORY_UNKNOWN,
42 enum class ReliabilityPolicy
44 BestEffort = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT,
45 Reliable = RMW_QOS_POLICY_RELIABILITY_RELIABLE,
46 SystemDefault = RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT,
47 BestAvailable = RMW_QOS_POLICY_RELIABILITY_BEST_AVAILABLE,
48 Unknown = RMW_QOS_POLICY_RELIABILITY_UNKNOWN,
51 enum class DurabilityPolicy
53 Volatile = RMW_QOS_POLICY_DURABILITY_VOLATILE,
54 TransientLocal = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
55 SystemDefault = RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT,
56 BestAvailable = RMW_QOS_POLICY_DURABILITY_BEST_AVAILABLE,
57 Unknown = RMW_QOS_POLICY_DURABILITY_UNKNOWN,
60 enum class LivelinessPolicy
62 Automatic = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
63 ManualByTopic = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC,
64 SystemDefault = RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
65 BestAvailable = RMW_QOS_POLICY_LIVELINESS_BEST_AVAILABLE,
66 Unknown = RMW_QOS_POLICY_LIVELINESS_UNKNOWN,
69 enum class QoSCompatibility
71 Ok = RMW_QOS_COMPATIBILITY_OK,
72 Warning = RMW_QOS_COMPATIBILITY_WARNING,
73 Error = RMW_QOS_COMPATIBILITY_ERROR,
79 rmw_qos_history_policy_t history_policy;
84 rmw_qos_history_policy_t history_policy_arg,
size_t depth_arg,
85 bool print_depth_warning =
true);
90 from_rmw(
const rmw_qos_profile_t & rmw_qos);
102 explicit KeepLast(
size_t depth,
bool print_depth_warning =
true);
135 const rmw_qos_profile_t & initial_profile = rmw_qos_profile_default);
146 QoS(
size_t history_depth);
150 get_rmw_qos_profile();
153 const rmw_qos_profile_t &
154 get_rmw_qos_profile()
const;
158 history(HistoryPolicy history);
162 history(rmw_qos_history_policy_t history);
166 keep_last(
size_t depth);
174 reliability(rmw_qos_reliability_policy_t reliability);
178 reliability(ReliabilityPolicy reliability);
190 reliability_best_available();
194 durability(rmw_qos_durability_policy_t durability);
198 durability(DurabilityPolicy durability);
205 durability_volatile();
213 durability_best_available();
217 deadline(rmw_time_t deadline);
225 lifespan(rmw_time_t lifespan);
233 liveliness(rmw_qos_liveliness_policy_t liveliness);
237 liveliness(LivelinessPolicy liveliness);
241 liveliness_lease_duration(rmw_time_t liveliness_lease_duration);
245 liveliness_lease_duration(
const rclcpp::Duration & liveliness_lease_duration);
249 avoid_ros_namespace_conventions(
bool avoid_ros_namespace_conventions);
281 liveliness_lease_duration()
const;
285 avoid_ros_namespace_conventions()
const;
288 rmw_qos_profile_t rmw_qos_profile_;
Encapsulation of Quality of Service settings.
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.
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.