@@ -35,14 +35,20 @@ class TimerNode : public rclcpp::Node
35
35
public:
36
36
explicit TimerNode (std::string subname)
37
37
: Node(" timer_node" , subname)
38
+ {
39
+ }
40
+
41
+ void CreateTimer1 ()
38
42
{
39
43
timer1_ = rclcpp::create_timer (
40
44
this ->get_node_base_interface (), get_node_timers_interface (),
41
45
get_clock (), 1ms,
42
46
std::bind (&TimerNode::Timer1Callback, this ));
47
+ }
43
48
44
- timer2_ =
45
- rclcpp::create_timer (
49
+ void CreateTimer2 ()
50
+ {
51
+ timer2_ = rclcpp::create_timer (
46
52
this ->get_node_base_interface (), get_node_timers_interface (),
47
53
get_clock (), 1ms,
48
54
std::bind (&TimerNode::Timer2Callback, this ));
@@ -76,14 +82,14 @@ class TimerNode : public rclcpp::Node
76
82
private:
77
83
void Timer1Callback ()
78
84
{
79
- RCLCPP_DEBUG (this ->get_logger (), " Timer 1!" );
80
85
cnt1_++;
86
+ RCLCPP_DEBUG (this ->get_logger (), " Timer 1! (%d)" , cnt1_);
81
87
}
82
88
83
89
void Timer2Callback ()
84
90
{
85
- RCLCPP_DEBUG (this ->get_logger (), " Timer 2!" );
86
91
cnt2_++;
92
+ RCLCPP_DEBUG (this ->get_logger (), " Timer 2! (%d)" , cnt2_);
87
93
}
88
94
89
95
rclcpp::TimerBase::SharedPtr timer1_;
@@ -200,11 +206,18 @@ class TestTimerCancelBehavior : public ::testing::Test
200
206
ASSERT_TRUE (param_client->wait_for_service (5s));
201
207
202
208
auto set_parameters_results = param_client->set_parameters (
203
- {rclcpp::Parameter (" use_sim_time" , false )});
209
+ {rclcpp::Parameter (" use_sim_time" , true )});
204
210
for (auto & result : set_parameters_results) {
205
211
ASSERT_TRUE (result.successful );
206
212
}
207
213
214
+ // Check if the clock type is simulation time
215
+ EXPECT_EQ (RCL_ROS_TIME, node->get_clock ()->get_clock_type ());
216
+
217
+ // Create timers
218
+ this ->node ->CreateTimer1 ();
219
+ this ->node ->CreateTimer2 ();
220
+
208
221
// Run standalone thread to publish clock time
209
222
sim_clock_node = std::make_shared<ClockPublisher>();
210
223
@@ -233,7 +246,16 @@ class TestTimerCancelBehavior : public ::testing::Test
233
246
T executor;
234
247
};
235
248
236
- TYPED_TEST_SUITE (TestTimerCancelBehavior, ExecutorTypes, ExecutorTypeNames);
249
+ using MainExecutorTypes =
250
+ ::testing::Types<
251
+ rclcpp::executors::SingleThreadedExecutor,
252
+ rclcpp::executors::MultiThreadedExecutor,
253
+ rclcpp::executors::StaticSingleThreadedExecutor>;
254
+
255
+ // TODO(@fujitatomoya): this test excludes EventExecutor because it does not
256
+ // support simulation time used for this test to relax the racy condition.
257
+ // See more details for https://github.com/ros2/rclcpp/issues/2457.
258
+ TYPED_TEST_SUITE (TestTimerCancelBehavior, MainExecutorTypes, ExecutorTypeNames);
237
259
238
260
TYPED_TEST (TestTimerCancelBehavior, testTimer1CancelledWithExecutorSpin) {
239
261
// Validate that cancelling one timer yields no change in behavior for other
0 commit comments