|
18 | 18 |
|
19 | 19 | import pytest |
20 | 20 | import rclpy |
| 21 | +from rclpy.constants import S_TO_NS |
21 | 22 | from rclpy.executors import SingleThreadedExecutor |
22 | 23 |
|
23 | 24 |
|
@@ -49,7 +50,7 @@ def test_zero_callback(period): |
49 | 50 | executor = SingleThreadedExecutor(context=context) |
50 | 51 | try: |
51 | 52 | executor.add_node(node) |
52 | | - # The first spin_once() takes long enough for 1ms timer tests to fail |
| 53 | + # The first spin_once() takes long enough for 1ms timer tests to fail |
53 | 54 | executor.spin_once(timeout_sec=0) |
54 | 55 |
|
55 | 56 | callbacks = [] |
@@ -78,7 +79,7 @@ def test_number_callbacks(period): |
78 | 79 | executor = SingleThreadedExecutor(context=context) |
79 | 80 | try: |
80 | 81 | executor.add_node(node) |
81 | | - # The first spin_once() takes long enough for 1ms timer tests to fail |
| 82 | + # The first spin_once() takes long enough for 1ms timer tests to fail |
82 | 83 | executor.spin_once(timeout_sec=0) |
83 | 84 |
|
84 | 85 | callbacks = [] |
@@ -110,7 +111,7 @@ def test_cancel_reset(period): |
110 | 111 | executor = SingleThreadedExecutor(context=context) |
111 | 112 | try: |
112 | 113 | executor.add_node(node) |
113 | | - # The first spin_once() takes long enough for 1ms timer tests to fail |
| 114 | + # The first spin_once() takes long enough for 1ms timer tests to fail |
114 | 115 | executor.spin_once(timeout_sec=0) |
115 | 116 |
|
116 | 117 | callbacks = [] |
@@ -148,3 +149,34 @@ def test_cancel_reset(period): |
148 | 149 | node.destroy_node() |
149 | 150 | finally: |
150 | 151 | rclpy.shutdown(context=context) |
| 152 | + |
| 153 | + |
| 154 | +def test_time_until_next_call(): |
| 155 | + node = None |
| 156 | + executor = None |
| 157 | + timer = None |
| 158 | + context = rclpy.context.Context() |
| 159 | + rclpy.init(context=context) |
| 160 | + try: |
| 161 | + node = rclpy.create_node('test_time_until_next_call', context=context) |
| 162 | + executor = SingleThreadedExecutor(context=context) |
| 163 | + executor.add_node(node) |
| 164 | + executor.spin_once(timeout_sec=0) |
| 165 | + timer = node.create_timer(1, lambda: None) |
| 166 | + assert not timer.is_canceled() |
| 167 | + executor.spin_once(0.1) |
| 168 | + assert timer.time_until_next_call() <= (1 * S_TO_NS) |
| 169 | + timer.reset() |
| 170 | + assert not timer.is_canceled() |
| 171 | + assert timer.time_until_next_call() <= (1 * S_TO_NS) |
| 172 | + timer.cancel() |
| 173 | + assert timer.is_canceled() |
| 174 | + assert timer.time_until_next_call() is None |
| 175 | + finally: |
| 176 | + if timer is not None: |
| 177 | + node.destroy_timer(timer) |
| 178 | + if executor is not None: |
| 179 | + executor.shutdown() |
| 180 | + if node is not None: |
| 181 | + node.destroy_node() |
| 182 | + rclpy.shutdown(context=context) |
0 commit comments