From 06e8d84007e9d0c50a764f5a999b5bd218cda3fb Mon Sep 17 00:00:00 2001 From: Ivan Santiago Paunovic Date: Thu, 14 May 2020 10:04:35 -0300 Subject: [PATCH] Actually update timer period Signed-off-by: Ivan Santiago Paunovic --- rclcpp/CMakeLists.txt | 1 - rclcpp/test/executors/test_multi_threaded_executor.cpp | 9 +++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index d7463f7a2a..7e5702cd79 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -604,7 +604,6 @@ if(BUILD_TESTING) ament_target_dependencies(test_multi_threaded_executor "rcl") target_link_libraries(test_multi_threaded_executor ${PROJECT_NAME}) - ament_add_test_label(test_multi_threaded_executor xfail) endif() ament_add_gtest(test_guard_condition test/test_guard_condition.cpp diff --git a/rclcpp/test/executors/test_multi_threaded_executor.cpp b/rclcpp/test/executors/test_multi_threaded_executor.cpp index ce54025ee1..06e3619e3d 100644 --- a/rclcpp/test/executors/test_multi_threaded_executor.cpp +++ b/rclcpp/test/executors/test_multi_threaded_executor.cpp @@ -34,6 +34,10 @@ class TestMultiThreadedExecutor : public ::testing::Test } }; +constexpr double PERIOD = 1.0f; +constexpr double TOLERANCE = 0.25f; +constexpr std::chrono::milliseconds PERIOD_MS = 1000ms; + /* Test that timers are not taken multiple times when using reentrant callback groups. */ @@ -70,9 +74,6 @@ TEST_F(TestMultiThreadedExecutor, timer_over_take) { // While this tolerance is a little wide, if the bug occurs, the next step will // happen almost instantly. The purpose of this test is not to measure the jitter // in timers, just assert that a reasonable amount of time has passed. - const double PERIOD = 1.0f; - const double TOLERANCE = 0.25f; - rclcpp::Time now = system_clock.now(); timer_count++; @@ -93,7 +94,7 @@ TEST_F(TestMultiThreadedExecutor, timer_over_take) { } }; - auto timer = node->create_wall_timer(100ms, timer_callback, cbg); + auto timer = node->create_wall_timer(PERIOD_MS, timer_callback, cbg); executor.add_node(node); executor.spin(); }