From 8566e7014358560354ca593b3e90f6ef2409357d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Matou=C5=A1=20Vrba?= Date: Thu, 9 May 2024 13:19:22 +0200 Subject: [PATCH] [TimeoutManager]: minor updates --- CMakeLists.txt | 5 +++++ src/timeout_manager/timeout_manager.cpp | 12 ++++++------ test/timeout_manager/test.cpp | 7 ++++++- 3 files changed, 17 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 92dd848c..a902d822 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,6 +16,11 @@ add_definitions(-Wall) add_definitions(-Wextra) add_definitions(-Wpedantic) +# if(CATKIN_ENABLE_TESTING AND MRS_ENABLE_TESTING) +# add_definitions(-fsanitize=address -g3 -fno-omit-frame-pointer) +# add_link_options(-fsanitize=address) +# endif() + if(COVERAGE) message(WARNING "building with --coverage, the performance might be limited") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} --coverage") diff --git a/src/timeout_manager/timeout_manager.cpp b/src/timeout_manager/timeout_manager.cpp index d96a3f1f..98b836a3 100644 --- a/src/timeout_manager/timeout_manager.cpp +++ b/src/timeout_manager/timeout_manager.cpp @@ -16,12 +16,12 @@ namespace mrs_lib const auto new_id = m_timeouts.size(); m_timeouts.emplace_back( timeout_info_t{ - .oneshot = oneshot, - .started = autostart, - .callback = callback, - .timeout = timeout, - .last_reset = last_reset, - .last_callback = last_reset + oneshot, + autostart, + callback, + timeout, + last_reset, + last_reset }); return new_id; } diff --git a/test/timeout_manager/test.cpp b/test/timeout_manager/test.cpp index 264c33fe..6eb530f7 100644 --- a/test/timeout_manager/test.cpp +++ b/test/timeout_manager/test.cpp @@ -21,6 +21,7 @@ struct obj_t // error flags std::mutex mtx; int n_cbks = 0; + int sooner_cbks = 0; bool null_cbk = false; bool cbk_not_running = false; std::atomic_bool cbk_running = false; @@ -63,7 +64,10 @@ struct obj_t const ros::Duration dt = now - last_update; const auto dt_err = dt - desired_dt; if (dt_err < ros::Duration(0)) - ROS_ERROR_STREAM("Callback has a larger/smaller delay than expected: " << dt << "s (should be " << desired_dt << "s). Error: " << dt_err << "s (max. expected: " << max_expected_dt_err << "s)!"); + { + ROS_ERROR_STREAM("Callback called sooner than expected: " << dt << "s (should be " << desired_dt << "s). Error: " << dt_err << "s < 0!"); + sooner_cbks++; + } if (dt_err > max_expected_dt_err) ROS_ERROR_STREAM("Callback has a larger/smaller delay than expected: " << dt << "s (should be " << desired_dt << "s). Error: " << dt_err << "s (max. expected: " << max_expected_dt_err << "s)!"); if (dt_err > max_dt_err || n_cbks == 1) @@ -183,6 +187,7 @@ TEST(TESTSuite, timeout_test) EXPECT_LE(obj.max_dt_err, obj.max_expected_dt_err); EXPECT_LE(obj.avg_dt_err, update_period); + EXPECT_EQ(obj.sooner_cbks, 0); EXPECT_FALSE(callback_while_tm_null); EXPECT_FALSE(callback_while_not_running);