@@ -54,8 +54,16 @@ class TimerNode : public rclcpp::Node
54
54
std::bind (&TimerNode::Timer2Callback, this ));
55
55
}
56
56
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
+ }
59
67
60
68
void ResetTimer1 ()
61
69
{
@@ -82,16 +90,24 @@ class TimerNode : public rclcpp::Node
82
90
private:
83
91
void Timer1Callback ()
84
92
{
85
- cnt1_++;
93
+ {
94
+ const std::lock_guard<std::mutex> lock (mutex_);
95
+ cnt1_++;
96
+ }
86
97
RCLCPP_DEBUG (this ->get_logger (), " Timer 1! (%d)" , cnt1_);
87
98
}
88
99
89
100
void Timer2Callback ()
90
101
{
91
- cnt2_++;
102
+ {
103
+ const std::lock_guard<std::mutex> lock (mutex_);
104
+ cnt2_++;
105
+ }
92
106
RCLCPP_DEBUG (this ->get_logger (), " Timer 2! (%d)" , cnt2_);
93
107
}
94
108
109
+ std::mutex mutex_;
110
+
95
111
rclcpp::TimerBase::SharedPtr timer1_;
96
112
rclcpp::TimerBase::SharedPtr timer2_;
97
113
int cnt1_ = 0 ;
@@ -130,6 +146,18 @@ class ClockPublisher : public rclcpp::Node
130
146
}
131
147
}
132
148
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
+
133
161
void sleep_for (rclcpp::Duration duration)
134
162
{
135
163
rclcpp::Time start_time (0 , 0 , RCL_ROS_TIME);
@@ -148,7 +176,10 @@ class ClockPublisher : public rclcpp::Node
148
176
return ;
149
177
}
150
178
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
+ }
152
183
}
153
184
}
154
185
@@ -163,9 +194,11 @@ class ClockPublisher : public rclcpp::Node
163
194
164
195
void PublishClock ()
165
196
{
166
- const std::lock_guard<std::mutex> lock (mutex_);
167
197
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
+ }
169
202
clock_publisher_->publish (message);
170
203
}
171
204
@@ -227,6 +260,9 @@ class TestTimerCancelBehavior : public ::testing::Test
227
260
[this ]() {
228
261
executor.spin ();
229
262
});
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 ());
230
266
}
231
267
232
268
void TearDown ()
0 commit comments