Skip to content

Commit

Permalink
Make test logging rosout more reliable (#846)
Browse files Browse the repository at this point in the history
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
  • Loading branch information
ivanpauno authored Oct 28, 2020
1 parent e1480ea commit 980cf85
Showing 1 changed file with 7 additions and 6 deletions.
13 changes: 7 additions & 6 deletions rcl/test/rcl/test_logging_rosout.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,8 @@ class TEST_FIXTURE_P_RMW (TestLoggingRosoutFixture)
};

void
wait_for_subscription_to_be_ready(
check_if_rosout_subscription_gets_a_message(
const char * logger_name,
rcl_subscription_t * subscription,
rcl_context_t * context,
size_t max_tries,
Expand All @@ -159,6 +160,7 @@ wait_for_subscription_to_be_ready(
});
size_t iteration = 0;
do {
RCUTILS_LOG_INFO_NAMED(logger_name, "SOMETHING");
++iteration;
ret = rcl_wait_set_clear(&wait_set);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
Expand All @@ -182,11 +184,10 @@ wait_for_subscription_to_be_ready(
/* Testing the subscriber of topic 'rosout' whether to get event from logging or not.
*/
TEST_P_RMW(TestLoggingRosoutFixture, test_logging_rosout) {
// log
RCUTILS_LOG_INFO_NAMED(rcl_node_get_logger_name(this->node_ptr), "SOMETHING");

bool success;
wait_for_subscription_to_be_ready(this->subscription_ptr, this->context_ptr, 10, 100, success);
bool success = false;
check_if_rosout_subscription_gets_a_message(
rcl_node_get_logger_name(this->node_ptr), this->subscription_ptr,
this->context_ptr, 30, 100, success);
ASSERT_EQ(success, GetParam().expected_success);
}

Expand Down

0 comments on commit 980cf85

Please sign in to comment.