Skip to content

Commit f9c4894

Browse files
jmachowinskiJanosch Machowinski
and
Janosch Machowinski
authored
Flaky timer test fix (#2469)
* fix(time_source): Fixed possible race condition Signed-off-by: Janosch Machowinski <j.machowinski@nospam.org> * fix(test_executors_time_cancel_behaviour): Fixed multiple race conditions Signed-off-by: Janosch Machowinski <j.machowinski@nospam.org> --------- Signed-off-by: Janosch Machowinski <j.machowinski@nospam.org> Co-authored-by: Janosch Machowinski <j.machowinski@nospam.org>
1 parent f510db1 commit f9c4894

File tree

2 files changed

+52
-11
lines changed

2 files changed

+52
-11
lines changed

rclcpp/src/rclcpp/time_source.cpp

+9-4
Original file line numberDiff line numberDiff line change
@@ -288,10 +288,10 @@ class TimeSource::NodeState final
288288
// Detach the attached node
289289
void detachNode()
290290
{
291-
std::lock_guard<std::mutex> guard(node_base_lock_);
292291
// destroy_clock_sub() *must* be first here, to ensure that the executor
293292
// can't possibly call any of the callbacks as we are cleaning up.
294293
destroy_clock_sub();
294+
std::lock_guard<std::mutex> guard(node_base_lock_);
295295
clocks_state_.disable_ros_time();
296296
if (on_set_parameters_callback_) {
297297
node_parameters_->remove_on_set_parameters_callback(on_set_parameters_callback_.get());
@@ -409,9 +409,14 @@ class TimeSource::NodeState final
409409
"/clock",
410410
qos_,
411411
[this](std::shared_ptr<const rosgraph_msgs::msg::Clock> msg) {
412-
// We are using node_base_ as an indication if there is a node attached.
413-
// Only call the clock_cb if that is the case.
414-
if (node_base_ != nullptr) {
412+
bool execute_cb = false;
413+
{
414+
std::lock_guard<std::mutex> guard(node_base_lock_);
415+
// We are using node_base_ as an indication if there is a node attached.
416+
// Only call the clock_cb if that is the case.
417+
execute_cb = node_base_ != nullptr;
418+
}
419+
if (execute_cb) {
415420
clock_cb(msg);
416421
}
417422
},

rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp

+43-7
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,16 @@ class TimerNode : public rclcpp::Node
5454
std::bind(&TimerNode::Timer2Callback, this));
5555
}
5656

57-
int GetTimer1Cnt() {return cnt1_;}
58-
int GetTimer2Cnt() {return cnt2_;}
57+
int GetTimer1Cnt()
58+
{
59+
const std::lock_guard<std::mutex> lock(mutex_);
60+
return cnt1_;
61+
}
62+
int GetTimer2Cnt()
63+
{
64+
const std::lock_guard<std::mutex> lock(mutex_);
65+
return cnt2_;
66+
}
5967

6068
void ResetTimer1()
6169
{
@@ -82,16 +90,24 @@ class TimerNode : public rclcpp::Node
8290
private:
8391
void Timer1Callback()
8492
{
85-
cnt1_++;
93+
{
94+
const std::lock_guard<std::mutex> lock(mutex_);
95+
cnt1_++;
96+
}
8697
RCLCPP_DEBUG(this->get_logger(), "Timer 1! (%d)", cnt1_);
8798
}
8899

89100
void Timer2Callback()
90101
{
91-
cnt2_++;
102+
{
103+
const std::lock_guard<std::mutex> lock(mutex_);
104+
cnt2_++;
105+
}
92106
RCLCPP_DEBUG(this->get_logger(), "Timer 2! (%d)", cnt2_);
93107
}
94108

109+
std::mutex mutex_;
110+
95111
rclcpp::TimerBase::SharedPtr timer1_;
96112
rclcpp::TimerBase::SharedPtr timer2_;
97113
int cnt1_ = 0;
@@ -130,6 +146,18 @@ class ClockPublisher : public rclcpp::Node
130146
}
131147
}
132148

149+
bool wait_for_connection(std::chrono::nanoseconds timeout)
150+
{
151+
auto end_time = std::chrono::steady_clock::now() + timeout;
152+
while (clock_publisher_->get_subscription_count() == 0 &&
153+
(std::chrono::steady_clock::now() < end_time))
154+
{
155+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
156+
}
157+
158+
return clock_publisher_->get_subscription_count() != 0;
159+
}
160+
133161
void sleep_for(rclcpp::Duration duration)
134162
{
135163
rclcpp::Time start_time(0, 0, RCL_ROS_TIME);
@@ -148,7 +176,10 @@ class ClockPublisher : public rclcpp::Node
148176
return;
149177
}
150178
std::this_thread::sleep_for(realtime_clock_step_.to_chrono<std::chrono::milliseconds>());
151-
rostime_ += ros_update_duration_;
179+
{
180+
const std::lock_guard<std::mutex> lock(mutex_);
181+
rostime_ += ros_update_duration_;
182+
}
152183
}
153184
}
154185

@@ -163,9 +194,11 @@ class ClockPublisher : public rclcpp::Node
163194

164195
void PublishClock()
165196
{
166-
const std::lock_guard<std::mutex> lock(mutex_);
167197
auto message = rosgraph_msgs::msg::Clock();
168-
message.clock = rostime_;
198+
{
199+
const std::lock_guard<std::mutex> lock(mutex_);
200+
message.clock = rostime_;
201+
}
169202
clock_publisher_->publish(message);
170203
}
171204

@@ -227,6 +260,9 @@ class TestTimerCancelBehavior : public ::testing::Test
227260
[this]() {
228261
executor.spin();
229262
});
263+
264+
EXPECT_TRUE(this->sim_clock_node->wait_for_connection(50ms));
265+
EXPECT_EQ(RCL_ROS_TIME, node->get_clock()->ros_time_is_active());
230266
}
231267

232268
void TearDown()

0 commit comments

Comments
 (0)