Skip to content

Commit 1527a9e

Browse files
committed
Add benchmark tests
Signed-off-by: Shane Loretz <[email protected]>
1 parent c4cf7a0 commit 1527a9e

File tree

7 files changed

+387
-0
lines changed

7 files changed

+387
-0
lines changed

rclpy/CMakeLists.txt

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -156,6 +156,11 @@ if(BUILD_TESTING)
156156
if(NOT _typesupport_impls STREQUAL "")
157157
# Run each test in its own pytest invocation to isolate any global state in rclpy
158158
set(_rclpy_pytest_tests
159+
test/benchmark/test_benchmark_actions.py
160+
test/benchmark/test_benchmark_client_service.py
161+
test/benchmark/test_benchmark_guard_condition.py
162+
test/benchmark/test_benchmark_pub_sub.py
163+
test/benchmark/test_benchmark_timer.py
159164
test/test_action_client.py
160165
test/test_action_graph.py
161166
test/test_action_server.py
@@ -198,13 +203,24 @@ if(BUILD_TESTING)
198203
)
199204

200205
foreach(_test_path ${_rclpy_pytest_tests})
206+
if(NOT AMENT_RUN_PERFORMANCE_TESTS)
207+
get_filename_component(_test_dir ${_test_path} DIRECTORY)
208+
get_filename_component(_test_dir ${_test_dir} NAME)
209+
if(_test_dir STREQUAL "benchmark")
210+
set(_SKIP_TEST "SKIP_TEST")
211+
else()
212+
set(_SKIP_TEST "")
213+
endif()
214+
endif()
201215
get_filename_component(_test_name ${_test_path} NAME_WE)
202216
ament_add_pytest_test(${_test_name} ${_test_path}
217+
${_SKIP_TEST}
203218
APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}
204219
PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR}
205220
TIMEOUT 120
206221
WERROR ON
207222
)
223+
# Skip benchmark tests by default
208224
endforeach()
209225
endif()
210226
endif()

rclpy/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@
4444
<test_depend>ament_lint_auto</test_depend>
4545
<test_depend>ament_lint_common</test_depend>
4646
<test_depend>python3-pytest</test_depend>
47+
<test_depend>python3-pytest-benchmark</test_depend>
4748
<test_depend>rosidl_generator_py</test_depend>
4849
<test_depend>test_msgs</test_depend>
4950

Lines changed: 76 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
1+
# Copyright 2022 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from action_msgs.msg import GoalStatus
16+
import rclpy
17+
from rclpy.action import ActionClient, ActionServer
18+
from rclpy.executors import SingleThreadedExecutor
19+
from rclpy.qos import qos_profile_services_default, ReliabilityPolicy
20+
from test_msgs.action import Fibonacci
21+
22+
23+
ONE_HUNDRED = 100
24+
25+
26+
def test_one_hundred_goals(benchmark):
27+
context = rclpy.context.Context()
28+
rclpy.init(context=context)
29+
try:
30+
node = rclpy.create_node('benchmark_actions', context=context)
31+
qos = qos_profile_services_default
32+
qos.reliability = ReliabilityPolicy.RELIABLE
33+
34+
action_client = ActionClient(
35+
node,
36+
Fibonacci,
37+
'benchmark',
38+
goal_service_qos_profile=qos,
39+
result_service_qos_profile=qos)
40+
41+
def execute_cb(goal_handle):
42+
goal_handle.succeed()
43+
return Fibonacci.Result()
44+
45+
action_server = ActionServer(
46+
node,
47+
Fibonacci,
48+
'benchmark',
49+
execute_cb,
50+
goal_service_qos_profile=qos,
51+
result_service_qos_profile=qos)
52+
53+
executor = SingleThreadedExecutor(context=context)
54+
executor.add_node(node)
55+
56+
# Wait for client/server to discover each other
57+
assert action_client.wait_for_server(timeout_sec=5.0)
58+
59+
def bm():
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
68+
69+
benchmark(bm)
70+
71+
executor.shutdown()
72+
action_client.destroy()
73+
action_server.destroy()
74+
node.destroy_node()
75+
finally:
76+
rclpy.shutdown(context=context)
Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
# Copyright 2022 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import rclpy
16+
from rclpy.executors import SingleThreadedExecutor
17+
from rclpy.qos import qos_profile_services_default, ReliabilityPolicy
18+
from test_msgs.srv import Empty as EmptySrv
19+
20+
21+
ONE_THOUSAND = 1000
22+
23+
24+
def test_one_thousand_service_calls(benchmark):
25+
context = rclpy.context.Context()
26+
rclpy.init(context=context)
27+
try:
28+
node = rclpy.create_node('benchmark_client_service', context=context)
29+
qos = qos_profile_services_default
30+
qos.reliability = ReliabilityPolicy.RELIABLE
31+
client = node.create_client(EmptySrv, 'empty', qos_profile=qos)
32+
33+
def cb(_, response):
34+
return response
35+
36+
service = node.create_service(EmptySrv, 'empty', cb, qos_profile=qos)
37+
38+
executor = SingleThreadedExecutor(context=context)
39+
executor.add_node(node)
40+
41+
# Wait for client/service to discover each other
42+
assert client.wait_for_service(timeout_sec=5.0)
43+
44+
def bm():
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
49+
50+
benchmark(bm)
51+
52+
executor.shutdown()
53+
node.destroy_client(client)
54+
node.destroy_service(service)
55+
node.destroy_node()
56+
finally:
57+
rclpy.shutdown(context=context)
Lines changed: 87 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,87 @@
1+
# Copyright 2022 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import rclpy
16+
from rclpy.executors import SingleThreadedExecutor
17+
18+
19+
ONE_THOUSAND = 1000
20+
21+
22+
def test_one_thousand_guard_callbacks(benchmark):
23+
context = rclpy.context.Context()
24+
rclpy.init(context=context)
25+
try:
26+
node = rclpy.create_node('benchmark_many_gc_calls', context=context)
27+
num_calls = 0
28+
29+
def cb():
30+
nonlocal num_calls
31+
num_calls += 1
32+
33+
gc = node.create_guard_condition(cb)
34+
35+
executor = SingleThreadedExecutor(context=context)
36+
executor.add_node(node)
37+
38+
def bm():
39+
nonlocal num_calls
40+
# Reset for each benchmark run
41+
num_calls = 0
42+
while num_calls < ONE_THOUSAND:
43+
gc.trigger()
44+
executor.spin_once(timeout_sec=0)
45+
return num_calls == ONE_THOUSAND
46+
47+
assert benchmark(bm)
48+
49+
executor.shutdown()
50+
node.destroy_guard_condition(gc)
51+
node.destroy_node()
52+
finally:
53+
rclpy.shutdown(context=context)
54+
55+
56+
def test_one_thousand_guard_coroutine_callbacks(benchmark):
57+
context = rclpy.context.Context()
58+
rclpy.init(context=context)
59+
try:
60+
node = rclpy.create_node('benchmark_many_gc_calls', context=context)
61+
num_calls = 0
62+
63+
async def coro():
64+
nonlocal num_calls
65+
num_calls += 1
66+
67+
gc = node.create_guard_condition(coro)
68+
69+
executor = SingleThreadedExecutor(context=context)
70+
executor.add_node(node)
71+
72+
def bm():
73+
nonlocal num_calls
74+
# Reset for each benchmark run
75+
num_calls = 0
76+
while num_calls < ONE_THOUSAND:
77+
gc.trigger()
78+
executor.spin_once(timeout_sec=0)
79+
return num_calls == ONE_THOUSAND
80+
81+
assert benchmark(bm)
82+
83+
executor.shutdown()
84+
node.destroy_guard_condition(gc)
85+
node.destroy_node()
86+
finally:
87+
rclpy.shutdown(context=context)
Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
# Copyright 2022 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import rclpy
16+
from rclpy.executors import SingleThreadedExecutor
17+
from rclpy.qos import QoSProfile, ReliabilityPolicy
18+
from test_msgs.msg import Empty as EmptyMsg
19+
20+
21+
ONE_THOUSAND = 1000
22+
23+
24+
def test_one_thousand_messages(benchmark):
25+
context = rclpy.context.Context()
26+
rclpy.init(context=context)
27+
try:
28+
node = rclpy.create_node('benchmark_pub_sub', context=context)
29+
qos = QoSProfile(depth=1, reliability=ReliabilityPolicy.RELIABLE)
30+
pub = node.create_publisher(EmptyMsg, 'empty', qos)
31+
num_calls = 0
32+
33+
def cb(_):
34+
nonlocal num_calls
35+
num_calls += 1
36+
# Send next message
37+
pub.publish(EmptyMsg())
38+
39+
sub = node.create_subscription(EmptyMsg, 'empty', cb, qos)
40+
41+
executor = SingleThreadedExecutor(context=context)
42+
executor.add_node(node)
43+
44+
# Wait for pub/sub to discover each other
45+
while not pub.get_subscription_count():
46+
executor.spin_once(timeout_sec=0.01)
47+
48+
def bm():
49+
nonlocal num_calls
50+
# Reset for each benchmark run
51+
num_calls = 0
52+
# Prime the loop with a message
53+
pub.publish(EmptyMsg())
54+
while num_calls < ONE_THOUSAND:
55+
executor.spin_once(timeout_sec=0)
56+
return num_calls == ONE_THOUSAND
57+
58+
assert benchmark(bm)
59+
60+
executor.shutdown()
61+
node.destroy_publisher(pub)
62+
node.destroy_subscription(sub)
63+
node.destroy_node()
64+
finally:
65+
rclpy.shutdown(context=context)

0 commit comments

Comments
 (0)