Add timer coverage tests (#1363)

* Add missing tests API
* Reformat style error throw
* Add internal errors tests

Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
This commit is contained in:
Jorge Perez 2020-09-30 17:20:40 -03:00 committed by brawner
parent bcce051eb2
commit 80b2f5439b
3 changed files with 87 additions and 15 deletions

View file

@ -76,8 +76,9 @@ TimerBase::~TimerBase()
void
TimerBase::cancel()
{
if (rcl_timer_cancel(timer_handle_.get()) != RCL_RET_OK) {
throw std::runtime_error(std::string("Couldn't cancel timer: ") + rcl_get_error_string().str);
rcl_ret_t ret = rcl_timer_cancel(timer_handle_.get());
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't cancel timer");
}
}
@ -95,8 +96,9 @@ TimerBase::is_canceled()
void
TimerBase::reset()
{
if (rcl_timer_reset(timer_handle_.get()) != RCL_RET_OK) {
throw std::runtime_error(std::string("Couldn't reset timer: ") + rcl_get_error_string().str);
rcl_ret_t ret = rcl_timer_reset(timer_handle_.get());
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Couldn't reset timer");
}
}
@ -104,8 +106,9 @@ bool
TimerBase::is_ready()
{
bool ready = false;
if (rcl_timer_is_ready(timer_handle_.get(), &ready) != RCL_RET_OK) {
throw std::runtime_error(std::string("Failed to check timer: ") + rcl_get_error_string().str);
rcl_ret_t ret = rcl_timer_is_ready(timer_handle_.get(), &ready);
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to check timer");
}
return ready;
}
@ -114,14 +117,10 @@ std::chrono::nanoseconds
TimerBase::time_until_trigger()
{
int64_t time_until_next_call = 0;
if (
rcl_timer_get_time_until_next_call(
timer_handle_.get(),
&time_until_next_call) != RCL_RET_OK)
{
throw std::runtime_error(
std::string(
"Timer could not get time until next call: ") + rcl_get_error_string().str);
rcl_ret_t ret = rcl_timer_get_time_until_next_call(
timer_handle_.get(), &time_until_next_call);
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(ret, "Timer could not get time until next call");
}
return std::chrono::nanoseconds(time_until_next_call);
}

View file

@ -484,7 +484,7 @@ ament_add_gtest(test_timer rclcpp/test_timer.cpp
if(TARGET test_timer)
ament_target_dependencies(test_timer
"rcl")
target_link_libraries(test_timer ${PROJECT_NAME})
target_link_libraries(test_timer ${PROJECT_NAME} mimick)
endif()
ament_add_gtest(test_time_source rclcpp/test_time_source.cpp

View file

@ -25,6 +25,9 @@
#include "rclcpp/executors/single_threaded_executor.hpp"
#include "rclcpp/rclcpp.hpp"
#include "../mocking_utils/patch.hpp"
#include "../utils/rclcpp_gtest_macros.hpp"
using namespace std::chrono_literals;
/// Timer testing bring up and teardown
@ -207,4 +210,74 @@ TEST_F(TestTimer, callback_with_timer) {
executor->spin_once(std::chrono::milliseconds(10));
}
EXPECT_EQ(timer.get(), timer_ptr);
EXPECT_LE(std::chrono::nanoseconds(0).count(), timer_ptr->time_until_trigger().count());
EXPECT_FALSE(timer_ptr->is_ready());
}
TEST_F(TestTimer, callback_with_period_zero) {
rclcpp::TimerBase * timer_ptr = nullptr;
timer = test_node->create_wall_timer(
std::chrono::milliseconds(0),
[&timer_ptr](rclcpp::TimerBase & timer) {
timer_ptr = &timer;
});
auto start = std::chrono::steady_clock::now();
while (nullptr == timer_ptr &&
(std::chrono::steady_clock::now() - start) < std::chrono::milliseconds(100))
{
executor->spin_once(std::chrono::milliseconds(10));
}
ASSERT_EQ(timer.get(), timer_ptr);
EXPECT_GE(std::chrono::nanoseconds(0).count(), timer_ptr->time_until_trigger().count());
EXPECT_TRUE(timer_ptr->is_ready());
}
/// Test internal failures using mocks
TEST_F(TestTimer, test_failures_with_exceptions)
{
// expect clean state, don't run otherwise
test_initial_conditions(timer, has_timer_run);
{
std::shared_ptr<rclcpp::TimerBase> timer_to_test_destructor;
// Test destructor failure, just logs a msg
auto mock = mocking_utils::inject_on_return("lib:rclcpp", rcl_timer_fini, RCL_RET_ERROR);
EXPECT_NO_THROW(
{
timer_to_test_destructor =
test_node->create_wall_timer(std::chrono::milliseconds(0), [](void) {});
timer_to_test_destructor.reset();
});
}
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_timer_cancel, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
timer->cancel(), std::runtime_error("Couldn't cancel timer: error not set"));
}
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_timer_is_canceled, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
timer->is_canceled(),
std::runtime_error("Couldn't get timer cancelled state: error not set"));
}
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_timer_reset, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
timer->reset(), std::runtime_error("Couldn't reset timer: error not set"));
}
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_timer_is_ready, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
timer->is_ready(), std::runtime_error("Failed to check timer: error not set"));
}
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_timer_get_time_until_next_call, RCL_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
timer->time_until_trigger(),
std::runtime_error("Timer could not get time until next call: error not set"));
}
}