@@ -273,6 +273,117 @@ TEST_F(CreateTimerTest, CreateTimer_MultipleTimers_AllFire)
273273 << " 100ms timer should fire at least as often as 150ms timer" ;
274274}
275275
276+ TEST_F (CreateTimerTest, CreateTimer_MultipleTimers_SimTime_AllFire)
277+ {
278+ auto node = std::make_shared<agnocast::Node>(" test_multiple_timers_sim_time" );
279+
280+ auto clock = node->get_clock ();
281+ rcl_clock_t * rcl_clock = clock->get_clock_handle ();
282+
283+ // Enable ROS time before creating timers
284+ {
285+ std::lock_guard<std::mutex> lock (clock->get_clock_mutex ());
286+ auto ret = rcl_enable_ros_time_override (rcl_clock);
287+ ASSERT_EQ (ret, RCL_RET_OK) << " Failed to enable ros time override" ;
288+ }
289+
290+ // Set initial ROS time to 1s
291+ const rcl_time_point_value_t initial_time = 1000000000LL ;
292+ {
293+ std::lock_guard<std::mutex> lock (clock->get_clock_mutex ());
294+ auto ret = rcl_set_ros_time_override (rcl_clock, initial_time);
295+ ASSERT_EQ (ret, RCL_RET_OK) << " Failed to set initial ros time" ;
296+ }
297+
298+ // Create multiple timers with different periods
299+ std::atomic<int > callback_count_100ms{0 };
300+ std::atomic<int > callback_count_200ms{0 };
301+ std::atomic<int > callback_count_300ms{0 };
302+
303+ auto timer_100ms =
304+ node->create_timer (100ms, [&callback_count_100ms]() { callback_count_100ms++; });
305+ auto timer_200ms =
306+ node->create_timer (200ms, [&callback_count_200ms]() { callback_count_200ms++; });
307+ auto timer_300ms =
308+ node->create_timer (300ms, [&callback_count_300ms]() { callback_count_300ms++; });
309+
310+ // Verify all timers use clock_eventfd (no timerfd since ROS time is active)
311+ {
312+ std::lock_guard<std::mutex> lock (agnocast::id2_timer_info_mtx);
313+ for (const auto & [id, info] : agnocast::id2_timer_info) {
314+ EXPECT_EQ (info->timer_fd , -1 ) << " timer_fd should be -1 when ROS time is active" ;
315+ EXPECT_GE (info->clock_eventfd , 0 ) << " clock_eventfd should be valid" ;
316+ }
317+ }
318+
319+ auto executor = std::make_shared<agnocast::AgnocastOnlySingleThreadedExecutor>();
320+ executor->add_node (node);
321+
322+ std::thread spin_thread ([&executor]() { executor->spin (); });
323+
324+ // Small delay for executor to start
325+ std::this_thread::sleep_for (50ms);
326+
327+ // Forward jump to 1.15s: fires 100ms timer (next_call=1.1s), not others
328+ {
329+ std::lock_guard<std::mutex> lock (clock->get_clock_mutex ());
330+ auto ret = rcl_set_ros_time_override (rcl_clock, 1150000000LL );
331+ ASSERT_EQ (ret, RCL_RET_OK);
332+ }
333+
334+ // Wait for 100ms timer callback
335+ {
336+ const auto deadline = std::chrono::steady_clock::now () + 1s;
337+ while (callback_count_100ms.load () == 0 && std::chrono::steady_clock::now () < deadline) {
338+ std::this_thread::sleep_for (10ms);
339+ }
340+ }
341+ EXPECT_EQ (callback_count_100ms.load (), 1 ) << " 100ms timer should have fired once at 1.15s" ;
342+ EXPECT_EQ (callback_count_200ms.load (), 0 ) << " 200ms timer should not have fired yet" ;
343+ EXPECT_EQ (callback_count_300ms.load (), 0 ) << " 300ms timer should not have fired yet" ;
344+
345+ // Forward jump to 1.25s: fires 100ms timer again (next_call=1.2s), 200ms timer (next_call=1.2s)
346+ {
347+ std::lock_guard<std::mutex> lock (clock->get_clock_mutex ());
348+ auto ret = rcl_set_ros_time_override (rcl_clock, 1250000000LL );
349+ ASSERT_EQ (ret, RCL_RET_OK);
350+ }
351+
352+ // Wait for callbacks
353+ {
354+ const auto deadline = std::chrono::steady_clock::now () + 1s;
355+ while ((callback_count_100ms.load () < 2 || callback_count_200ms.load () < 1 ) &&
356+ std::chrono::steady_clock::now () < deadline) {
357+ std::this_thread::sleep_for (10ms);
358+ }
359+ }
360+ EXPECT_EQ (callback_count_100ms.load (), 2 ) << " 100ms timer should have fired twice by 1.25s" ;
361+ EXPECT_EQ (callback_count_200ms.load (), 1 ) << " 200ms timer should have fired once by 1.25s" ;
362+ EXPECT_EQ (callback_count_300ms.load (), 0 ) << " 300ms timer should not have fired yet" ;
363+
364+ // Forward jump to 1.35s: fires 100ms (next_call=1.3s), 300ms (next_call=1.3s)
365+ {
366+ std::lock_guard<std::mutex> lock (clock->get_clock_mutex ());
367+ auto ret = rcl_set_ros_time_override (rcl_clock, 1350000000LL );
368+ ASSERT_EQ (ret, RCL_RET_OK);
369+ }
370+
371+ // Wait for callbacks
372+ {
373+ const auto deadline = std::chrono::steady_clock::now () + 1s;
374+ while ((callback_count_100ms.load () < 3 || callback_count_300ms.load () < 1 ) &&
375+ std::chrono::steady_clock::now () < deadline) {
376+ std::this_thread::sleep_for (10ms);
377+ }
378+ }
379+ EXPECT_EQ (callback_count_100ms.load (), 3 ) << " 100ms timer should have fired 3 times by 1.35s" ;
380+ EXPECT_EQ (callback_count_200ms.load (), 1 ) << " 200ms timer should still be at 1 by 1.35s" ;
381+ EXPECT_EQ (callback_count_300ms.load (), 1 ) << " 300ms timer should have fired once by 1.35s" ;
382+
383+ executor->cancel ();
384+ spin_thread.join ();
385+ }
386+
276387TEST_F (CreateTimerTest, CreateTimer_RosTimeAlreadyActive)
277388{
278389 auto node = std::make_shared<agnocast::Node>(" test_ros_time_already_active" );
0 commit comments