Skip to content

Commit

Permalink
Omnibus fixes for running tests with Connext. (backport #2684) (#2690)
Browse files Browse the repository at this point in the history
* 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]>
  • Loading branch information
3 people authored Dec 3, 2024
1 parent df09c6e commit a7b8ada
Show file tree
Hide file tree
Showing 3 changed files with 78 additions and 20 deletions.
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_client_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -431,7 +431,7 @@ TYPED_TEST(TestAllClientTypesWithServer, client_qos)

rclcpp::ServicesQoS qos_profile;
qos_profile.liveliness(rclcpp::LivelinessPolicy::Automatic);
rclcpp::Duration duration(std::chrono::nanoseconds(1));
rclcpp::Duration duration(std::chrono::milliseconds(1));
qos_profile.deadline(duration);
qos_profile.lifespan(duration);
qos_profile.liveliness_lease_duration(duration);
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -335,7 +335,7 @@ TEST_F(TestService, rcl_service_request_subscription_get_actual_qos_error) {
TEST_F(TestService, server_qos) {
rclcpp::ServicesQoS qos_profile;
qos_profile.liveliness(rclcpp::LivelinessPolicy::Automatic);
rclcpp::Duration duration(std::chrono::nanoseconds(1));
rclcpp::Duration duration(std::chrono::milliseconds(1));
qos_profile.deadline(duration);
qos_profile.lifespan(duration);
qos_profile.liveliness_lease_duration(duration);
Expand Down
94 changes: 76 additions & 18 deletions rclcpp/test/rclcpp/test_service_introspection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,9 +92,16 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal)
request->set__int64_value(42);

client->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);

// Wait for the introspection to attach to our subscription
size_t tries = 1000;
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(sub->get_publisher_count(), 2u);

auto future = client->async_send_request(request);
ASSERT_EQ(
Expand Down Expand Up @@ -149,9 +156,11 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal)
TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
{
client->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);

ASSERT_EQ(sub->get_publisher_count(), 0);

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

client->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);

// Wait for the introspection to attach to our subscription
size_t tries = 1000;
while (this->sub->get_publisher_count() < 1 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(sub->get_publisher_count(), 1u);

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

client->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);

// Wait for the introspection to attach to our subscription
tries = 1000;
while (this->sub->get_publisher_count() < 1 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(sub->get_publisher_count(), 1u);

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

client->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);

// Wait for the introspection to attach to our subscription
tries = 1000;
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(sub->get_publisher_count(), 2u);

future = client->async_send_request(request);
ASSERT_EQ(
Expand All @@ -221,9 +251,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events)
TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_content)
{
client->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);

// Wait for the introspection to attach to our subscription
size_t tries = 1000;
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(sub->get_publisher_count(), 2u);

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

client->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);

// Wait for the introspection to attach to our subscription
tries = 1000;
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(sub->get_publisher_count(), 2u);

future = client->async_send_request(request);
ASSERT_EQ(
Expand Down Expand Up @@ -278,9 +322,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
events.clear();

client->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);

// Wait for the introspection to attach to our subscription
tries = 1000;
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(sub->get_publisher_count(), 2u);

future = client->async_send_request(request);
ASSERT_EQ(
Expand Down Expand Up @@ -311,9 +362,16 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont
events.clear();

client->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);

// Wait for the introspection to attach to our subscription
tries = 1000;
while (this->sub->get_publisher_count() < 2 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(sub->get_publisher_count(), 2u);

future = client->async_send_request(request);
ASSERT_EQ(
Expand Down

0 comments on commit a7b8ada

Please sign in to comment.