Skip to content

Commit 9984197

Browse files
authored
Omnibus fixes for running tests with Connext. (#2684)
* Omnibus fixes for running tests with Connext. When running the tests with RTI Connext as the default RMW, some of the tests are failing. There are three different failures fixed here: 1. Setting the liveliness duration to a value smaller than a microsecond causes Connext to throw an error. Set it to a millisecond. 2. Using the SystemDefaultsQoS sets the QoS to KEEP_LAST 1. Connext is somewhat slow in this regard, so it can be the case that we are overwriting a previous service introspection event with the next one. Switch to the ServicesDefaultQoS in the test, which ensures we will not lose events. 3. Connext is slow to match publishers and subscriptions. Thus, when creating a subscription "on-the-fly", we should wait for the publisher to match it before expecting the subscription to actually receive data from it. With these fixes in place, the test_client_common, test_generic_service, test_service_introspection, and test_executors tests all pass for me with rmw_connextdds. Signed-off-by: Chris Lalancette <[email protected]> * Fixes for executors. Signed-off-by: Chris Lalancette <[email protected]> * One more fix for services. Signed-off-by: Chris Lalancette <[email protected]> * More fixes for service_introspection. Signed-off-by: Chris Lalancette <[email protected]> * More fixes for introspection. Signed-off-by: Chris Lalancette <[email protected]> --------- Signed-off-by: Chris Lalancette <[email protected]>
1 parent e9b1004 commit 9984197

File tree

5 files changed

+93
-21
lines changed

5 files changed

+93
-21
lines changed

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -714,6 +714,13 @@ TYPED_TEST(TestExecutors, notifyTwiceWhileSpinning)
714714
sub1_msg_count++;
715715
});
716716

717+
// Wait for the subscription to be matched
718+
size_t tries = 10000;
719+
while (this->publisher->get_subscription_count() < 2 && tries-- > 0) {
720+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
721+
}
722+
ASSERT_EQ(this->publisher->get_subscription_count(), 2);
723+
717724
// Publish a message and verify it's received
718725
this->publisher->publish(test_msgs::msg::Empty());
719726
auto start = std::chrono::steady_clock::now();
@@ -731,6 +738,13 @@ TYPED_TEST(TestExecutors, notifyTwiceWhileSpinning)
731738
sub2_msg_count++;
732739
});
733740

741+
// Wait for the subscription to be matched
742+
tries = 10000;
743+
while (this->publisher->get_subscription_count() < 3 && tries-- > 0) {
744+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
745+
}
746+
ASSERT_EQ(this->publisher->get_subscription_count(), 3);
747+
734748
// Publish a message and verify it's received by both subscriptions
735749
this->publisher->publish(test_msgs::msg::Empty());
736750
start = std::chrono::steady_clock::now();

rclcpp/test/rclcpp/test_client_common.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -431,7 +431,7 @@ TYPED_TEST(TestAllClientTypesWithServer, client_qos)
431431

432432
rclcpp::ServicesQoS qos_profile;
433433
qos_profile.liveliness(rclcpp::LivelinessPolicy::Automatic);
434-
rclcpp::Duration duration(std::chrono::nanoseconds(1));
434+
rclcpp::Duration duration(std::chrono::milliseconds(1));
435435
qos_profile.deadline(duration);
436436
qos_profile.lifespan(duration);
437437
qos_profile.liveliness_lease_duration(duration);

rclcpp/test/rclcpp/test_generic_service.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -320,7 +320,7 @@ TEST_F(TestGenericService, rcl_service_request_subscription_get_actual_qos_error
320320
TEST_F(TestGenericService, generic_service_qos) {
321321
rclcpp::ServicesQoS qos_profile;
322322
qos_profile.liveliness(rclcpp::LivelinessPolicy::Automatic);
323-
rclcpp::Duration duration(std::chrono::nanoseconds(1));
323+
rclcpp::Duration duration(std::chrono::milliseconds(1));
324324
qos_profile.deadline(duration);
325325
qos_profile.lifespan(duration);
326326
qos_profile.liveliness_lease_duration(duration);

rclcpp/test/rclcpp/test_service.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -335,7 +335,7 @@ TEST_F(TestService, rcl_service_request_subscription_get_actual_qos_error) {
335335
TEST_F(TestService, server_qos) {
336336
rclcpp::ServicesQoS qos_profile;
337337
qos_profile.liveliness(rclcpp::LivelinessPolicy::Automatic);
338-
rclcpp::Duration duration(std::chrono::nanoseconds(1));
338+
rclcpp::Duration duration(std::chrono::milliseconds(1));
339339
qos_profile.deadline(duration);
340340
qos_profile.lifespan(duration);
341341
qos_profile.liveliness_lease_duration(duration);

rclcpp/test/rclcpp/test_service_introspection.cpp

Lines changed: 76 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -92,9 +92,16 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal)
9292
request->set__int64_value(42);
9393

9494
client->configure_introspection(
95-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
95+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
9696
service->configure_introspection(
97-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
97+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
98+
99+
// Wait for the introspection to attach to our subscription
100+
size_t tries = 1000;
101+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
102+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
103+
}
104+
ASSERT_EQ(sub->get_publisher_count(), 2u);
98105

99106
auto future = client->async_send_request(request);
100107
ASSERT_EQ(
@@ -163,9 +170,11 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal)
163170
TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
164171
{
165172
client->configure_introspection(
166-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
173+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
167174
service->configure_introspection(
168-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
175+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
176+
177+
ASSERT_EQ(sub->get_publisher_count(), 0);
169178

170179
auto request = std::make_shared<BasicTypes::Request>();
171180
request->set__bool_value(true);
@@ -183,9 +192,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
183192
events.clear();
184193

185194
client->configure_introspection(
186-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
195+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
187196
service->configure_introspection(
188-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
197+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
198+
199+
// Wait for the introspection to attach to our subscription
200+
size_t tries = 1000;
201+
while (this->sub->get_publisher_count() < 1 && tries-- > 0) {
202+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
203+
}
204+
ASSERT_EQ(sub->get_publisher_count(), 1u);
189205

190206
future = client->async_send_request(request);
191207
ASSERT_EQ(
@@ -200,9 +216,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
200216
events.clear();
201217

202218
client->configure_introspection(
203-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
219+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
204220
service->configure_introspection(
205-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
221+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
222+
223+
// Wait for the introspection to attach to our subscription
224+
tries = 1000;
225+
while (this->sub->get_publisher_count() < 1 && tries-- > 0) {
226+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
227+
}
228+
ASSERT_EQ(sub->get_publisher_count(), 1u);
206229

207230
future = client->async_send_request(request);
208231
ASSERT_EQ(
@@ -217,9 +240,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
217240
events.clear();
218241

219242
client->configure_introspection(
220-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
243+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
221244
service->configure_introspection(
222-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
245+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
246+
247+
// Wait for the introspection to attach to our subscription
248+
tries = 1000;
249+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
250+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
251+
}
252+
ASSERT_EQ(sub->get_publisher_count(), 2u);
223253

224254
future = client->async_send_request(request);
225255
ASSERT_EQ(
@@ -235,9 +265,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
235265
TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_content)
236266
{
237267
client->configure_introspection(
238-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
268+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
239269
service->configure_introspection(
240-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
270+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
271+
272+
// Wait for the introspection to attach to our subscription
273+
size_t tries = 1000;
274+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
275+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
276+
}
277+
ASSERT_EQ(sub->get_publisher_count(), 2u);
241278

242279
auto request = std::make_shared<BasicTypes::Request>();
243280
request->set__bool_value(true);
@@ -259,9 +296,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
259296
events.clear();
260297

261298
client->configure_introspection(
262-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
299+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
263300
service->configure_introspection(
264-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
301+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
302+
303+
// Wait for the introspection to attach to our subscription
304+
tries = 1000;
305+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
306+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
307+
}
308+
ASSERT_EQ(sub->get_publisher_count(), 2u);
265309

266310
future = client->async_send_request(request);
267311
ASSERT_EQ(
@@ -292,9 +336,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
292336
events.clear();
293337

294338
client->configure_introspection(
295-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
339+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
296340
service->configure_introspection(
297-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
341+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
342+
343+
// Wait for the introspection to attach to our subscription
344+
tries = 1000;
345+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
346+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
347+
}
348+
ASSERT_EQ(sub->get_publisher_count(), 2u);
298349

299350
future = client->async_send_request(request);
300351
ASSERT_EQ(
@@ -325,9 +376,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
325376
events.clear();
326377

327378
client->configure_introspection(
328-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
379+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
329380
service->configure_introspection(
330-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
381+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
382+
383+
// Wait for the introspection to attach to our subscription
384+
tries = 1000;
385+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
386+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
387+
}
388+
ASSERT_EQ(sub->get_publisher_count(), 2u);
331389

332390
future = client->async_send_request(request);
333391
ASSERT_EQ(

0 commit comments

Comments
 (0)