Quality of Service (QoS)
12/8/2020: Edit to remind about a key concept from the docs with respect to QoS.
A connection between a publisher and a subscription is only made if the pair has compatible QoS profiles.
ROS2 allows for granular management of the quality of service (QoS) by exposing the QoS profile. The profile is a struct
defined as follows in types.h
.
/// ROS MiddleWare quality of service profile. *
typedef struct RMW_PUBLIC_TYPE rmw_qos_profile_t
{
enum rmw_qos_history_policy_t history;
size_t depth;
enum rmw_qos_reliability_policy_t reliability;
enum rmw_qos_durability_policy_t durability;
struct rmw_time_t deadline;
struct rmw_time_t lifespan;
enum rmw_qos_liveliness_policy_t liveliness;
struct rmw_time_t liveliness_lease_duration;
bool avoid_ros_namespace_conventions;
} rmw_qos_profile_t;
Modified for readability
If the QoS settings are not modified the default settings are applied. For example, the QoS defaults settings for publishers and subscribers are specified by the profile rmw_qos_profile_default
.
static const rmw_qos_profile_t rmw_qos_profile_default =
{
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
10,
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
RMW_QOS_POLICY_DURABILITY_VOLATILE,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
false
};
This profile isn’t particularly fitting for sensor data where in most use cases the priority is placed on receiving data in a timely fashion as opposed to receiving all the data. Reliability can be sacrificed. Default profiles are available, e.g. rmw_qos_profile_sensor_data
.
Example use cases:
//example1.hpp
rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
//example1.cpp
auto qos = rclcpp::QoS(
rclcpp::QoSInitialization(
qos_profile.history,
qos_profile.depth
),
qos_profile);
pub_ = create_publisher<sensor_msgs::msg::Image>(topic_, qos);
//example2.hpp
rclcpp::QoS qos_;
//example2.cpp
RtspStreamer::RtspStreamer(const rclcpp::NodeOptions & options)
: Node("rtsp_streamer", options),
qos_(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_sensor_data))
{
...
}
A more complete example can be found in the cam2image demo.
References
- https://index.ros.org/doc/ros2/Concepts/About-Quality-of-Service-Settings/
- http://design.ros2.org/articles/qos.html1
- https://github.com/ros2/demos/blob/master/image_tools/src/cam2image.cpp
- https://github.com/ros2/rmw/blob/master/rmw/include/rmw/qos_profiles.h
- https://github.com/ros2/rmw/blob/master/rmw/include/rmw/types.h
- https://answers.ros.org/question/298594/how-does-ros2-select-the-default-qos-profile/
- https://docs.ros2.org/latest/api/rclcpp/qos_8hpp_source.html