Skip to content

Commit

Permalink
Update tests to use new graph API
Browse files Browse the repository at this point in the history
We can simplify some tests by reusing the new graph functions.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Apr 1, 2021
1 parent b1dbca9 commit 466ee6e
Show file tree
Hide file tree
Showing 4 changed files with 41 additions and 166 deletions.
115 changes: 31 additions & 84 deletions rcl/test/rcl/test_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -799,13 +799,11 @@ TEST_F(
void
check_graph_state(
const rcl_node_t * node_ptr,
rcl_wait_set_t * wait_set_ptr,
const rcl_guard_condition_t * graph_guard_condition,
std::string & topic_name,
size_t expected_publisher_count,
size_t expected_subscriber_count,
bool expected_in_tnat,
size_t number_of_tries)
const std::chrono::nanoseconds & timeout)
{
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME,
Expand All @@ -814,78 +812,39 @@ check_graph_state(
expected_subscriber_count,
expected_in_tnat ? "" : " not"
);
size_t publisher_count = 0;
size_t subscriber_count = 0;
bool is_in_tnat = false;
rcl_names_and_types_t tnat {};
rcl_ret_t ret;
rcl_allocator_t allocator = rcl_get_default_allocator();
for (size_t i = 0; i < number_of_tries; ++i) {
ret = rcl_count_publishers(node_ptr, topic_name.c_str(), &publisher_count);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error();

ret = rcl_count_subscribers(node_ptr, topic_name.c_str(), &subscriber_count);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error();

tnat = rcl_get_zero_initialized_names_and_types();
ret = rcl_get_topic_names_and_types(node_ptr, &allocator, false, &tnat);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error();
is_in_tnat = false;
for (size_t i = 0; RCL_RET_OK == ret && i < tnat.names.size; ++i) {
if (topic_name == std::string(tnat.names.data[i])) {
ASSERT_FALSE(is_in_tnat) << "duplicates in the tnat"; // Found it more than once!
is_in_tnat = true;
}
}
if (RCL_RET_OK == ret) {
ret = rcl_names_and_types_fini(&tnat);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error();
}

RCUTILS_LOG_INFO_NAMED(
ROS_PACKAGE_NAME,
" Try %zu: %zu publishers, %zu subscribers, and that the topic is%s in the graph.",
i + 1,
publisher_count,
subscriber_count,
is_in_tnat ? "" : " not"
);
if (
expected_publisher_count == publisher_count &&
expected_subscriber_count == subscriber_count &&
expected_in_tnat == is_in_tnat)
{
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, " state correct!");
break;
}
// Wait for graph change before trying again.
if ((i + 1) == number_of_tries) {
// Don't wait for the graph to change on the last loop because we won't check again.
continue;
}
ret = rcl_wait_set_clear(wait_set_ptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(wait_set_ptr, graph_guard_condition, nullptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
std::chrono::nanoseconds time_to_sleep = std::chrono::milliseconds(400);
RCUTILS_LOG_INFO_NAMED(
ROS_PACKAGE_NAME,
" state wrong, waiting up to '%s' nanoseconds for graph changes... ",
std::to_string(time_to_sleep.count()).c_str());
ret = rcl_wait(wait_set_ptr, time_to_sleep.count());
if (ret == RCL_RET_TIMEOUT) {
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "timeout");
continue;
// Wait for expected number of publishers
bool success = false;
ret = rcl_wait_for_publishers(
node_ptr, &allocator, topic_name.c_str(), expected_publisher_count, timeout.count(), &success);
ASSERT_EQ(ret, RCL_RET_OK);
EXPECT_TRUE(success);
// Wait for expected number of subscribers
success = false;
ret = rcl_wait_for_subscribers(
node_ptr, &allocator, topic_name.c_str(), expected_subscriber_count, timeout.count(), &success);
ASSERT_EQ(ret, RCL_RET_OK);
EXPECT_TRUE(success);

tnat = rcl_get_zero_initialized_names_and_types();
ret = rcl_get_topic_names_and_types(node_ptr, &allocator, false, &tnat);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
is_in_tnat = false;
for (size_t i = 0; RCL_RET_OK == ret && i < tnat.names.size; ++i) {
if (topic_name == std::string(tnat.names.data[i])) {
ASSERT_FALSE(is_in_tnat) << "duplicates in the tnat"; // Found it more than once!
is_in_tnat = true;
}
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "change occurred");
}
if (RCL_RET_OK == ret) {
ret = rcl_names_and_types_fini(&tnat);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}
EXPECT_EQ(expected_publisher_count, publisher_count);
EXPECT_EQ(expected_subscriber_count, subscriber_count);

if (expected_in_tnat) {
EXPECT_TRUE(is_in_tnat);
} else {
Expand Down Expand Up @@ -1235,18 +1194,14 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio
topic_name += std::to_string(now.count());
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Using topic name: %s", topic_name.c_str());
rcl_ret_t ret;
const rcl_guard_condition_t * graph_guard_condition =
rcl_node_get_graph_guard_condition(this->node_ptr);
// First assert the "topic_name" is not in use.
check_graph_state(
this->node_ptr,
this->wait_set_ptr,
graph_guard_condition,
topic_name,
0, // expected publishers on topic
0, // expected subscribers on topic
false, // topic expected in graph
9); // number of retries
std::chrono::seconds(4)); // timeout
// Now create a publisher on "topic_name" and check that it is seen.
rcl_publisher_t pub = rcl_get_zero_initialized_publisher();
rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options();
Expand All @@ -1257,13 +1212,11 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio
// Check the graph.
check_graph_state(
this->node_ptr,
this->wait_set_ptr,
graph_guard_condition,
topic_name,
1, // expected publishers on topic
0, // expected subscribers on topic
true, // topic expected in graph
9); // number of retries
std::chrono::seconds(4)); // timeout
// Now create a subscriber.
rcl_subscription_t sub = rcl_get_zero_initialized_subscription();
rcl_subscription_options_t sub_ops = rcl_subscription_get_default_options();
Expand All @@ -1273,41 +1226,35 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio
// Check the graph again.
check_graph_state(
this->node_ptr,
this->wait_set_ptr,
graph_guard_condition,
topic_name,
1, // expected publishers on topic
1, // expected subscribers on topic
true, // topic expected in graph
9); // number of retries
std::chrono::seconds(4)); // timeout
// Destroy the publisher.
ret = rcl_publisher_fini(&pub, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error();
// Check the graph again.
check_graph_state(
this->node_ptr,
this->wait_set_ptr,
graph_guard_condition,
topic_name,
0, // expected publishers on topic
1, // expected subscribers on topic
true, // topic expected in graph
9); // number of retries
std::chrono::seconds(4)); // timeout
// Destroy the subscriber.
ret = rcl_subscription_fini(&sub, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error();
// Check the graph again.
check_graph_state(
this->node_ptr,
this->wait_set_ptr,
graph_guard_condition,
topic_name,
0, // expected publishers on topic
0, // expected subscribers on topic
false, // topic expected in graph
9); // number of retries
std::chrono::seconds(4)); // timeout
}

/* Test the graph guard condition notices below changes.
Expand Down
12 changes: 10 additions & 2 deletions rcl/test/rcl/test_info_by_topic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -359,7 +359,11 @@ TEST_F(
ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
const std::string fqdn = std::string("/") + this->topic_name;
// Wait until GraphCache publishers are updated
ASSERT_TRUE(wait_for_graph_publication(&this->node, fqdn.c_str(), 1u, 10, 100));
bool success = false;
ret = rcl_wait_for_publishers(
&this->node, &allocator, fqdn.c_str(), 1u, RCUTILS_S_TO_NS(1), &success);
ASSERT_EQ(ret, RCL_RET_OK);
ASSERT_TRUE(success);
// Get publishers info by topic
rmw_topic_endpoint_info_array_t topic_endpoint_info_array_pub =
rmw_get_zero_initialized_topic_endpoint_info_array();
Expand All @@ -375,7 +379,11 @@ TEST_F(
assert_qos_equality(topic_endpoint_info_pub.qos_profile, default_qos_profile, true);

// Wait until GraphCache subcribers are updated
ASSERT_TRUE(wait_for_graph_subscription(&this->node, fqdn.c_str(), 1u, 10, 100));
success = false;
ret = rcl_wait_for_subscribers(
&this->node, &allocator, fqdn.c_str(), 1u, RCUTILS_S_TO_NS(1), &success);
ASSERT_EQ(ret, RCL_RET_OK);
ASSERT_TRUE(success);
// Get subscribers info by topic
rmw_topic_endpoint_info_array_t topic_endpoint_info_array_sub =
rmw_get_zero_initialized_topic_endpoint_info_array();
Expand Down
60 changes: 0 additions & 60 deletions rcl/test/rcl/wait_for_entity_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -236,63 +236,3 @@ wait_for_subscription_to_be_ready(
}
return false;
}

bool
wait_for_graph_publication(
const rcl_node_t * node,
const char * topic_name,
size_t count_to_wait,
size_t max_tries,
int64_t period_ms)
{
if (count_to_wait == 0) {
return true; // Nothing to wait
}
size_t iteration = 0;
while (iteration < max_tries) {
++iteration;
size_t count;
rcl_ret_t ret = rcl_count_publishers(node, topic_name, &count);
if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME,
"Error in rcl_count_publishers: %s", rcl_get_error_string().str);
return false;
}
if (count == count_to_wait) {
return true;
}
std::this_thread::sleep_for(std::chrono::milliseconds(period_ms));
}
return false;
}

bool
wait_for_graph_subscription(
const rcl_node_t * node,
const char * topic_name,
size_t count_to_wait,
size_t max_tries,
int64_t period_ms)
{
if (count_to_wait == 0) {
return true; // Nothing to wait
}
size_t iteration = 0;
while (iteration < max_tries) {
++iteration;
size_t count;
rcl_ret_t ret = rcl_count_subscribers(node, topic_name, &count);
if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME,
"Error in rcl_count_subscribers: %s", rcl_get_error_string().str);
return false;
}
if (count == count_to_wait) {
return true;
}
std::this_thread::sleep_for(std::chrono::milliseconds(period_ms));
}
return false;
}
20 changes: 0 additions & 20 deletions rcl/test/rcl/wait_for_entity_helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,24 +63,4 @@ wait_for_subscription_to_be_ready(
size_t max_tries,
int64_t period_ms);

/// Wait for specified number of publication in GraphCache
/// by trying at most `max_tries` times with a `period_ms` period.
bool
wait_for_graph_publication(
const rcl_node_t * node,
const char * topic_name,
size_t count_to_wait,
size_t max_tries,
int64_t period_ms);

/// Wait for specified number of subcription in GraphCache
/// by trying at most `max_tries` times with a `period_ms` period.
bool
wait_for_graph_subscription(
const rcl_node_t * node,
const char * topic_name,
size_t count_to_wait,
size_t max_tries,
int64_t period_ms);

#endif // RCL__WAIT_FOR_ENTITY_HELPERS_HPP_

0 comments on commit 466ee6e

Please sign in to comment.