Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Omnibus fixes for running tests with Connext. #2684

Open
wants to merge 5 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 14 additions & 0 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -714,6 +714,13 @@ TYPED_TEST(TestExecutors, notifyTwiceWhileSpinning)
sub1_msg_count++;
});

// Wait for the subscription to be matched
size_t tries = 10000;
while (this->publisher->get_subscription_count() < 2 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(this->publisher->get_subscription_count(), 2);

// Publish a message and verify it's received
this->publisher->publish(test_msgs::msg::Empty());
auto start = std::chrono::steady_clock::now();
Expand All @@ -731,6 +738,13 @@ TYPED_TEST(TestExecutors, notifyTwiceWhileSpinning)
sub2_msg_count++;
});

// Wait for the subscription to be matched
tries = 10000;
while (this->publisher->get_subscription_count() < 3 && tries-- > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
ASSERT_EQ(this->publisher->get_subscription_count(), 3);

// Publish a message and verify it's received by both subscriptions
this->publisher->publish(test_msgs::msg::Empty());
start = std::chrono::steady_clock::now();
Expand Down
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_generic_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -320,7 +320,7 @@ TEST_F(TestGenericService, rcl_service_request_subscription_get_actual_qos_error
TEST_F(TestGenericService, generic_service_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 @@ -163,9 +170,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 @@ -183,9 +192,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 @@ -200,9 +216,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 @@ -217,9 +240,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 @@ -235,9 +265,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 @@ -259,9 +296,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 @@ -292,9 +336,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 @@ -325,9 +376,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