Skip to content

Commit 60cbd2c

Browse files
committed
Loop to minimize benchmark overhead in results
1 parent 3e49727 commit 60cbd2c

File tree

5 files changed

+88
-64
lines changed

5 files changed

+88
-64
lines changed

rclpy/test/benchmark/test_benchmark_actions.py

Lines changed: 15 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -13,15 +13,17 @@
1313
# limitations under the License.
1414

1515
from action_msgs.msg import GoalStatus
16-
import pytest
1716
import rclpy
1817
from rclpy.action import ActionClient, ActionServer
1918
from rclpy.executors import SingleThreadedExecutor
20-
from rclpy.qos import qos_profile_services_default, QoSProfile, ReliabilityPolicy
19+
from rclpy.qos import qos_profile_services_default, ReliabilityPolicy
2120
from test_msgs.action import Fibonacci
2221

2322

24-
def test_one_goal(benchmark):
23+
ONE_HUNDRED = 100
24+
25+
26+
def test_one_hundred_goals(benchmark):
2527
context = rclpy.context.Context()
2628
rclpy.init(context=context)
2729
try:
@@ -38,7 +40,7 @@ def test_one_goal(benchmark):
3840

3941
def execute_cb(goal_handle):
4042
goal_handle.succeed()
41-
return response
43+
return Fibonacci.Result()
4244

4345
action_server = ActionServer(
4446
node,
@@ -55,15 +57,16 @@ def execute_cb(goal_handle):
5557
assert action_client.wait_for_server(timeout_sec=5.0)
5658

5759
def bm():
58-
fut = action_client.send_goal_async(Fibonacci.Goal())
59-
executor.spin_until_future_complete(fut)
60-
goal_handle = fut.result() # Raises if there was an error
61-
assert goal_handle.accepted
62-
result_fut= goal_handle.get_result_async()
63-
executor.spin_until_future_complete(result_fut)
64-
return result_fut.result().status
60+
for _ in range(ONE_HUNDRED):
61+
goal_fut = action_client.send_goal_async(Fibonacci.Goal())
62+
executor.spin_until_future_complete(goal_fut)
63+
client_goal_handle = goal_fut.result()
64+
assert client_goal_handle.accepted
65+
result_fut = client_goal_handle.get_result_async()
66+
executor.spin_until_future_complete(result_fut)
67+
assert GoalStatus.STATUS_SUCCEEDED == result_fut.result().status
6568

66-
assert GoalStatus.STATUS_SUCCEEDED == benchmark(bm)
69+
benchmark(bm)
6770

6871
executor.shutdown()
6972
action_client.destroy()

rclpy/test/benchmark/test_benchmark_client_service.py

Lines changed: 10 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -12,14 +12,16 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
import pytest
1615
import rclpy
1716
from rclpy.executors import SingleThreadedExecutor
18-
from rclpy.qos import qos_profile_services_default, QoSProfile, ReliabilityPolicy
17+
from rclpy.qos import qos_profile_services_default, ReliabilityPolicy
1918
from test_msgs.srv import Empty as EmptySrv
2019

2120

22-
def test_one_call(benchmark):
21+
ONE_THOUSAND = 1000
22+
23+
24+
def test_one_thousand_service_calls(benchmark):
2325
context = rclpy.context.Context()
2426
rclpy.init(context=context)
2527
try:
@@ -40,11 +42,12 @@ def cb(_, response):
4042
assert client.wait_for_service(timeout_sec=5.0)
4143

4244
def bm():
43-
fut = client.call_async(EmptySrv.Request())
44-
executor.spin_until_future_complete(fut)
45-
return fut.result() # Raises if there was an error
45+
for _ in range(ONE_THOUSAND):
46+
fut = client.call_async(EmptySrv.Request())
47+
executor.spin_until_future_complete(fut)
48+
assert fut.result() # Raises if there was an error
4649

47-
assert isinstance(benchmark(bm), EmptySrv.Response)
50+
benchmark(bm)
4851

4952
executor.shutdown()
5053
node.destroy_client(client)

rclpy/test/benchmark/test_benchmark_guard_condition.py

Lines changed: 23 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -12,33 +12,37 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
import pytest
1615
import rclpy
1716
from rclpy.executors import SingleThreadedExecutor
1817

1918

20-
def test_one_callback(benchmark):
19+
ONE_THOUSAND = 1000
20+
21+
22+
def test_one_thousand_guard_callbacks(benchmark):
2123
context = rclpy.context.Context()
2224
rclpy.init(context=context)
2325
try:
2426
node = rclpy.create_node('benchmark_many_gc_calls', context=context)
25-
called = False
27+
num_calls = 0
2628

2729
def cb():
28-
nonlocal called
29-
called = True
30+
nonlocal num_calls
31+
num_calls += 1
3032

3133
gc = node.create_guard_condition(cb)
3234

3335
executor = SingleThreadedExecutor(context=context)
3436
executor.add_node(node)
3537

3638
def bm():
37-
nonlocal called
38-
gc.trigger()
39-
while not called:
39+
nonlocal num_calls
40+
# Reset for each benchmark run
41+
num_calls = 0
42+
while num_calls < ONE_THOUSAND:
43+
gc.trigger()
4044
executor.spin_once(timeout_sec=0)
41-
return called
45+
return num_calls == ONE_THOUSAND
4246

4347
assert benchmark(bm)
4448

@@ -49,28 +53,30 @@ def bm():
4953
rclpy.shutdown(context=context)
5054

5155

52-
def test_one_coroutine_callback(benchmark):
56+
def test_one_thousand_guard_coroutine_callbacks(benchmark):
5357
context = rclpy.context.Context()
5458
rclpy.init(context=context)
5559
try:
5660
node = rclpy.create_node('benchmark_many_gc_calls', context=context)
57-
called = False
61+
num_calls = 0
5862

5963
async def coro():
60-
nonlocal called
61-
called = True
64+
nonlocal num_calls
65+
num_calls += 1
6266

6367
gc = node.create_guard_condition(coro)
6468

6569
executor = SingleThreadedExecutor(context=context)
6670
executor.add_node(node)
6771

6872
def bm():
69-
nonlocal called
70-
gc.trigger()
71-
while not called:
73+
nonlocal num_calls
74+
# Reset for each benchmark run
75+
num_calls = 0
76+
while num_calls < ONE_THOUSAND:
77+
gc.trigger()
7278
executor.spin_once(timeout_sec=0)
73-
return called
79+
return num_calls == ONE_THOUSAND
7480

7581
assert benchmark(bm)
7682

rclpy/test/benchmark/test_benchmark_pub_sub.py

Lines changed: 15 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -12,25 +12,29 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
import pytest
1615
import rclpy
1716
from rclpy.executors import SingleThreadedExecutor
1817
from rclpy.qos import QoSProfile, ReliabilityPolicy
1918
from test_msgs.msg import Empty as EmptyMsg
2019

2120

22-
def test_one_message(benchmark):
21+
ONE_THOUSAND = 1000
22+
23+
24+
def test_one_thousand_messages(benchmark):
2325
context = rclpy.context.Context()
2426
rclpy.init(context=context)
2527
try:
2628
node = rclpy.create_node('benchmark_pub_sub', context=context)
2729
qos = QoSProfile(depth=1, reliability=ReliabilityPolicy.RELIABLE)
2830
pub = node.create_publisher(EmptyMsg, 'empty', qos)
29-
called = False
31+
num_calls = 0
3032

3133
def cb(_):
32-
nonlocal called
33-
called = True
34+
nonlocal num_calls
35+
num_calls += 1
36+
# Send next message
37+
pub.publish(EmptyMsg())
3438

3539
sub = node.create_subscription(EmptyMsg, 'empty', cb, qos)
3640

@@ -42,11 +46,14 @@ def cb(_):
4246
executor.spin_once(timeout_sec=0.01)
4347

4448
def bm():
45-
nonlocal called
49+
nonlocal num_calls
50+
# Reset for each benchmark run
51+
num_calls = 0
52+
# Prime the loop with a message
4653
pub.publish(EmptyMsg())
47-
while not called:
54+
while num_calls < ONE_THOUSAND:
4855
executor.spin_once(timeout_sec=0)
49-
return called
56+
return num_calls == ONE_THOUSAND
5057

5158
assert benchmark(bm)
5259

rclpy/test/benchmark/test_benchmark_timer.py

Lines changed: 25 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -12,33 +12,36 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
import pytest
1615
import rclpy
1716
from rclpy.executors import SingleThreadedExecutor
1817

1918

20-
def test_one_callback(benchmark):
19+
ONE_THOUSAND = 1000
20+
21+
22+
def test_one_thousand_timer_coroutine_callbacks(benchmark):
2123
context = rclpy.context.Context()
2224
rclpy.init(context=context)
2325
try:
2426
node = rclpy.create_node('benchmark_many_timer_calls', context=context)
25-
called = False
27+
num_calls = 0
2628

27-
def timer_cb():
28-
nonlocal called
29-
called = True
29+
async def timer_coro():
30+
nonlocal num_calls
31+
num_calls += 1
3032

31-
timer = node.create_timer(0, timer_cb)
33+
timer = node.create_timer(0, timer_coro)
3234

3335
executor = SingleThreadedExecutor(context=context)
3436
executor.add_node(node)
3537

36-
3738
def bm():
38-
nonlocal called
39-
while not called:
39+
nonlocal num_calls
40+
# Reset for each benchmark run
41+
num_calls = 0
42+
while num_calls < ONE_THOUSAND:
4043
executor.spin_once(timeout_sec=0)
41-
return called
44+
return num_calls == ONE_THOUSAND
4245

4346
assert benchmark(bm)
4447

@@ -49,27 +52,29 @@ def bm():
4952
rclpy.shutdown(context=context)
5053

5154

52-
def test_one_coroutine_callback(benchmark):
55+
def test_one_thousand_timer_callbacks(benchmark):
5356
context = rclpy.context.Context()
5457
rclpy.init(context=context)
5558
try:
5659
node = rclpy.create_node('benchmark_many_timer_calls', context=context)
57-
called = False
60+
num_calls = 0
5861

59-
async def timer_coro():
60-
nonlocal called
61-
called = True
62+
def timer_cb():
63+
nonlocal num_calls
64+
num_calls += 1
6265

63-
timer = node.create_timer(0, timer_coro)
66+
timer = node.create_timer(0, timer_cb)
6467

6568
executor = SingleThreadedExecutor(context=context)
6669
executor.add_node(node)
6770

6871
def bm():
69-
nonlocal called
70-
while not called:
72+
nonlocal num_calls
73+
# Reset for each benchmark run
74+
num_calls = 0
75+
while num_calls < ONE_THOUSAND:
7176
executor.spin_once(timeout_sec=0)
72-
return called
77+
return num_calls == ONE_THOUSAND
7378

7479
assert benchmark(bm)
7580

0 commit comments

Comments
 (0)