Skip to content

Commit 1a0092a

Browse files
ahcordeYadunund
andauthored
Fixed test qos rmw zenoh (#2639)
* Fixed test qos rmw zenoh Signed-off-by: Alejandro Hernández Cordero <[email protected]> * Update rclcpp/test/rclcpp/test_qos.cpp Co-authored-by: Yadu <[email protected]> Signed-off-by: Alejandro Hernández Cordero <[email protected]> --------- Signed-off-by: Alejandro Hernández Cordero <[email protected]> Co-authored-by: Yadu <[email protected]>
1 parent 2813045 commit 1a0092a

File tree

1 file changed

+17
-4
lines changed

1 file changed

+17
-4
lines changed

rclcpp/test/rclcpp/test_qos.cpp

+17-4
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <string>
1818

1919
#include "rclcpp/qos.hpp"
20+
#include "rmw/rmw.h"
2021

2122
#include "rmw/types.h"
2223

@@ -241,21 +242,33 @@ TEST(TestQoS, qos_check_compatible)
241242
// TODO(jacobperron): programmatically check if current RMW is one of the officially
242243
// supported DDS middlewares before running the following tests
243244

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());
244247
// Incompatible
245248
{
246249
rclcpp::QoS pub_qos = rclcpp::QoS(1).best_effort();
247250
rclcpp::QoS sub_qos = rclcpp::QoS(1).reliable();
248251
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+
}
251259
}
252260

253261
// Warn of possible incompatibility
254262
{
255263
rclcpp::SystemDefaultsQoS pub_qos;
256264
rclcpp::QoS sub_qos = rclcpp::QoS(1).reliable();
257265
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+
}
260273
}
261274
}

0 commit comments

Comments
 (0)