@@ -33,13 +33,14 @@ using namespace std::chrono_literals;
3333class TestQosEvent : public ::testing::Test
3434{
3535protected:
36- static void SetUpTestCase ()
36+ void SetUp ()
3737 {
38+ // We initialize and shutdown the context (and hence also the rmw_context),
39+ // for each test case to reset the ROS graph for each test case.
3840 rclcpp::init (0 , nullptr );
39- }
4041
41- void SetUp ()
42- {
42+ rmw_implementation_str = std::string ( rmw_get_implementation_identifier ());
43+
4344 node = std::make_shared<rclcpp::Node>(" test_qos_event" , " /ns" );
4445
4546 message_callback = [node = node.get ()](test_msgs::msg::Empty::ConstSharedPtr /* msg*/ ) {
@@ -50,13 +51,10 @@ class TestQosEvent : public ::testing::Test
5051 void TearDown ()
5152 {
5253 node.reset ();
53- }
54-
55- static void TearDownTestCase ()
56- {
5754 rclcpp::shutdown ();
5855 }
5956
57+ std::string rmw_implementation_str;
6058 static constexpr char topic_name[] = " test_topic" ;
6159 rclcpp::Node::SharedPtr node;
6260 std::function<void (test_msgs::msg::Empty::ConstSharedPtr)> message_callback;
@@ -75,28 +73,29 @@ TEST_F(TestQosEvent, test_publisher_constructor)
7573 auto publisher = node->create_publisher <test_msgs::msg::Empty>(
7674 topic_name, 10 , options);
7775
78- // options arg with one of the callbacks
79- options.event_callbacks .deadline_callback =
80- [node = node.get ()](rclcpp::QOSDeadlineOfferedInfo & event) {
81- RCLCPP_INFO (
82- node->get_logger (),
83- " Offered deadline missed - total %d (delta %d)" ,
84- event.total_count , event.total_count_change );
85- };
86- publisher = node->create_publisher <test_msgs::msg::Empty>(
87- topic_name, 10 , options);
88-
89- // options arg with two of the callbacks
90- options.event_callbacks .liveliness_callback =
91- [node = node.get ()](rclcpp::QOSLivelinessLostInfo & event) {
92- RCLCPP_INFO (
93- node->get_logger (),
94- " Liveliness lost - total %d (delta %d)" ,
95- event.total_count , event.total_count_change );
96- };
97- publisher = node->create_publisher <test_msgs::msg::Empty>(
98- topic_name, 10 , options);
99-
76+ if (rmw_implementation_str != " rmw_zenoh_cpp" ) {
77+ // options arg with one of the callbacks
78+ options.event_callbacks .deadline_callback =
79+ [node = node.get ()](rclcpp::QOSDeadlineOfferedInfo & event) {
80+ RCLCPP_INFO (
81+ node->get_logger (),
82+ " Offered deadline missed - total %d (delta %d)" ,
83+ event.total_count , event.total_count_change );
84+ };
85+ publisher = node->create_publisher <test_msgs::msg::Empty>(
86+ topic_name, 10 , options);
87+
88+ // options arg with two of the callbacks
89+ options.event_callbacks .liveliness_callback =
90+ [node = node.get ()](rclcpp::QOSLivelinessLostInfo & event) {
91+ RCLCPP_INFO (
92+ node->get_logger (),
93+ " Liveliness lost - total %d (delta %d)" ,
94+ event.total_count , event.total_count_change );
95+ };
96+ publisher = node->create_publisher <test_msgs::msg::Empty>(
97+ topic_name, 10 , options);
98+ }
10099 // options arg with three of the callbacks
101100 options.event_callbacks .incompatible_qos_callback =
102101 [node = node.get ()](rclcpp::QOSOfferedIncompatibleQoSInfo & event) {
@@ -114,35 +113,38 @@ TEST_F(TestQosEvent, test_publisher_constructor)
114113 */
115114TEST_F (TestQosEvent, test_subscription_constructor)
116115{
116+ // While rmw_zenoh does not support Deadline/LivelinessChanged events,
117+ // it does support IncompatibleQoS
117118 rclcpp::SubscriptionOptions options;
118119
119120 // options arg with no callbacks
120121 auto subscription = node->create_subscription <test_msgs::msg::Empty>(
121122 topic_name, 10 , message_callback, options);
122123
123- // options arg with one of the callbacks
124- options.event_callbacks .deadline_callback =
125- [node = node.get ()](rclcpp::QOSDeadlineRequestedInfo & event) {
126- RCLCPP_INFO (
127- node->get_logger (),
128- " Requested deadline missed - total %d (delta %d)" ,
129- event.total_count , event.total_count_change );
130- };
131- subscription = node->create_subscription <test_msgs::msg::Empty>(
132- topic_name, 10 , message_callback, options);
133-
134- // options arg with two of the callbacks
135- options.event_callbacks .liveliness_callback =
136- [node = node.get ()](rclcpp::QOSLivelinessChangedInfo & event) {
137- RCLCPP_INFO (
138- node->get_logger (),
139- " Liveliness changed - alive %d (delta %d), not alive %d (delta %d)" ,
140- event.alive_count , event.alive_count_change ,
141- event.not_alive_count , event.not_alive_count_change );
142- };
143- subscription = node->create_subscription <test_msgs::msg::Empty>(
144- topic_name, 10 , message_callback, options);
145-
124+ if (rmw_implementation_str != " rmw_zenoh_cpp" ) {
125+ // options arg with one of the callbacks
126+ options.event_callbacks .deadline_callback =
127+ [node = node.get ()](rclcpp::QOSDeadlineRequestedInfo & event) {
128+ RCLCPP_INFO (
129+ node->get_logger (),
130+ " Requested deadline missed - total %d (delta %d)" ,
131+ event.total_count , event.total_count_change );
132+ };
133+ subscription = node->create_subscription <test_msgs::msg::Empty>(
134+ topic_name, 10 , message_callback, options);
135+
136+ // options arg with two of the callbacks
137+ options.event_callbacks .liveliness_callback =
138+ [node = node.get ()](rclcpp::QOSLivelinessChangedInfo & event) {
139+ RCLCPP_INFO (
140+ node->get_logger (),
141+ " Liveliness changed - alive %d (delta %d), not alive %d (delta %d)" ,
142+ event.alive_count , event.alive_count_change ,
143+ event.not_alive_count , event.not_alive_count_change );
144+ };
145+ subscription = node->create_subscription <test_msgs::msg::Empty>(
146+ topic_name, 10 , message_callback, options);
147+ }
146148 // options arg with three of the callbacks
147149 options.event_callbacks .incompatible_qos_callback =
148150 [node = node.get ()](rclcpp::QOSRequestedIncompatibleQoSInfo & event) {
@@ -209,14 +211,19 @@ TEST_F(TestQosEvent, test_default_incompatible_qos_callbacks)
209211 const auto timeout = std::chrono::seconds (10 );
210212 ex.spin_until_future_complete (log_msgs_future, timeout);
211213
212- EXPECT_EQ (
213- " New subscription discovered on topic '/ns/test_topic', requesting incompatible QoS. "
214- " No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY" ,
215- pub_log_msg);
216- EXPECT_EQ (
217- " New publisher discovered on topic '/ns/test_topic', offering incompatible QoS. "
218- " No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY" ,
219- sub_log_msg);
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+ EXPECT_EQ (
219+ " New subscription discovered on topic '/ns/test_topic', requesting incompatible QoS. "
220+ " No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY" ,
221+ pub_log_msg);
222+ EXPECT_EQ (
223+ " New publisher discovered on topic '/ns/test_topic', offering incompatible QoS. "
224+ " No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY" ,
225+ sub_log_msg);
226+ }
220227
221228 rcutils_logging_set_output_handler (original_output_handler);
222229}
@@ -228,7 +235,8 @@ TEST_F(TestQosEvent, construct_destruct_rcl_error) {
228235
229236 // This callback requires some type of parameter, but it could be anything
230237 auto callback = [](int ) {};
231- const rcl_publisher_event_type_t event_type = RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
238+ const rcl_publisher_event_type_t event_type = rmw_implementation_str == " rmw_zenoh_cpp" ?
239+ RCL_PUBLISHER_MATCHED : RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
232240
233241 {
234242 // Logs error and returns
@@ -265,13 +273,16 @@ TEST_F(TestQosEvent, construct_destruct_rcl_error) {
265273}
266274
267275TEST_F (TestQosEvent, execute) {
276+ if (rmw_implementation_str == " rmw_zenoh_cpp" ) {
277+ GTEST_SKIP ();
278+ }
268279 auto publisher = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 );
269280 auto rcl_handle = publisher->get_publisher_handle ();
270281
271282 bool handler_callback_executed = false ;
272283 // This callback requires some type of parameter, but it could be anything
273284 auto callback = [&handler_callback_executed](int ) {handler_callback_executed = true ;};
274- rcl_publisher_event_type_t event_type = RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
285+ const rcl_publisher_event_type_t event_type = RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
275286
276287 rclcpp::EventHandler<decltype (callback), decltype (rcl_handle)> handler (
277288 callback, rcl_publisher_event_init, rcl_handle, event_type);
@@ -297,8 +308,9 @@ TEST_F(TestQosEvent, add_to_wait_set) {
297308 // This callback requires some type of parameter, but it could be anything
298309 auto callback = [](int ) {};
299310
300- rcl_publisher_event_type_t event_type = RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
301- rclcpp::EventHandler<decltype (callback), decltype (rcl_handle)> handler (
311+ const rcl_publisher_event_type_t event_type = rmw_implementation_str == " rmw_zenoh_cpp" ?
312+ RCL_PUBLISHER_MATCHED : RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
313+ rclcpp::EventHandler<decltype (callback), decltype (rcl_handle)> handler (
302314 callback, rcl_publisher_event_init, rcl_handle, event_type);
303315
304316 EXPECT_EQ (1u , handler.get_number_of_ready_events ());
@@ -319,6 +331,10 @@ TEST_F(TestQosEvent, add_to_wait_set) {
319331
320332TEST_F (TestQosEvent, test_on_new_event_callback)
321333{
334+ if (rmw_implementation_str == " rmw_zenoh_cpp" ) {
335+ GTEST_SKIP ();
336+ }
337+
322338 auto offered_deadline = rclcpp::Duration (std::chrono::milliseconds (1 ));
323339 auto requested_deadline = rclcpp::Duration (std::chrono::milliseconds (2 ));
324340
@@ -364,18 +380,19 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
364380 auto sub = node->create_subscription <test_msgs::msg::Empty>(topic_name, 10 , message_callback);
365381 auto dummy_cb = [](size_t count_events) {(void )count_events;};
366382
367- EXPECT_NO_THROW (
368- pub->set_on_new_qos_event_callback (dummy_cb, RCL_PUBLISHER_OFFERED_DEADLINE_MISSED));
383+ if (rmw_implementation_str != " rmw_zenoh_cpp" ) {
384+ EXPECT_NO_THROW (
385+ pub->set_on_new_qos_event_callback (dummy_cb, RCL_PUBLISHER_OFFERED_DEADLINE_MISSED));
369386
370- EXPECT_NO_THROW (
371- pub->clear_on_new_qos_event_callback (RCL_PUBLISHER_OFFERED_DEADLINE_MISSED));
387+ EXPECT_NO_THROW (
388+ pub->clear_on_new_qos_event_callback (RCL_PUBLISHER_OFFERED_DEADLINE_MISSED));
372389
373- EXPECT_NO_THROW (
374- pub->set_on_new_qos_event_callback (dummy_cb, RCL_PUBLISHER_LIVELINESS_LOST));
390+ EXPECT_NO_THROW (
391+ pub->set_on_new_qos_event_callback (dummy_cb, RCL_PUBLISHER_LIVELINESS_LOST));
375392
376- EXPECT_NO_THROW (
393+ EXPECT_NO_THROW (
377394 pub->clear_on_new_qos_event_callback (RCL_PUBLISHER_LIVELINESS_LOST));
378-
395+ }
379396 EXPECT_NO_THROW (
380397 pub->set_on_new_qos_event_callback (dummy_cb, RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS));
381398
@@ -388,18 +405,19 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
388405 EXPECT_NO_THROW (
389406 pub->clear_on_new_qos_event_callback (RCL_PUBLISHER_MATCHED));
390407
391- EXPECT_NO_THROW (
392- sub->set_on_new_qos_event_callback (dummy_cb, RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED));
408+ if (rmw_implementation_str == " rmw_zenoh_cpp" ) {
409+ EXPECT_NO_THROW (
410+ sub->set_on_new_qos_event_callback (dummy_cb, RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED));
393411
394- EXPECT_NO_THROW (
395- sub->clear_on_new_qos_event_callback (RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED));
412+ EXPECT_NO_THROW (
413+ sub->clear_on_new_qos_event_callback (RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED));
396414
397- EXPECT_NO_THROW (
398- sub->set_on_new_qos_event_callback (dummy_cb, RCL_SUBSCRIPTION_LIVELINESS_CHANGED));
399-
400- EXPECT_NO_THROW (
401- sub->clear_on_new_qos_event_callback (RCL_SUBSCRIPTION_LIVELINESS_CHANGED));
415+ EXPECT_NO_THROW (
416+ sub->set_on_new_qos_event_callback (dummy_cb, RCL_SUBSCRIPTION_LIVELINESS_CHANGED));
402417
418+ EXPECT_NO_THROW (
419+ sub->clear_on_new_qos_event_callback (RCL_SUBSCRIPTION_LIVELINESS_CHANGED));
420+ }
403421 EXPECT_NO_THROW (
404422 sub->set_on_new_qos_event_callback (dummy_cb, RCL_SUBSCRIPTION_REQUESTED_INCOMPATIBLE_QOS));
405423
@@ -412,24 +430,26 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback)
412430 EXPECT_NO_THROW (
413431 sub->clear_on_new_qos_event_callback (RCL_SUBSCRIPTION_MATCHED));
414432
415- std::function<void (size_t )> invalid_cb;
433+ if (rmw_implementation_str != " rmw_zenoh_cpp" ) {
434+ std::function<void (size_t )> invalid_cb;
416435
417- rclcpp::SubscriptionOptions sub_options;
418- sub_options.event_callbacks .deadline_callback = [](auto ) {};
419- sub = node->create_subscription <test_msgs::msg::Empty>(
420- topic_name, 10 , message_callback, sub_options);
436+ rclcpp::SubscriptionOptions sub_options;
437+ sub_options.event_callbacks .deadline_callback = [](auto ) {};
438+ sub = node->create_subscription <test_msgs::msg::Empty>(
439+ topic_name, 10 , message_callback, sub_options);
421440
422- EXPECT_THROW (
423- sub->set_on_new_qos_event_callback (invalid_cb, RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED),
424- std::invalid_argument);
441+ EXPECT_THROW (
442+ sub->set_on_new_qos_event_callback (invalid_cb, RCL_SUBSCRIPTION_REQUESTED_DEADLINE_MISSED),
443+ std::invalid_argument);
425444
426- rclcpp::PublisherOptions pub_options;
427- pub_options.event_callbacks .deadline_callback = [](auto ) {};
428- pub = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 , pub_options);
445+ rclcpp::PublisherOptions pub_options;
446+ pub_options.event_callbacks .deadline_callback = [](auto ) {};
447+ pub = node->create_publisher <test_msgs::msg::Empty>(topic_name, 10 , pub_options);
429448
430- EXPECT_THROW (
431- pub->set_on_new_qos_event_callback (invalid_cb, RCL_PUBLISHER_OFFERED_DEADLINE_MISSED),
432- std::invalid_argument);
449+ EXPECT_THROW (
450+ pub->set_on_new_qos_event_callback (invalid_cb, RCL_PUBLISHER_OFFERED_DEADLINE_MISSED),
451+ std::invalid_argument);
452+ }
433453}
434454
435455TEST_F (TestQosEvent, test_pub_matched_event_by_set_event_callback)
0 commit comments