|
17 | 17 | #include <string>
|
18 | 18 |
|
19 | 19 | #include "rclcpp/qos.hpp"
|
| 20 | +#include "rmw/rmw.h" |
20 | 21 |
|
21 | 22 | #include "rmw/types.h"
|
22 | 23 |
|
@@ -241,21 +242,33 @@ TEST(TestQoS, qos_check_compatible)
|
241 | 242 | // TODO(jacobperron): programmatically check if current RMW is one of the officially
|
242 | 243 | // supported DDS middlewares before running the following tests
|
243 | 244 |
|
| 245 | + // If the RMW implementation is rmw_zenoh_cpp, we do not expect any QoS incompatibilities. |
| 246 | + std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier()); |
244 | 247 | // Incompatible
|
245 | 248 | {
|
246 | 249 | rclcpp::QoS pub_qos = rclcpp::QoS(1).best_effort();
|
247 | 250 | rclcpp::QoS sub_qos = rclcpp::QoS(1).reliable();
|
248 | 251 | rclcpp::QoSCheckCompatibleResult ret = rclcpp::qos_check_compatible(pub_qos, sub_qos);
|
249 |
| - EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Error); |
250 |
| - EXPECT_FALSE(ret.reason.empty()); |
| 252 | + if (rmw_implementation_str == "rmw_zenoh_cpp") { |
| 253 | + EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Ok); |
| 254 | + EXPECT_TRUE(ret.reason.empty()); |
| 255 | + } else { |
| 256 | + EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Error); |
| 257 | + EXPECT_FALSE(ret.reason.empty()); |
| 258 | + } |
251 | 259 | }
|
252 | 260 |
|
253 | 261 | // Warn of possible incompatibility
|
254 | 262 | {
|
255 | 263 | rclcpp::SystemDefaultsQoS pub_qos;
|
256 | 264 | rclcpp::QoS sub_qos = rclcpp::QoS(1).reliable();
|
257 | 265 | rclcpp::QoSCheckCompatibleResult ret = rclcpp::qos_check_compatible(pub_qos, sub_qos);
|
258 |
| - EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Warning); |
259 |
| - EXPECT_FALSE(ret.reason.empty()); |
| 266 | + if (rmw_implementation_str == "rmw_zenoh_cpp") { |
| 267 | + EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Ok); |
| 268 | + EXPECT_TRUE(ret.reason.empty()); |
| 269 | + } else { |
| 270 | + EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Warning); |
| 271 | + EXPECT_FALSE(ret.reason.empty()); |
| 272 | + } |
260 | 273 | }
|
261 | 274 | }
|
0 commit comments