|
| 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) |
0 commit comments