Skip to content

Commit

Permalink
Fixed test_events_executors in zenoh (#2643)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Oct 17, 2024
1 parent 0be8aa0 commit 4567b6e
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 9 deletions.
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -555,7 +555,7 @@ if(TARGET test_executor_notify_waitable)
target_link_libraries(test_executor_notify_waitable ${PROJECT_NAME} mimick rcpputils::rcpputils)
endif()

ament_add_gtest(test_events_executor executors/test_events_executor.cpp TIMEOUT 5)
ament_add_gtest(test_events_executor executors/test_events_executor.cpp TIMEOUT 60)
if(TARGET test_events_executor)
target_link_libraries(test_events_executor ${PROJECT_NAME} ${test_msgs_TARGETS})
endif()
Expand Down
23 changes: 15 additions & 8 deletions rclcpp/test/rclcpp/executors/test_events_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -479,14 +479,21 @@ TEST_F(TestEventsExecutor, 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 '/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 '/test_topic', offering incompatible QoS. "
"No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY",
sub_log_msg);
rclcpp::QoSCheckCompatibleResult qos_compatible = rclcpp::qos_check_compatible(
publisher->get_actual_qos(), subscription->get_actual_qos());
if (qos_compatible.compatibility == rclcpp::QoSCompatibility::Error) {
EXPECT_EQ(
"New subscription discovered on topic '/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 '/test_topic', offering incompatible QoS. "
"No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY",
sub_log_msg);
} else {
EXPECT_EQ("", pub_log_msg);
EXPECT_EQ("", sub_log_msg);
}

rcutils_logging_set_output_handler(original_output_handler);
}

0 comments on commit 4567b6e

Please sign in to comment.