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

use QoS Reliable and History Depth 10 for stable test result. #2651

Draft
wants to merge 1 commit into
base: rolling
Choose a base branch
from
Draft
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
40 changes: 21 additions & 19 deletions rclcpp/test/rclcpp/test_service_introspection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,8 @@ class TestServiceIntrospection : public ::testing::Test

client = node->create_client<BasicTypes>("service");
service = node->create_service<BasicTypes>("service", srv_callback);
sub = node->create_subscription<BasicTypes::Event>("service/_service_event", 10, callback);
sub = node->create_subscription<BasicTypes::Event>(
"service/_service_event", qos_profile_, callback);
events.clear();
}

Expand All @@ -80,6 +81,7 @@ class TestServiceIntrospection : public ::testing::Test
rclcpp::Node::SharedPtr node;
rclcpp::Client<BasicTypes>::SharedPtr client;
rclcpp::Service<BasicTypes>::SharedPtr service;
rclcpp::QoS qos_profile_ = rclcpp::QoS(10).reliable();
Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Having the qos reliable and depth 10 for both publishers and subscription for service events to make this test result stable.

Unfortunately even with this setting, it still fails with rmw_connextdds.
I tried to increase the timeout from 1000 to 3000 but still sometimes fails.

colcon test --event-handlers console_direct+ --packages-select rclcpp --ctest-args -R test_service_introspection --retest-until-fail 100
...
74: /root/ros2_ws/colcon_ws/src/ros2/rclcpp/rclcpp/test/rclcpp/test_service_introspection.cpp:200: Failure
74: Expected equality of these values:
74:   events.size()
74:     Which is: 1
74:   2U
74:     Which is: 2
74:
74: [  FAILED  ] TestServiceIntrospection.service_introspection_enable_disable_events (2312 ms)
74: [ RUN      ] TestServiceIntrospection.service_introspection_enable_disable_event_content
74: RTI Connext DDS Non-commercial license is for academic, research, evaluation and personal use only. USE FOR COMMERCIAL PURPOSES IS PROHIBITED. See RTI_LICENSE.TXT for terms. Download free tools at rti.com/ncl. License issued to Non-Commercial User license@rti.com For non-production use only.
74: Expires on 00-jan-00 See www.rti.com for more information.
74: [       OK ] TestServiceIntrospection.service_introspection_enable_disable_event_content (216 ms)
74: [----------] 3 tests from TestServiceIntrospection (2834 ms total)
74:
74: [----------] Global test environment tear-down
74: [==========] 3 tests from 1 test suite ran. (2843 ms total)
74: [  PASSED  ] 2 tests.
74: [  FAILED  ] 1 test, listed below:
74: [  FAILED  ] TestServiceIntrospection.service_introspection_enable_disable_events
74:
74:  1 FAILED TEST
74: -- run_test.py: return code 1
74: -- run_test.py: inject classname prefix into gtest result file '/root/ros2_ws/colcon_ws/build/rclcpp/test_results/rclcpp/test_service_introspection.gtest.xml'
74: -- run_test.py: verify result file '/root/ros2_ws/colcon_ws/build/rclcpp/test_results/rclcpp/test_service_introspection.gtest.xml'
    Test #74: test_service_introspection .......***Failed    2.91 sec

0% tests passed, 1 tests failed out of 1

Label Time Summary:
gmock     =   2.91 sec*proc (1 test)
mimick    =   2.91 sec*proc (1 test)

Total Test time (real) =   8.89 sec

The following tests FAILED:
         74 - test_service_introspection (Failed)
Errors while running CTest
Output from these tests are in: /root/ros2_ws/colcon_ws/build/rclcpp/Testing/Temporary/LastTest.log
Use "--rerun-failed --output-on-failure" to re-run the failed cases verbosely.
--- stderr: rclcpp
Errors while running CTest
Output from these tests are in: /root/ros2_ws/colcon_ws/build/rclcpp/Testing/Temporary/LastTest.log
Use "--rerun-failed --output-on-failure" to re-run the failed cases verbosely.
---
Finished <<< rclcpp [9.07s]     [ with test failures ]

Summary: 1 package finished [10.1s]
  1 package had stderr output: rclcpp
  1 package had test failures: rclcpp

rclcpp::Subscription<BasicTypes::Event>::SharedPtr sub;
std::vector<std::shared_ptr<const BasicTypes::Event>> events;
std::chrono::milliseconds timeout = std::chrono::milliseconds(1000);
Expand All @@ -92,9 +94,9 @@ 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(), qos_profile_, RCL_SERVICE_INTROSPECTION_CONTENTS);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
node->get_clock(), qos_profile_, RCL_SERVICE_INTROSPECTION_CONTENTS);

auto future = client->async_send_request(request);
ASSERT_EQ(
Expand Down Expand Up @@ -163,9 +165,9 @@ 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(), qos_profile_, RCL_SERVICE_INTROSPECTION_OFF);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
node->get_clock(), qos_profile_, RCL_SERVICE_INTROSPECTION_OFF);

auto request = std::make_shared<BasicTypes::Request>();
request->set__bool_value(true);
Expand All @@ -183,9 +185,9 @@ 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(), qos_profile_, RCL_SERVICE_INTROSPECTION_METADATA);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_OFF);
node->get_clock(), qos_profile_, RCL_SERVICE_INTROSPECTION_OFF);

future = client->async_send_request(request);
ASSERT_EQ(
Expand All @@ -200,9 +202,9 @@ 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(), qos_profile_, RCL_SERVICE_INTROSPECTION_OFF);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), qos_profile_, RCL_SERVICE_INTROSPECTION_METADATA);

future = client->async_send_request(request);
ASSERT_EQ(
Expand All @@ -217,9 +219,9 @@ 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(), qos_profile_, RCL_SERVICE_INTROSPECTION_METADATA);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), qos_profile_, RCL_SERVICE_INTROSPECTION_METADATA);

future = client->async_send_request(request);
ASSERT_EQ(
Expand All @@ -235,9 +237,9 @@ 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(), qos_profile_, RCL_SERVICE_INTROSPECTION_METADATA);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), qos_profile_, RCL_SERVICE_INTROSPECTION_METADATA);

auto request = std::make_shared<BasicTypes::Request>();
request->set__bool_value(true);
Expand All @@ -259,9 +261,9 @@ 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(), qos_profile_, RCL_SERVICE_INTROSPECTION_CONTENTS);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_METADATA);
node->get_clock(), qos_profile_, RCL_SERVICE_INTROSPECTION_METADATA);

future = client->async_send_request(request);
ASSERT_EQ(
Expand Down Expand Up @@ -292,9 +294,9 @@ 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(), qos_profile_, RCL_SERVICE_INTROSPECTION_METADATA);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
node->get_clock(), qos_profile_, RCL_SERVICE_INTROSPECTION_CONTENTS);

future = client->async_send_request(request);
ASSERT_EQ(
Expand Down Expand Up @@ -325,9 +327,9 @@ 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(), qos_profile_, RCL_SERVICE_INTROSPECTION_CONTENTS);
service->configure_introspection(
node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS);
node->get_clock(), qos_profile_, RCL_SERVICE_INTROSPECTION_CONTENTS);

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