diff --git a/rclcpp/test/rclcpp/test_qos.cpp b/rclcpp/test/rclcpp/test_qos.cpp index b2446beed3..eecfaf97a7 100644 --- a/rclcpp/test/rclcpp/test_qos.cpp +++ b/rclcpp/test/rclcpp/test_qos.cpp @@ -17,6 +17,7 @@ #include #include "rclcpp/qos.hpp" +#include "rmw/rmw.h" #include "rmw/types.h" @@ -241,13 +242,20 @@ TEST(TestQoS, qos_check_compatible) // TODO(jacobperron): programmatically check if current RMW is one of the officially // supported DDS middlewares before running the following tests + // If the RMW implementation is rmw_zenoh_cpp, we do not expect any QoS incompatibilities. + std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier()); // Incompatible { rclcpp::QoS pub_qos = rclcpp::QoS(1).best_effort(); rclcpp::QoS sub_qos = rclcpp::QoS(1).reliable(); rclcpp::QoSCheckCompatibleResult ret = rclcpp::qos_check_compatible(pub_qos, sub_qos); - EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Error); - EXPECT_FALSE(ret.reason.empty()); + if (rmw_implementation_str == "rmw_zenoh_cpp") { + EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Ok); + EXPECT_TRUE(ret.reason.empty()); + } else { + EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Error); + EXPECT_FALSE(ret.reason.empty()); + } } // Warn of possible incompatibility @@ -255,7 +263,12 @@ TEST(TestQoS, qos_check_compatible) rclcpp::SystemDefaultsQoS pub_qos; rclcpp::QoS sub_qos = rclcpp::QoS(1).reliable(); rclcpp::QoSCheckCompatibleResult ret = rclcpp::qos_check_compatible(pub_qos, sub_qos); - EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Warning); - EXPECT_FALSE(ret.reason.empty()); + if (rmw_implementation_str == "rmw_zenoh_cpp") { + EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Ok); + EXPECT_TRUE(ret.reason.empty()); + } else { + EXPECT_EQ(ret.compatibility, rclcpp::QoSCompatibility::Warning); + EXPECT_FALSE(ret.reason.empty()); + } } }