Skip to content

Commit a493f18

Browse files
authored
Add tests for 'best available' QoS policies (#501)
* Add tests for 'best available' QoS policies Testing feature added in ros2/rmw#320 for all supported rmw implementations. Test creating a subscription and publisher with 'best available' policies and confirm the actual QoS policies are what we expect (adapting to an existing endpoint). * Add tests for services and clients Signed-off-by: Jacob Perron <[email protected]>
1 parent 83a4e48 commit a493f18

File tree

3 files changed

+161
-1
lines changed

3 files changed

+161
-1
lines changed

test_quality_of_service/CMakeLists.txt

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,10 +18,12 @@ if(BUILD_TESTING)
1818
ament_lint_auto_find_test_dependencies()
1919

2020
find_package(ament_cmake_gtest REQUIRED)
21+
find_package(rcl REQUIRED)
2122
find_package(rclcpp REQUIRED)
2223
find_package(rcutils)
2324
find_package(rmw REQUIRED)
2425
find_package(std_msgs REQUIRED)
26+
find_package(test_msgs REQUIRED)
2527

2628
# get the rmw implementations ahead of time
2729
find_package(rmw_implementation_cmake REQUIRED)
@@ -53,13 +55,14 @@ if(BUILD_TESTING)
5355
target_compile_definitions(${target}${target_suffix}
5456
PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}")
5557
target_link_libraries(${target}${target_suffix} ${PROJECT_NAME}_support)
56-
ament_target_dependencies(${target}${target_suffix} rclcpp rcutils std_msgs)
58+
ament_target_dependencies(${target}${target_suffix} rcl rclcpp rcutils std_msgs test_msgs)
5759
endfunction()
5860

5961
macro(tests)
6062
add_custom_gtest(test_deadline test/test_deadline.cpp)
6163
add_custom_gtest(test_lifespan test/test_lifespan.cpp)
6264
add_custom_gtest(test_liveliness test/test_liveliness.cpp)
65+
add_custom_gtest(test_best_available test/test_best_available.cpp)
6366
endmacro()
6467

6568
call_for_each_rmw_implementation(tests)

test_quality_of_service/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,12 +23,14 @@
2323
<test_depend>ament_cmake_gtest</test_depend>
2424
<test_depend>ament_lint_auto</test_depend>
2525
<test_depend>ament_lint_common</test_depend>
26+
<test_depend>rcl</test_depend>
2627
<test_depend>rclcpp</test_depend>
2728
<test_depend>rcutils</test_depend>
2829
<test_depend>rmw</test_depend>
2930
<test_depend>rmw_implementation</test_depend>
3031
<test_depend>rmw_implementation_cmake</test_depend>
3132
<test_depend>std_msgs</test_depend>
33+
<test_depend>test_msgs</test_depend>
3234

3335
<export>
3436
<build_type>ament_cmake</build_type>
Lines changed: 155 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,155 @@
1+
// Copyright 2022 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <chrono>
16+
#include <functional>
17+
#include <memory>
18+
#include <string>
19+
20+
#include "gtest/gtest.h"
21+
22+
#include "rcl/graph.h"
23+
24+
#include "rclcpp/rclcpp.hpp"
25+
26+
#include "test_msgs/srv/empty.hpp"
27+
28+
#include "test_quality_of_service/qos_test_publisher.hpp"
29+
#include "test_quality_of_service/qos_test_subscriber.hpp"
30+
#include "test_quality_of_service/qos_utilities.hpp"
31+
32+
TEST_F(QosRclcppTestFixture, test_best_available_policies_subscription) {
33+
const std::string topic = "/test_best_available_subscription";
34+
const std::chrono::milliseconds publish_period{5000};
35+
const std::chrono::milliseconds publisher_deadline{2};
36+
const std::chrono::milliseconds publisher_liveliness_lease_duration{3};
37+
38+
rclcpp::QoS publisher_qos_profile(1);
39+
publisher_qos_profile
40+
.best_effort()
41+
.transient_local()
42+
.deadline(publisher_deadline)
43+
.liveliness(rclcpp::LivelinessPolicy::Automatic)
44+
.liveliness_lease_duration(publisher_liveliness_lease_duration);
45+
46+
rclcpp::BestAvailableQoS subscription_qos_profile;
47+
48+
publisher = std::make_shared<QosTestPublisher>(
49+
"publisher", topic, publisher_qos_profile, publish_period);
50+
publisher->toggle();
51+
52+
subscriber = std::make_shared<QosTestSubscriber>(
53+
"subscriber", topic, subscription_qos_profile);
54+
55+
// Wait for discovery before creating subscription
56+
auto allocator = subscriber->get_node_options().allocator();
57+
bool discovery_successful = false;
58+
rcl_ret_t rcl_ret = rcl_wait_for_publishers(
59+
subscriber->get_node_base_interface()->get_rcl_node_handle(),
60+
&allocator,
61+
topic.c_str(),
62+
1u,
63+
static_cast<rcutils_duration_value_t>(5e9), // 5 second timeout
64+
&discovery_successful);
65+
ASSERT_EQ(rcl_ret, RCL_RET_OK) << rcl_get_error_string().str;
66+
ASSERT_TRUE(discovery_successful);
67+
68+
subscriber->toggle();
69+
70+
// Check actual subscription QoS
71+
// We expect it to have exactly the same policies as the publisher for some subset of policies
72+
std::vector<rclcpp::TopicEndpointInfo> subscriptions_info =
73+
subscriber->get_subscriptions_info_by_topic(topic);
74+
ASSERT_EQ(subscriptions_info.size(), 1u);
75+
const auto & actual_qos = subscriptions_info[0].qos_profile();
76+
EXPECT_EQ(actual_qos.reliability(), publisher_qos_profile.reliability());
77+
EXPECT_EQ(actual_qos.durability(), publisher_qos_profile.durability());
78+
EXPECT_EQ(actual_qos.deadline(), publisher_qos_profile.deadline());
79+
EXPECT_EQ(actual_qos.liveliness(), publisher_qos_profile.liveliness());
80+
EXPECT_EQ(
81+
actual_qos.liveliness_lease_duration(), publisher_qos_profile.liveliness_lease_duration());
82+
}
83+
84+
TEST_F(QosRclcppTestFixture, test_best_available_policies_publisher) {
85+
const std::string topic = "/test_best_available_publisher";
86+
const std::chrono::milliseconds publish_period{5000};
87+
const std::chrono::milliseconds subscription_deadline{2};
88+
const std::chrono::milliseconds subscription_liveliness_lease_duration{3};
89+
90+
rclcpp::QoS subscription_qos_profile(1);
91+
subscription_qos_profile
92+
.best_effort()
93+
.durability_volatile()
94+
.deadline(subscription_deadline)
95+
.liveliness(rclcpp::LivelinessPolicy::ManualByTopic)
96+
.liveliness_lease_duration(subscription_liveliness_lease_duration);
97+
98+
rclcpp::BestAvailableQoS publisher_qos_profile;
99+
100+
publisher = std::make_shared<QosTestPublisher>(
101+
"publisher", topic, publisher_qos_profile, publish_period);
102+
103+
subscriber = std::make_shared<QosTestSubscriber>(
104+
"subscriber", topic, subscription_qos_profile);
105+
subscriber->toggle();
106+
107+
// Wait for discovery before creating publisher
108+
auto allocator = publisher->get_node_options().allocator();
109+
bool discovery_successful = false;
110+
rcl_ret_t rcl_ret = rcl_wait_for_subscribers(
111+
publisher->get_node_base_interface()->get_rcl_node_handle(),
112+
&allocator,
113+
topic.c_str(),
114+
1u,
115+
static_cast<rcutils_duration_value_t>(5e9), // 5 second timeout
116+
&discovery_successful);
117+
ASSERT_EQ(rcl_ret, RCL_RET_OK) << rcl_get_error_string().str;
118+
ASSERT_TRUE(discovery_successful);
119+
120+
publisher->toggle();
121+
122+
// Check actual publisher QoS
123+
// We expect it to have exactly the same policies as the publisher for some subset of policies
124+
// However, it should always be reliable and transient local (for DDS middlewares)
125+
std::vector<rclcpp::TopicEndpointInfo> publishers_info =
126+
publisher->get_publishers_info_by_topic(topic);
127+
128+
ASSERT_EQ(publishers_info.size(), 1u);
129+
const auto & actual_qos = publishers_info[0].qos_profile();
130+
EXPECT_EQ(actual_qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
131+
EXPECT_EQ(actual_qos.durability(), rclcpp::DurabilityPolicy::TransientLocal);
132+
EXPECT_EQ(actual_qos.deadline(), subscription_qos_profile.deadline());
133+
EXPECT_EQ(actual_qos.liveliness(), subscription_qos_profile.liveliness());
134+
EXPECT_EQ(
135+
actual_qos.liveliness_lease_duration(), subscription_qos_profile.liveliness_lease_duration());
136+
}
137+
138+
TEST_F(QosRclcppTestFixture, test_best_available_policies_services) {
139+
// Test no errors occur when creating a service with best available policies
140+
rclcpp::Node node("test_create_service_with_best_available_policies");
141+
node.create_service<test_msgs::srv::Empty>(
142+
"test_best_available_service",
143+
[](
144+
std::shared_ptr<rmw_request_id_t>,
145+
std::shared_ptr<test_msgs::srv::Empty::Request>,
146+
std::shared_ptr<test_msgs::srv::Empty::Response>) {},
147+
rmw_qos_profile_best_available);
148+
}
149+
150+
TEST_F(QosRclcppTestFixture, test_best_available_policies_clients) {
151+
// Test no errors occur when creating a client with best available policies
152+
rclcpp::Node node("test_create_client_with_best_available_policies");
153+
node.create_client<test_msgs::srv::Empty>(
154+
"test_best_available_client", rmw_qos_profile_best_available);
155+
}

0 commit comments

Comments
 (0)