Skip to content

Commit 496c455

Browse files
authored
Fix bug in timers lifecycle for events executor (#2586)
* Remove expired timers before updating the collection Signed-off-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com> * Add regression test for reinitialized timers bug Signed-off-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com> * Add missing includes Signed-off-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com> * Relocate test under the executors directory Signed-off-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com> * Extend test to run with all supported executors Signed-off-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com> * Adjust comment in fix to make it more generic Signed-off-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com> * Apply ament clang format to test Signed-off-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com> * Fix uncrustify findings Signed-off-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com> --------- Signed-off-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com> Co-authored-by: Alexis Pojomovsky <apojomovsky@ekumenlabs.com>
1 parent 2739327 commit 496c455

File tree

3 files changed

+104
-0
lines changed

3 files changed

+104
-0
lines changed

rclcpp/src/rclcpp/experimental/executors/events_executor/events_executor.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -341,6 +341,11 @@ EventsExecutor::refresh_current_collection(
341341
// Acquire lock before modifying the current collection
342342
std::lock_guard<std::mutex> guard(mutex_);
343343

344+
// Remove expired entities to ensure re-initialized objects
345+
// are updated. This fixes issues with stale state entities.
346+
// See: https://github.com/ros2/rclcpp/pull/2586
347+
current_collection_.remove_expired_entities();
348+
344349
current_collection_.timers.update(
345350
new_collection.timers,
346351
[this](rclcpp::TimerBase::SharedPtr timer) {timers_manager_->add_timer(timer);},

rclcpp/test/rclcpp/CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -450,6 +450,13 @@ if(TARGET test_interface_traits)
450450
target_link_libraries(test_interface_traits ${PROJECT_NAME})
451451
endif()
452452

453+
ament_add_gtest(test_reinitialized_timers
454+
executors/test_reinitialized_timers.cpp
455+
TIMEOUT 30)
456+
if(TARGET test_reinitialized_timers)
457+
target_link_libraries(test_reinitialized_timers ${PROJECT_NAME})
458+
endif()
459+
453460
ament_add_gtest(
454461
test_executors
455462
executors/test_executors.cpp
Lines changed: 92 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
// Copyright 2024 iRobot Corporation.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <gtest/gtest.h>
16+
17+
#include <chrono>
18+
#include <cstddef>
19+
#include <memory>
20+
#include <thread>
21+
22+
#include "rclcpp/executors/multi_threaded_executor.hpp"
23+
#include "rclcpp/executors/single_threaded_executor.hpp"
24+
#include "rclcpp/executors/static_single_threaded_executor.hpp"
25+
#include "rclcpp/experimental/executors/events_executor/events_executor.hpp"
26+
#include "rclcpp/rclcpp.hpp"
27+
28+
template<typename ExecutorType>
29+
class TestTimersLifecycle : public testing::Test
30+
{
31+
public:
32+
void SetUp() override {rclcpp::init(0, nullptr);}
33+
34+
void TearDown() override {rclcpp::shutdown();}
35+
};
36+
37+
using ExecutorTypes = ::testing::Types<
38+
rclcpp::executors::SingleThreadedExecutor, rclcpp::executors::MultiThreadedExecutor,
39+
rclcpp::executors::StaticSingleThreadedExecutor, rclcpp::experimental::executors::EventsExecutor>;
40+
41+
TYPED_TEST_SUITE(TestTimersLifecycle, ExecutorTypes);
42+
43+
TYPED_TEST(TestTimersLifecycle, timers_lifecycle_reinitialized_object)
44+
{
45+
auto timers_period = std::chrono::milliseconds(50);
46+
auto node = std::make_shared<rclcpp::Node>("test_node");
47+
auto executor = std::make_unique<TypeParam>();
48+
49+
executor->add_node(node);
50+
51+
size_t count_1 = 0;
52+
auto timer_1 = rclcpp::create_timer(
53+
node, node->get_clock(), rclcpp::Duration(timers_period), [&count_1]() {count_1++;});
54+
55+
size_t count_2 = 0;
56+
auto timer_2 = rclcpp::create_timer(
57+
node, node->get_clock(), rclcpp::Duration(timers_period), [&count_2]() {count_2++;});
58+
59+
{
60+
std::thread executor_thread([&executor]() {executor->spin();});
61+
62+
while (count_2 < 10u) {
63+
std::this_thread::sleep_for(std::chrono::milliseconds(10));
64+
}
65+
executor->cancel();
66+
executor_thread.join();
67+
68+
EXPECT_GE(count_2, 10u);
69+
EXPECT_LE(count_2 - count_1, 1u);
70+
}
71+
72+
count_1 = 0;
73+
timer_1 = rclcpp::create_timer(
74+
node, node->get_clock(), rclcpp::Duration(timers_period), [&count_1]() {count_1++;});
75+
76+
count_2 = 0;
77+
timer_2 = rclcpp::create_timer(
78+
node, node->get_clock(), rclcpp::Duration(timers_period), [&count_2]() {count_2++;});
79+
80+
{
81+
std::thread executor_thread([&executor]() {executor->spin();});
82+
83+
while (count_2 < 10u) {
84+
std::this_thread::sleep_for(std::chrono::milliseconds(10));
85+
}
86+
executor->cancel();
87+
executor_thread.join();
88+
89+
EXPECT_GE(count_2, 10u);
90+
EXPECT_LE(count_2 - count_1, 1u);
91+
}
92+
}

0 commit comments

Comments
 (0)