Skip to content

Commit 3e7ce76

Browse files
authored
Cleanup test_count_matched test to handle non-DDS RMWs (#1164)
* Make check_state a class method in test_count_matched. This allows us to pass fewer parameters into each each invocation, and allows us to hide some more of the implementation inside the class. * Rename "ops" to "opts" in test_count_matched. It just better reflects what these structures are. * Cleanup pub/subs with a scope_exit in test_count_matched. This just ensures that they are always cleaned up, even if we exit early. Note that we specifically do *not* use it for test_count_matched_functions, since the cleanup is intentionally interleaved with other tests. * Check with the RMW layer to see whether QoS is compatible. Some RMWs may have different compatibility than DDS, so check with the RMW layer to see what we should expect for the number of publishers and subscriptions. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 2b159af commit 3e7ce76

File tree

1 file changed

+137
-117
lines changed

1 file changed

+137
-117
lines changed

rcl/test/rcl/test_count_matched.cpp

Lines changed: 137 additions & 117 deletions
Original file line numberDiff line numberDiff line change
@@ -11,12 +11,16 @@
1111
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
14+
1415
#include <gtest/gtest.h>
1516

1617
#include <chrono>
18+
#include <cstddef>
1719
#include <string>
1820
#include <thread>
1921

22+
#include "osrf_testing_tools_cpp/scope_exit.hpp"
23+
2024
#include "rcl/rcl.h"
2125
#include "rcl/publisher.h"
2226
#include "rcl/subscription.h"
@@ -28,73 +32,11 @@
2832

2933
#include "rcl/error_handling.h"
3034

31-
void check_state(
32-
rcl_wait_set_t * wait_set_ptr,
33-
rcl_publisher_t * publisher,
34-
rcl_subscription_t * subscriber,
35-
const rcl_guard_condition_t * graph_guard_condition,
36-
size_t expected_subscriber_count,
37-
size_t expected_publisher_count,
38-
size_t number_of_tries)
39-
{
40-
size_t subscriber_count = -1;
41-
size_t publisher_count = -1;
42-
43-
rcl_ret_t ret;
44-
45-
for (size_t i = 0; i < number_of_tries; ++i) {
46-
if (publisher) {
47-
ret = rcl_publisher_get_subscription_count(publisher, &subscriber_count);
48-
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
49-
rcl_reset_error();
50-
}
51-
52-
if (subscriber) {
53-
ret = rcl_subscription_get_publisher_count(subscriber, &publisher_count);
54-
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
55-
rcl_reset_error();
56-
}
57-
58-
if (
59-
expected_publisher_count == publisher_count &&
60-
expected_subscriber_count == subscriber_count)
61-
{
62-
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, " state correct!");
63-
break;
64-
}
65-
66-
if ((i + 1) == number_of_tries) {
67-
// Don't wait for the graph to change on the last loop because we won't check again.
68-
continue;
69-
}
70-
71-
ret = rcl_wait_set_clear(wait_set_ptr);
72-
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
73-
ret = rcl_wait_set_add_guard_condition(wait_set_ptr, graph_guard_condition, NULL);
74-
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
75-
std::chrono::nanoseconds time_to_sleep = std::chrono::milliseconds(200);
76-
RCUTILS_LOG_INFO_NAMED(
77-
ROS_PACKAGE_NAME,
78-
" state wrong, waiting up to '%s' nanoseconds for graph changes... ",
79-
std::to_string(time_to_sleep.count()).c_str());
80-
ret = rcl_wait(wait_set_ptr, time_to_sleep.count());
81-
if (ret == RCL_RET_TIMEOUT) {
82-
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "timeout");
83-
continue;
84-
}
85-
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "change occurred");
86-
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
87-
}
88-
EXPECT_EQ(expected_publisher_count, publisher_count);
89-
EXPECT_EQ(expected_subscriber_count, subscriber_count);
90-
}
91-
9235
class TestCountFixture : public ::testing::Test
9336
{
9437
public:
9538
rcl_node_t * node_ptr;
96-
rcl_context_t * context_ptr;
97-
rcl_wait_set_t * wait_set_ptr;
39+
9840
void SetUp()
9941
{
10042
rcl_ret_t ret;
@@ -120,6 +62,8 @@ class TestCountFixture : public ::testing::Test
12062
ret = rcl_wait_set_init(
12163
this->wait_set_ptr, 0, 1, 0, 0, 0, 0, this->context_ptr, rcl_get_default_allocator());
12264
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
65+
66+
graph_guard_condition = rcl_node_get_graph_guard_condition(this->node_ptr);
12367
}
12468

12569
void TearDown()
@@ -141,47 +85,109 @@ class TestCountFixture : public ::testing::Test
14185
delete this->context_ptr;
14286
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
14387
}
88+
89+
protected:
90+
const rcl_guard_condition_t * graph_guard_condition;
91+
rcl_context_t * context_ptr;
92+
rcl_wait_set_t * wait_set_ptr;
93+
94+
void check_state(
95+
rcl_publisher_t * publisher,
96+
rcl_subscription_t * subscriber,
97+
size_t expected_subscriber_count,
98+
size_t expected_publisher_count,
99+
size_t number_of_tries)
100+
{
101+
size_t subscriber_count = -1;
102+
size_t publisher_count = -1;
103+
104+
rcl_ret_t ret;
105+
106+
for (size_t i = 0; i < number_of_tries; ++i) {
107+
if (publisher) {
108+
ret = rcl_publisher_get_subscription_count(publisher, &subscriber_count);
109+
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
110+
rcl_reset_error();
111+
}
112+
113+
if (subscriber) {
114+
ret = rcl_subscription_get_publisher_count(subscriber, &publisher_count);
115+
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
116+
rcl_reset_error();
117+
}
118+
119+
if (
120+
expected_publisher_count == publisher_count &&
121+
expected_subscriber_count == subscriber_count)
122+
{
123+
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "state correct!");
124+
break;
125+
}
126+
127+
if ((i + 1) == number_of_tries) {
128+
// Don't wait for the graph to change on the last loop because we won't check again.
129+
continue;
130+
}
131+
132+
ret = rcl_wait_set_clear(wait_set_ptr);
133+
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
134+
ret = rcl_wait_set_add_guard_condition(wait_set_ptr, graph_guard_condition, NULL);
135+
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
136+
std::chrono::nanoseconds time_to_sleep = std::chrono::milliseconds(200);
137+
RCUTILS_LOG_INFO_NAMED(
138+
ROS_PACKAGE_NAME,
139+
"state wrong, waiting up to '%s' nanoseconds for graph changes... ",
140+
std::to_string(time_to_sleep.count()).c_str());
141+
ret = rcl_wait(wait_set_ptr, time_to_sleep.count());
142+
if (ret == RCL_RET_TIMEOUT) {
143+
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "timeout");
144+
continue;
145+
}
146+
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "change occurred");
147+
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
148+
}
149+
EXPECT_EQ(expected_publisher_count, publisher_count);
150+
EXPECT_EQ(expected_subscriber_count, subscriber_count);
151+
}
144152
};
145153

146-
TEST_F(TestCountFixture, test_count_matched_functions) {
154+
TEST_F(TestCountFixture, test_count_matched_functions)
155+
{
147156
std::string topic_name("/test_count_matched_functions__");
148157
rcl_ret_t ret;
149158

150159
rcl_publisher_t pub = rcl_get_zero_initialized_publisher();
151-
rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options();
160+
rcl_publisher_options_t pub_opts = rcl_publisher_get_default_options();
152161
auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes);
153-
ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_ops);
162+
ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_opts);
154163
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
155164
rcl_reset_error();
156165

157-
const rcl_guard_condition_t * graph_guard_condition =
158-
rcl_node_get_graph_guard_condition(this->node_ptr);
159-
160-
check_state(wait_set_ptr, &pub, nullptr, graph_guard_condition, 0, -1, 9);
166+
check_state(&pub, nullptr, 0, -1, 9);
161167

162168
rcl_subscription_t sub = rcl_get_zero_initialized_subscription();
163-
rcl_subscription_options_t sub_ops = rcl_subscription_get_default_options();
164-
ret = rcl_subscription_init(&sub, this->node_ptr, ts, topic_name.c_str(), &sub_ops);
169+
rcl_subscription_options_t sub_opts = rcl_subscription_get_default_options();
170+
ret = rcl_subscription_init(&sub, this->node_ptr, ts, topic_name.c_str(), &sub_opts);
165171
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
166172
rcl_reset_error();
167173

168-
check_state(wait_set_ptr, &pub, &sub, graph_guard_condition, 1, 1, 9);
174+
check_state(&pub, &sub, 1, 1, 9);
169175

170176
rcl_subscription_t sub2 = rcl_get_zero_initialized_subscription();
171177
rcl_subscription_options_t sub2_ops = rcl_subscription_get_default_options();
172178
ret = rcl_subscription_init(&sub2, this->node_ptr, ts, topic_name.c_str(), &sub2_ops);
173179
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
174180
rcl_reset_error();
175181

176-
check_state(wait_set_ptr, &pub, &sub, graph_guard_condition, 2, 1, 9);
177-
check_state(wait_set_ptr, &pub, &sub2, graph_guard_condition, 2, 1, 9);
182+
check_state(&pub, &sub, 2, 1, 9);
183+
check_state(&pub, &sub2, 2, 1, 9);
178184

179185
ret = rcl_publisher_fini(&pub, this->node_ptr);
180186
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
181187
rcl_reset_error();
182188

183-
check_state(wait_set_ptr, nullptr, &sub, graph_guard_condition, -1, 0, 9);
184-
check_state(wait_set_ptr, nullptr, &sub2, graph_guard_condition, -1, 0, 9);
189+
check_state(nullptr, &sub, -1, 0, 9);
190+
check_state(nullptr, &sub2, -1, 0, 9);
185191

186192
ret = rcl_subscription_fini(&sub, this->node_ptr);
187193
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
@@ -192,66 +198,80 @@ TEST_F(TestCountFixture, test_count_matched_functions) {
192198
rcl_reset_error();
193199
}
194200

195-
TEST_F(TestCountFixture, test_count_matched_functions_mismatched_qos) {
201+
TEST_F(TestCountFixture, test_count_matched_functions_mismatched_qos)
202+
{
196203
std::string topic_name("/test_count_matched_functions_mismatched_qos__");
197204
rcl_ret_t ret;
198205

199206
rcl_publisher_t pub = rcl_get_zero_initialized_publisher();
200207

201-
rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options();
202-
pub_ops.qos.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
203-
pub_ops.qos.depth = 10;
204-
pub_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
205-
pub_ops.qos.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
206-
pub_ops.qos.avoid_ros_namespace_conventions = false;
207-
pub_ops.allocator = rcl_get_default_allocator();
208+
rcl_publisher_options_t pub_opts = rcl_publisher_get_default_options();
209+
pub_opts.qos.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
210+
pub_opts.qos.depth = 10;
211+
pub_opts.qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
212+
pub_opts.qos.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
213+
pub_opts.qos.avoid_ros_namespace_conventions = false;
214+
pub_opts.allocator = rcl_get_default_allocator();
208215

209216
auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes);
210-
ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_ops);
217+
ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_opts);
211218
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
212219
rcl_reset_error();
220+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
221+
{
222+
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&pub, this->node_ptr)) << rcl_get_error_string().str;
223+
});
213224

214-
const rcl_guard_condition_t * graph_guard_condition =
215-
rcl_node_get_graph_guard_condition(this->node_ptr);
216-
217-
check_state(wait_set_ptr, &pub, nullptr, graph_guard_condition, 0, -1, 9);
225+
check_state(&pub, nullptr, 0, -1, 9);
218226

219227
rcl_subscription_t sub = rcl_get_zero_initialized_subscription();
220228

221-
rcl_subscription_options_t sub_ops = rcl_subscription_get_default_options();
222-
sub_ops.qos.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
223-
sub_ops.qos.depth = 10;
224-
sub_ops.qos.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
225-
sub_ops.qos.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
226-
sub_ops.qos.avoid_ros_namespace_conventions = false;
227-
sub_ops.allocator = rcl_get_default_allocator();
229+
rcl_subscription_options_t sub_opts = rcl_subscription_get_default_options();
230+
sub_opts.qos.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
231+
sub_opts.qos.depth = 10;
232+
sub_opts.qos.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
233+
sub_opts.qos.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
234+
sub_opts.qos.avoid_ros_namespace_conventions = false;
235+
sub_opts.allocator = rcl_get_default_allocator();
228236

229-
ret = rcl_subscription_init(&sub, this->node_ptr, ts, topic_name.c_str(), &sub_ops);
237+
ret = rcl_subscription_init(&sub, this->node_ptr, ts, topic_name.c_str(), &sub_opts);
230238
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
231239
rcl_reset_error();
232-
233-
// Expect that no publishers or subscribers should be matched due to qos.
234-
check_state(wait_set_ptr, &pub, &sub, graph_guard_condition, 0, 0, 9);
240+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
241+
{
242+
EXPECT_EQ(RCL_RET_OK,
243+
rcl_subscription_fini(&sub, this->node_ptr)) << rcl_get_error_string().str;
244+
});
245+
246+
rmw_qos_compatibility_type_t compat;
247+
rmw_ret_t rmw_ret =
248+
rmw_qos_profile_check_compatible(pub_opts.qos, sub_opts.qos, &compat, nullptr, 0);
249+
ASSERT_EQ(rmw_ret, RMW_RET_OK);
250+
251+
if (compat == RMW_QOS_COMPATIBILITY_OK) {
252+
check_state(&pub, &sub, 1, 1, 9);
253+
} else {
254+
// Expect that no publishers or subscribers should be matched due to qos.
255+
check_state(&pub, &sub, 0, 0, 9);
256+
}
235257

236258
rcl_subscription_t sub2 = rcl_get_zero_initialized_subscription();
237259
rcl_subscription_options_t sub2_ops = rcl_subscription_get_default_options();
238260
ret = rcl_subscription_init(&sub2, this->node_ptr, ts, topic_name.c_str(), &sub2_ops);
239261
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
240262
rcl_reset_error();
241-
242-
// Even multiple subscribers should not match
243-
check_state(wait_set_ptr, &pub, &sub, graph_guard_condition, 0, 0, 9);
244-
check_state(wait_set_ptr, &pub, &sub2, graph_guard_condition, 0, 0, 9);
245-
246-
ret = rcl_subscription_fini(&sub, this->node_ptr);
247-
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
248-
rcl_reset_error();
249-
250-
ret = rcl_subscription_fini(&sub2, this->node_ptr);
251-
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
252-
rcl_reset_error();
253-
254-
ret = rcl_publisher_fini(&pub, this->node_ptr);
255-
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
256-
rcl_reset_error();
263+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
264+
{
265+
EXPECT_EQ(RCL_RET_OK,
266+
rcl_subscription_fini(&sub2, this->node_ptr)) << rcl_get_error_string().str;
267+
});
268+
269+
if (compat == RMW_QOS_COMPATIBILITY_OK) {
270+
check_state(&pub, &sub, 2, 1, 9);
271+
check_state(&pub, &sub2, 2, 1, 9);
272+
} else {
273+
// Even multiple subscribers should not match
274+
check_state(&pub, &sub, 0, 0, 9);
275+
check_state(&pub, &sub2, 0, 0, 9);
276+
}
257277
}

0 commit comments

Comments
 (0)