Skip to content

Commit a7b8ada

Browse files
mergify[bot]clalancettefujitatomoya
authored
Omnibus fixes for running tests with Connext. (backport #2684) (#2690)
* 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]> (cherry picked from commit 9984197) # Conflicts: # rclcpp/test/rclcpp/executors/test_executors.cpp # rclcpp/test/rclcpp/test_generic_service.cpp * address backport merge conflicts. Signed-off-by: Tomoya Fujita <[email protected]> --------- Signed-off-by: Tomoya Fujita <[email protected]> Co-authored-by: Chris Lalancette <[email protected]> Co-authored-by: Tomoya Fujita <[email protected]>
1 parent df09c6e commit a7b8ada

File tree

3 files changed

+78
-20
lines changed

3 files changed

+78
-20
lines changed

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_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(
@@ -149,9 +156,11 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal)
149156
TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
150157
{
151158
client->configure_introspection(
152-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
159+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
153160
service->configure_introspection(
154-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
161+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
162+
163+
ASSERT_EQ(sub->get_publisher_count(), 0);
155164

156165
auto request = std::make_shared<BasicTypes::Request>();
157166
request->set__bool_value(true);
@@ -169,9 +178,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
169178
events.clear();
170179

171180
client->configure_introspection(
172-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
181+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
173182
service->configure_introspection(
174-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
183+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
184+
185+
// Wait for the introspection to attach to our subscription
186+
size_t tries = 1000;
187+
while (this->sub->get_publisher_count() < 1 && tries-- > 0) {
188+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
189+
}
190+
ASSERT_EQ(sub->get_publisher_count(), 1u);
175191

176192
future = client->async_send_request(request);
177193
ASSERT_EQ(
@@ -186,9 +202,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
186202
events.clear();
187203

188204
client->configure_introspection(
189-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
205+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
190206
service->configure_introspection(
191-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
207+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
208+
209+
// Wait for the introspection to attach to our subscription
210+
tries = 1000;
211+
while (this->sub->get_publisher_count() < 1 && tries-- > 0) {
212+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
213+
}
214+
ASSERT_EQ(sub->get_publisher_count(), 1u);
192215

193216
future = client->async_send_request(request);
194217
ASSERT_EQ(
@@ -203,9 +226,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
203226
events.clear();
204227

205228
client->configure_introspection(
206-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
229+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
207230
service->configure_introspection(
208-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
231+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
232+
233+
// Wait for the introspection to attach to our subscription
234+
tries = 1000;
235+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
236+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
237+
}
238+
ASSERT_EQ(sub->get_publisher_count(), 2u);
209239

210240
future = client->async_send_request(request);
211241
ASSERT_EQ(
@@ -221,9 +251,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
221251
TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_content)
222252
{
223253
client->configure_introspection(
224-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
254+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
225255
service->configure_introspection(
226-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
256+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
257+
258+
// Wait for the introspection to attach to our subscription
259+
size_t tries = 1000;
260+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
261+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
262+
}
263+
ASSERT_EQ(sub->get_publisher_count(), 2u);
227264

228265
auto request = std::make_shared<BasicTypes::Request>();
229266
request->set__bool_value(true);
@@ -245,9 +282,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
245282
events.clear();
246283

247284
client->configure_introspection(
248-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
285+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
249286
service->configure_introspection(
250-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
287+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
288+
289+
// Wait for the introspection to attach to our subscription
290+
tries = 1000;
291+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
292+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
293+
}
294+
ASSERT_EQ(sub->get_publisher_count(), 2u);
251295

252296
future = client->async_send_request(request);
253297
ASSERT_EQ(
@@ -278,9 +322,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
278322
events.clear();
279323

280324
client->configure_introspection(
281-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
325+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
282326
service->configure_introspection(
283-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
327+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
328+
329+
// Wait for the introspection to attach to our subscription
330+
tries = 1000;
331+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
332+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
333+
}
334+
ASSERT_EQ(sub->get_publisher_count(), 2u);
284335

285336
future = client->async_send_request(request);
286337
ASSERT_EQ(
@@ -311,9 +362,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
311362
events.clear();
312363

313364
client->configure_introspection(
314-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
365+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
315366
service->configure_introspection(
316-
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
367+
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
368+
369+
// Wait for the introspection to attach to our subscription
370+
tries = 1000;
371+
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
372+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
373+
}
374+
ASSERT_EQ(sub->get_publisher_count(), 2u);
317375

318376
future = client->async_send_request(request);
319377
ASSERT_EQ(

0 commit comments

Comments
 (0)