Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Skip some tests in test_qos_event and run others with event types supported by rmw_zenoh #2626

Merged
merged 11 commits into from
Sep 30, 2024
107 changes: 81 additions & 26 deletions rclcpp/test/rclcpp/test_qos_event.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,11 @@ constexpr char TestQosEvent::topic_name[];
*/
TEST_F(TestQosEvent, test_publisher_constructor)
{
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
Yadunund marked this conversation as resolved.
Show resolved Hide resolved
if (rmw_implementation_str == "rmw_zenoh_cpp") {
GTEST_SKIP();
}

Yadunund marked this conversation as resolved.
Show resolved Hide resolved
rclcpp::PublisherOptions options;

// options arg with no callbacks
Expand Down Expand Up @@ -112,34 +117,42 @@ TEST_F(TestQosEvent, test_publisher_constructor)
/*
Testing construction of a subscriptions with QoS event callback functions.
*/
TEST_F(TestQosEvent, test_subscription_constructor)
TEST_F(TestQosEvent, test_subscription_constructor_with_event_callbacks)
{
// While rmw_zenoh does not support Deadline/LivelinessChanged events,
// it does support IncompatibleQoS
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
Yadunund marked this conversation as resolved.
Show resolved Hide resolved

rclcpp::SubscriptionOptions options;

// options arg with no callbacks
auto subscription = node->create_subscription<test_msgs::msg::Empty>(
topic_name, 10, message_callback, options);

// options arg with one of the callbacks
options.event_callbacks.deadline_callback =
[node = node.get()](rclcpp::QOSDeadlineRequestedInfo & event) {
RCLCPP_INFO(
node->get_logger(),
"Requested deadline missed - total %d (delta %d)",
event.total_count, event.total_count_change);
};
if (rmw_implementation_str != "rmw_zenoh_cpp") {
// options arg with one of the callbacks
options.event_callbacks.deadline_callback =
[node = node.get()](rclcpp::QOSDeadlineRequestedInfo & event) {
RCLCPP_INFO(
node->get_logger(),
"Requested deadline missed - total %d (delta %d)",
event.total_count, event.total_count_change);
};
}
subscription = node->create_subscription<test_msgs::msg::Empty>(
topic_name, 10, message_callback, options);

// options arg with two of the callbacks
options.event_callbacks.liveliness_callback =
[node = node.get()](rclcpp::QOSLivelinessChangedInfo & event) {
RCLCPP_INFO(
node->get_logger(),
"Liveliness changed - alive %d (delta %d), not alive %d (delta %d)",
event.alive_count, event.alive_count_change,
event.not_alive_count, event.not_alive_count_change);
};
if (rmw_implementation_str != "rmw_zenoh_cpp") {
Yadunund marked this conversation as resolved.
Show resolved Hide resolved
// options arg with two of the callbacks
options.event_callbacks.liveliness_callback =
[node = node.get()](rclcpp::QOSLivelinessChangedInfo & event) {
RCLCPP_INFO(
node->get_logger(),
"Liveliness changed - alive %d (delta %d), not alive %d (delta %d)",
event.alive_count, event.alive_count_change,
event.not_alive_count, event.not_alive_count_change);
};
}
subscription = node->create_subscription<test_msgs::msg::Empty>(
topic_name, 10, message_callback, options);

Expand Down Expand Up @@ -209,19 +222,30 @@ TEST_F(TestQosEvent, test_default_incompatible_qos_callbacks)
const auto timeout = std::chrono::seconds(10);
ex.spin_until_future_complete(log_msgs_future, timeout);

EXPECT_EQ(
"New subscription discovered on topic '/ns/test_topic', requesting incompatible QoS. "
"No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY",
pub_log_msg);
EXPECT_EQ(
"New publisher discovered on topic '/ns/test_topic', offering incompatible QoS. "
"No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY",
sub_log_msg);
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
if (rmw_implementation_str == "rmw_zenoh_cpp") {
EXPECT_EQ(rclcpp::QoSCompatibility::Ok,
qos_check_compatible(qos_profile_publisher, qos_profile_subscription).compatibility);
} else {
EXPECT_EQ(
"New subscription discovered on topic '/ns/test_topic', requesting incompatible QoS. "
"No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY",
pub_log_msg);
EXPECT_EQ(
"New publisher discovered on topic '/ns/test_topic', offering incompatible QoS. "
"No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY",
sub_log_msg);
}

rcutils_logging_set_output_handler(original_output_handler);
}

TEST_F(TestQosEvent, construct_destruct_rcl_error) {
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
Yadunund marked this conversation as resolved.
Show resolved Hide resolved
if (rmw_implementation_str == "rmw_zenoh_cpp") {
GTEST_SKIP();
}

auto publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);
auto rcl_handle = publisher->get_publisher_handle();
ASSERT_NE(nullptr, rcl_handle);
Expand Down Expand Up @@ -265,6 +289,10 @@ TEST_F(TestQosEvent, construct_destruct_rcl_error) {
}

TEST_F(TestQosEvent, execute) {
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
if (rmw_implementation_str == "rmw_zenoh_cpp") {
GTEST_SKIP();
}
auto publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);
auto rcl_handle = publisher->get_publisher_handle();

Expand All @@ -291,6 +319,11 @@ TEST_F(TestQosEvent, execute) {
}

TEST_F(TestQosEvent, add_to_wait_set) {
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
if (rmw_implementation_str == "rmw_zenoh_cpp") {
GTEST_SKIP();
}

auto publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);
auto rcl_handle = publisher->get_publisher_handle();

Expand Down Expand Up @@ -319,6 +352,11 @@ TEST_F(TestQosEvent, add_to_wait_set) {

TEST_F(TestQosEvent, test_on_new_event_callback)
{
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
if (rmw_implementation_str == "rmw_zenoh_cpp") {
GTEST_SKIP();
}

auto offered_deadline = rclcpp::Duration(std::chrono::milliseconds(1));
auto requested_deadline = rclcpp::Duration(std::chrono::milliseconds(2));

Expand Down Expand Up @@ -360,6 +398,11 @@ TEST_F(TestQosEvent, test_on_new_event_callback)

TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
{
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
if (rmw_implementation_str == "rmw_zenoh_cpp") {
GTEST_SKIP();
}

auto pub = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);
auto sub = node->create_subscription<test_msgs::msg::Empty>(topic_name, 10, message_callback);
auto dummy_cb = [](size_t count_events) {(void)count_events;};
Expand Down Expand Up @@ -434,6 +477,10 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)

TEST_F(TestQosEvent, test_pub_matched_event_by_set_event_callback)
{
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
if (rmw_implementation_str == "rmw_zenoh_cpp") {
GTEST_SKIP();
}
std::atomic_size_t matched_count = 0;

rclcpp::PublisherOptions pub_options;
Expand Down Expand Up @@ -523,6 +570,10 @@ TEST_F(TestQosEvent, test_sub_matched_event_by_set_event_callback)

TEST_F(TestQosEvent, test_pub_matched_event_by_option_event_callback)
{
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
Yadunund marked this conversation as resolved.
Show resolved Hide resolved
if (rmw_implementation_str == "rmw_zenoh_cpp") {
GTEST_SKIP();
}
rmw_matched_status_t matched_expected_result;
std::promise<void> prom;

Expand Down Expand Up @@ -566,6 +617,10 @@ TEST_F(TestQosEvent, test_pub_matched_event_by_option_event_callback)

TEST_F(TestQosEvent, test_sub_matched_event_by_option_event_callback)
{
std::string rmw_implementation_str = std::string(rmw_get_implementation_identifier());
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

matched events should definitely work else there is a bug in rmw_zenoh.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

failing here too

Expected equality of these values:
  s.total_count
    Which is: 7
  matched_expected_result.total_count
    Which is: 1

/home/ahcorde/ros2_rolling/src/ros2/rclcpp/rclcpp/test/rclcpp/test_qos_event.cpp:620: Failure
Expected equality of these values:
  s.total_count_change
    Which is: 2
  matched_expected_result.total_count_change
    Which is: 1

/home/ahcorde/ros2_rolling/src/ros2/rclcpp/rclcpp/test/rclcpp/test_qos_event.cpp:621: Failure
Expected equality of these values:
  s.current_count
    Which is: 3
  matched_expected_result.current_count
    Which is: 1

/home/ahcorde/ros2_rolling/src/ros2/rclcpp/rclcpp/test/rclcpp/test_qos_event.cpp:619: Failure
Expected equality of these values:
  s.total_count
    Which is: 8
  matched_expected_result.total_count
    Which is: 1

/home/ahcorde/ros2_rolling/src/ros2/rclcpp/rclcpp/test/rclcpp/test_qos_event.cpp:620: Failure
Expected equality of these values:
  s.total_count_change
    Which is: 1
  matched_expected_result.total_count_change
    Which is: 0

/home/ahcorde/ros2_rolling/src/ros2/rclcpp/rclcpp/test/rclcpp/test_qos_event.cpp:621: Failure
Expected equality of these values:
  s.current_count
    Which is: 2
  matched_expected_result.current_count
    Which is: 0

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So this relates to what I mentioned above where we should update the test similar to 4) in ros2/rcl#1164. Basically more QoS combinations are compatible in rmw_zenoh so we should set the matched_expected_result.current_count to the output of rmw_qos_profile_check_compatible checks.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There might be some tests that we can fix with your comment, but the subscription counter is wrong, it's only increasing.

If you comment out some tests the numbers are different which somehow don't clean the counters between tests.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks like a bug in rmw_zenoh. I would suggest we don't skip this test and instead have it fail so that we can address it.

We should only skip the tests for functionalities we do not support.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

After looking at the problem closer; the issue is that

  1. rmw_init() is called once in SetUpTestCase() which creates the Zenoh session and initializes the ROS graph.
  2. Each time a new test case runs, we run SetUp() and TearDown() which creates and destroys the node and some publishes and subscriptions. However, since the session is still the same throughout the tests each time a new pub/sub match is found, the same total_count and total_count_change updates. From the sessions's perspective, the total count is indeed valid since it was never shutdown.

In 6c9baba, I moved the rmw_init() command inside SetUp() and the rmw_shutdown() inside TearDown(), the total_count numbers are accurate. With ros2/rmw_zenoh#287 all events tests are passing.

if (rmw_implementation_str == "rmw_zenoh_cpp") {
GTEST_SKIP();
}
rmw_matched_status_t matched_expected_result;

std::promise<void> prom;
Expand Down