@@ -73,7 +73,9 @@ TEST_F(TestQosEvent, test_publisher_constructor)
73
73
auto publisher = node->create_publisher <test_msgs::msg::Empty>(
74
74
topic_name, 10 , options);
75
75
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
+ {
77
79
// options arg with one of the callbacks
78
80
options.event_callbacks .deadline_callback =
79
81
[node = node.get ()](rclcpp::QOSDeadlineOfferedInfo & event) {
@@ -121,7 +123,9 @@ TEST_F(TestQosEvent, test_subscription_constructor)
121
123
auto subscription = node->create_subscription <test_msgs::msg::Empty>(
122
124
topic_name, 10 , message_callback, options);
123
125
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
+ {
125
129
// options arg with one of the callbacks
126
130
options.event_callbacks .deadline_callback =
127
131
[node = node.get ()](rclcpp::QOSDeadlineRequestedInfo & event) {
@@ -211,10 +215,9 @@ TEST_F(TestQosEvent, test_default_incompatible_qos_callbacks)
211
215
const auto timeout = std::chrono::seconds (10 );
212
216
ex.spin_until_future_complete (log_msgs_future, timeout);
213
217
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
+ {
218
221
EXPECT_EQ (
219
222
" New subscription discovered on topic '/ns/test_topic', requesting incompatible QoS. "
220
223
" No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY" ,
@@ -235,7 +238,8 @@ TEST_F(TestQosEvent, construct_destruct_rcl_error) {
235
238
236
239
// This callback requires some type of parameter, but it could be anything
237
240
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) ?
239
243
RCL_PUBLISHER_MATCHED : RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
240
244
241
245
{
@@ -273,9 +277,10 @@ TEST_F(TestQosEvent, construct_destruct_rcl_error) {
273
277
}
274
278
275
279
TEST_F (TestQosEvent, execute) {
276
- if (rmw_implementation_str == " rmw_zenoh_cpp " ) {
280
+ if (! rmw_event_type_is_supported (RMW_EVENT_OFFERED_DEADLINE_MISSED) ) {
277
281
GTEST_SKIP ();
278
282
}
283
+
279
284
auto publisher = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 );
280
285
auto rcl_handle = publisher->get_publisher_handle ();
281
286
@@ -308,9 +313,11 @@ TEST_F(TestQosEvent, add_to_wait_set) {
308
313
// This callback requires some type of parameter, but it could be anything
309
314
auto callback = [](int ) {};
310
315
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) ?
312
318
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 (
314
321
callback, rcl_publisher_event_init, rcl_handle, event_type);
315
322
316
323
EXPECT_EQ (1u , handler.get_number_of_ready_events ());
@@ -331,7 +338,9 @@ TEST_F(TestQosEvent, add_to_wait_set) {
331
338
332
339
TEST_F (TestQosEvent, test_on_new_event_callback)
333
340
{
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
+ {
335
344
GTEST_SKIP ();
336
345
}
337
346
@@ -380,7 +389,9 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
380
389
auto sub = node->create_subscription <test_msgs::msg::Empty>(topic_name, 10 , message_callback);
381
390
auto dummy_cb = [](size_t count_events) {(void )count_events;};
382
391
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
+ {
384
395
EXPECT_NO_THROW (
385
396
pub->set_on_new_qos_event_callback (dummy_cb, RCL_PUBLISHER_OFFERED_DEADLINE_MISSED));
386
397
@@ -405,7 +416,9 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
405
416
EXPECT_NO_THROW (
406
417
pub->clear_on_new_qos_event_callback (RCL_PUBLISHER_MATCHED));
407
418
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
+ {
409
422
EXPECT_NO_THROW (
410
423
sub->set_on_new_qos_event_callback (dummy_cb, RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED));
411
424
@@ -430,7 +443,9 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
430
443
EXPECT_NO_THROW (
431
444
sub->clear_on_new_qos_event_callback (RCL_SUBSCRIPTION_MATCHED));
432
445
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
+ {
434
449
std::function<void (size_t )> invalid_cb;
435
450
436
451
rclcpp::SubscriptionOptions sub_options;
0 commit comments