Skip to content

Commit

Permalink
Fixed test qos rmw zenoh (#2639)
Browse files Browse the repository at this point in the history
* 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]>
  • Loading branch information
ahcorde and Yadunund authored Oct 2, 2024
1 parent 2813045 commit 1a0092a
Showing 1 changed file with 17 additions and 4 deletions.
21 changes: 17 additions & 4 deletions rclcpp/test/rclcpp/test_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <string>

#include "rclcpp/qos.hpp"
#include "rmw/rmw.h"

#include "rmw/types.h"

Expand Down Expand Up @@ -241,21 +242,33 @@ 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
{
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());
}
}
}

0 comments on commit 1a0092a

Please sign in to comment.