@@ -73,7 +73,9 @@ TEST_F(TestQosEvent, test_publisher_constructor)
7373 auto publisher = node->create_publisher <test_msgs::msg::Empty>(
7474 topic_name, 10 , options);
7575
76- if (rmw_implementation_str != " rmw_zenoh_cpp" ) {
76+ if (rmw_event_type_is_supported (RMW_EVENT_OFFERED_DEADLINE_MISSED) &&
77+ rmw_event_type_is_supported (RMW_EVENT_LIVELINESS_LOST))
78+ {
7779 // options arg with one of the callbacks
7880 options.event_callbacks .deadline_callback =
7981 [node = node.get ()](rclcpp::QOSDeadlineOfferedInfo & event) {
@@ -121,7 +123,9 @@ TEST_F(TestQosEvent, test_subscription_constructor)
121123 auto subscription = node->create_subscription <test_msgs::msg::Empty>(
122124 topic_name, 10 , message_callback, options);
123125
124- if (rmw_implementation_str != " rmw_zenoh_cpp" ) {
126+ if (rmw_event_type_is_supported (RMW_EVENT_REQUESTED_DEADLINE_MISSED) &&
127+ rmw_event_type_is_supported (RMW_EVENT_LIVELINESS_CHANGED))
128+ {
125129 // options arg with one of the callbacks
126130 options.event_callbacks .deadline_callback =
127131 [node = node.get ()](rclcpp::QOSDeadlineRequestedInfo & event) {
@@ -211,10 +215,9 @@ TEST_F(TestQosEvent, test_default_incompatible_qos_callbacks)
211215 const auto timeout = std::chrono::seconds (10 );
212216 ex.spin_until_future_complete (log_msgs_future, timeout);
213217
214- if (rmw_implementation_str == " rmw_zenoh_cpp" ) {
215- EXPECT_EQ (rclcpp::QoSCompatibility::Ok,
216- qos_check_compatible (qos_profile_publisher, qos_profile_subscription).compatibility );
217- } else {
218+ if (qos_check_compatible (qos_profile_publisher,
219+ qos_profile_subscription).compatibility != rclcpp::QoSCompatibility::Ok)
220+ {
218221 EXPECT_EQ (
219222 " New subscription discovered on topic '/ns/test_topic', requesting incompatible QoS. "
220223 " No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY" ,
@@ -235,7 +238,8 @@ TEST_F(TestQosEvent, construct_destruct_rcl_error) {
235238
236239 // This callback requires some type of parameter, but it could be anything
237240 auto callback = [](int ) {};
238- const rcl_publisher_event_type_t event_type = rmw_implementation_str == " rmw_zenoh_cpp" ?
241+ const rcl_publisher_event_type_t event_type =
242+ !rmw_event_type_is_supported (RMW_EVENT_OFFERED_DEADLINE_MISSED) ?
239243 RCL_PUBLISHER_MATCHED : RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
240244
241245 {
@@ -273,9 +277,10 @@ TEST_F(TestQosEvent, construct_destruct_rcl_error) {
273277}
274278
275279TEST_F (TestQosEvent, execute) {
276- if (rmw_implementation_str == " rmw_zenoh_cpp " ) {
280+ if (! rmw_event_type_is_supported (RMW_EVENT_OFFERED_DEADLINE_MISSED) ) {
277281 GTEST_SKIP ();
278282 }
283+
279284 auto publisher = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 );
280285 auto rcl_handle = publisher->get_publisher_handle ();
281286
@@ -308,9 +313,11 @@ TEST_F(TestQosEvent, add_to_wait_set) {
308313 // This callback requires some type of parameter, but it could be anything
309314 auto callback = [](int ) {};
310315
311- const rcl_publisher_event_type_t event_type = rmw_implementation_str == " rmw_zenoh_cpp" ?
316+ const rcl_publisher_event_type_t event_type =
317+ !rmw_event_type_is_supported (RMW_EVENT_OFFERED_DEADLINE_MISSED) ?
312318 RCL_PUBLISHER_MATCHED : RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
313- rclcpp::EventHandler<decltype (callback), decltype (rcl_handle)> handler (
319+
320+ rclcpp::EventHandler<decltype (callback), decltype (rcl_handle)> handler (
314321 callback, rcl_publisher_event_init, rcl_handle, event_type);
315322
316323 EXPECT_EQ (1u , handler.get_number_of_ready_events ());
@@ -331,7 +338,9 @@ TEST_F(TestQosEvent, add_to_wait_set) {
331338
332339TEST_F (TestQosEvent, test_on_new_event_callback)
333340{
334- if (rmw_implementation_str == " rmw_zenoh_cpp" ) {
341+ if (!rmw_event_type_is_supported (RMW_EVENT_REQUESTED_DEADLINE_MISSED) ||
342+ !rmw_event_type_is_supported (RMW_EVENT_OFFERED_DEADLINE_MISSED))
343+ {
335344 GTEST_SKIP ();
336345 }
337346
@@ -380,7 +389,9 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
380389 auto sub = node->create_subscription <test_msgs::msg::Empty>(topic_name, 10 , message_callback);
381390 auto dummy_cb = [](size_t count_events) {(void )count_events;};
382391
383- if (rmw_implementation_str != " rmw_zenoh_cpp" ) {
392+ if (rmw_event_type_is_supported (RMW_EVENT_OFFERED_DEADLINE_MISSED) &&
393+ rmw_event_type_is_supported (RMW_EVENT_LIVELINESS_LOST))
394+ {
384395 EXPECT_NO_THROW (
385396 pub->set_on_new_qos_event_callback (dummy_cb, RCL_PUBLISHER_OFFERED_DEADLINE_MISSED));
386397
@@ -405,7 +416,9 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
405416 EXPECT_NO_THROW (
406417 pub->clear_on_new_qos_event_callback (RCL_PUBLISHER_MATCHED));
407418
408- if (rmw_implementation_str == " rmw_zenoh_cpp" ) {
419+ if (rmw_event_type_is_supported (RMW_EVENT_REQUESTED_DEADLINE_MISSED) &&
420+ rmw_event_type_is_supported (RMW_EVENT_LIVELINESS_CHANGED))
421+ {
409422 EXPECT_NO_THROW (
410423 sub->set_on_new_qos_event_callback (dummy_cb, RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED));
411424
@@ -430,7 +443,9 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
430443 EXPECT_NO_THROW (
431444 sub->clear_on_new_qos_event_callback (RCL_SUBSCRIPTION_MATCHED));
432445
433- if (rmw_implementation_str != " rmw_zenoh_cpp" ) {
446+ if (rmw_event_type_is_supported (RMW_EVENT_REQUESTED_DEADLINE_MISSED) &&
447+ rmw_event_type_is_supported (RMW_EVENT_OFFERED_DEADLINE_MISSED))
448+ {
434449 std::function<void (size_t )> invalid_cb;
435450
436451 rclcpp::SubscriptionOptions sub_options;
0 commit comments