From 6d225607eb6020cae0cc685e12483f2136926330 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Fri, 2 Aug 2024 20:01:01 +0300 Subject: [PATCH 1/5] Switched to moveit's own dockerfile and fixed dependency repos (#16) * Fixed dockerfile and dependencies. Middlewares were added as dependencies. (rmw_fastrtps, rmw_zenoh, rmw_cyclonedds) * Used moveit's own docker image instead of building it * Used moveit's latest rolling docker image * re-edited underlay workspace in dockerfile * Changed workspace dirs in dockerfile with moveit docker's own underlay workspace alias --- Dockerfile | 15 ++++++--------- moveit_middleware_benchmark.repos | 12 ++++++++---- 2 files changed, 14 insertions(+), 13 deletions(-) diff --git a/Dockerfile b/Dockerfile index ff7281a..a66f927 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,4 +1,4 @@ -FROM ros:rolling +FROM moveit/moveit2:rolling-source RUN apt-get update && \ apt install wget -y @@ -6,20 +6,17 @@ RUN apt-get update && \ RUN mkdir ws/src -p RUN . /opt/ros/rolling/setup.sh && \ - cd ws/src && \ - git clone https://github.com/CihatAltiparmak/moveit_middleware_benchmark.git -b development && \ + cd ${ROS_UNDERLAY}/../src && \ + git clone https://github.com/CihatAltiparmak/moveit_middleware_benchmark.git && \ vcs import < moveit_middleware_benchmark/moveit_middleware_benchmark.repos --recursive -RUN cd ws/src && \ - # git clone https://github.com/ros2/rmw_zenoh.git && \ - git clone https://github.com/ros2/rmw_cyclonedds.git - RUN . /opt/ros/rolling/setup.sh && \ - cd ws && \ + cd ${ROS_UNDERLAY}/.. && \ rosdep update --rosdistro=$ROS_DISTRO && \ apt-get update && \ + apt upgrade -y && \ rosdep install --from-paths src --ignore-src -r -y RUN . /opt/ros/rolling/setup.sh && \ - cd ws && \ + cd ${ROS_UNDERLAY}/.. && \ colcon build --mixin release --packages-skip test_dynmsg dynmsg_demo diff --git a/moveit_middleware_benchmark.repos b/moveit_middleware_benchmark.repos index 53423c1..58ac283 100644 --- a/moveit_middleware_benchmark.repos +++ b/moveit_middleware_benchmark.repos @@ -1,8 +1,4 @@ repositories: - moveit_msgs: - type: git - url: https://github.com/moveit/moveit2.git - version: main moveit_resources: type: git url: https://github.com/moveit/moveit_resources.git @@ -11,6 +7,14 @@ repositories: type: git url: https://github.com/ros2/rmw_zenoh.git version: rolling + rmw_cyclonedds: + type: git + url: https://github.com/ros2/rmw_cyclonedds.git + version: rolling + rmw_fastrtps: + type: git + url: https://github.com/ros2/rmw_fastrtps.git + version: rolling dynamic_message_introspection: type: git url: https://github.com/osrf/dynamic_message_introspection.git From 1a3ce3a3807db83480ae6fe2d948cbbc2170c646 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Mon, 5 Aug 2024 14:56:38 +0300 Subject: [PATCH 2/5] Set fail-fast param in github action jobs as false (#23) - Github CIes are sometimes failed without any reason --- .github/workflows/create_docker_image.yml | 2 ++ .github/workflows/industrial_ci.yml | 1 + .github/workflows/run_benchmarks.yml | 2 ++ .github/workflows/test_moveit_middleware_benchmark_action.yml | 2 ++ 4 files changed, 7 insertions(+) diff --git a/.github/workflows/create_docker_image.yml b/.github/workflows/create_docker_image.yml index 652e6ea..8e4e5f8 100644 --- a/.github/workflows/create_docker_image.yml +++ b/.github/workflows/create_docker_image.yml @@ -6,6 +6,8 @@ jobs: build_and_push_docker_image: name: build runs-on: ubuntu-latest + strategy: + fail-fast: false permissions: contents: read packages: write diff --git a/.github/workflows/industrial_ci.yml b/.github/workflows/industrial_ci.yml index d0f22c3..2971a45 100644 --- a/.github/workflows/industrial_ci.yml +++ b/.github/workflows/industrial_ci.yml @@ -6,6 +6,7 @@ jobs: industrial_ci: name: ROS ${{ matrix.ROS_DISTRO }} (${{ matrix.ROS_REPO }}) strategy: + fail-fast: false matrix: ROS_DISTRO: [rolling] ROS_REPO: [testing, main] diff --git a/.github/workflows/run_benchmarks.yml b/.github/workflows/run_benchmarks.yml index 9f87da6..be2a9d4 100644 --- a/.github/workflows/run_benchmarks.yml +++ b/.github/workflows/run_benchmarks.yml @@ -6,6 +6,8 @@ jobs: run_middleware_benchmarks: name: run_benchmarks runs-on: ubuntu-latest + strategy: + fail-fast: false permissions: contents: write deployments: write diff --git a/.github/workflows/test_moveit_middleware_benchmark_action.yml b/.github/workflows/test_moveit_middleware_benchmark_action.yml index b152d3f..3f717b5 100644 --- a/.github/workflows/test_moveit_middleware_benchmark_action.yml +++ b/.github/workflows/test_moveit_middleware_benchmark_action.yml @@ -6,6 +6,8 @@ jobs: moveit_middleware_benchmark_github_action_test: name: build runs-on: ubuntu-latest + strategy: + fail-fast: false steps: - uses: actions/checkout@v2 - uses: ./ From 1bb59171d4f9c686745acf1638875fdebe1af912 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Mon, 5 Aug 2024 17:21:12 +0300 Subject: [PATCH 3/5] Implemented the benchmark to observe the effect of middleware over service-client jobs (#18) * Implemented the benchmark to observe the effect of middleware over service-client jobs * Fixed dependency typo for demo_nodes_cpp * Added the relavant documentation for basic service client benchmarking scenario * Fix typo in basic_service_client_bechmark documentation * Fix typos docs/how_to_run.md Co-authored-by: Sebastian Jahr * Fix ROS 2 typo in the doc Co-authored-by: Sebastian Jahr * Kept documentation short for constructor of ScenarioBasicServiceClient class ( see https://github.com/CihatAltiparmak/moveit_middleware_benchmark/pull/18#discussion_r1702106816 ) * Passed node parameter in const & type. See ( https://github.com/CihatAltiparmak/moveit_middleware_benchmark/pull/18#discussion_r1702107562 ) * Eexcuted add_two_ints_server in Node instead of ExecuteProcess. - ExecuteProcess runs two process which are sh and ros2_node, if there is no signal handler for SIGINT, SIGTERM etc. when sh is terminated, some process may continue to run without killing. * Added service client benchmark to readme --------- Co-authored-by: Sebastian Jahr --- CMakeLists.txt | 28 +++- README.md | 1 + docs/how_to_run.md | 6 + .../basic_service_client_benchmark.md | 38 ++++++ .../scenario_basic_service_client.hpp | 96 ++++++++++++++ ...o_basic_service_client_benchmark.launch.py | 62 +++++++++ package.xml | 2 + ...io_basic_service_client_benchmark_main.cpp | 50 +++++++ .../scenario_basic_service_client.cpp | 124 ++++++++++++++++++ 9 files changed, 406 insertions(+), 1 deletion(-) create mode 100644 docs/scenarios/basic_service_client_benchmark.md create mode 100644 include/moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp create mode 100644 launch/scenario_basic_service_client_benchmark.launch.py create mode 100644 src/scenario_basic_service_client_benchmark_main.cpp create mode 100644 src/scenarios/scenario_basic_service_client.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 06d4872..ac991b4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,6 +14,8 @@ find_package(dynmsg REQUIRED) find_package(nav_msgs REQUIRED) find_package(ament_index_cpp REQUIRED) find_package(yaml-cpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(example_interfaces REQUIRED) add_executable( scenario_perception_pipeline_benchmark_main @@ -28,7 +30,8 @@ ament_target_dependencies( "benchmark" "dynmsg" "nav_msgs" - "yaml-cpp") + "yaml-cpp" + "example_interfaces") target_include_directories( scenario_perception_pipeline_benchmark_main @@ -38,7 +41,30 @@ target_include_directories( target_link_libraries(scenario_perception_pipeline_benchmark_main PUBLIC "benchmark::benchmark" ${YAML_CPP_LIBRARIES}) +add_executable( + scenario_basic_service_client_benchmark_main + src/scenario_basic_service_client_benchmark_main.cpp + src/scenarios/scenario_basic_service_client.cpp) + +ament_target_dependencies( + scenario_basic_service_client_benchmark_main + PUBLIC + "moveit_ros_planning_interface" + "rclcpp" + "benchmark" + "std_msgs" + "example_interfaces") + +target_include_directories( + scenario_basic_service_client_benchmark_main + PUBLIC $ + $) + +target_link_libraries(scenario_basic_service_client_benchmark_main + PUBLIC "benchmark::benchmark" ${YAML_CPP_LIBRARIES}) + install(TARGETS scenario_perception_pipeline_benchmark_main + scenario_basic_service_client_benchmark_main DESTINATION lib/moveit_middleware_benchmark) install(DIRECTORY launch config DESTINATION share/moveit_middleware_benchmark) diff --git a/README.md b/README.md index 00b7a7e..69c3eed 100644 --- a/README.md +++ b/README.md @@ -9,6 +9,7 @@ Under Construction This middleware benchmark tool aims to measure middleware effects on various scenarios like perception pipeline in MoveIt. There is a following list to see scenarios and how to measure the effects of middleware. * [Perception Pipeline](./docs/scenarios/perception_pipeline_benchmark.md) +* [Basic Service Client Works](./docs/scenarios/basic_service_client_benchmark.md) ## Getting Started diff --git a/docs/how_to_run.md b/docs/how_to_run.md index 2e894d6..db915ad 100644 --- a/docs/how_to_run.md +++ b/docs/how_to_run.md @@ -7,3 +7,9 @@ This benchmark measures the elapsed time by which the determined path is sent fo Firstly, `node` and `move_group_interface`in SetUp are created before each benchmark. `poses` inside `nav_msgs/msg/Path` is sent one by one to plan trajectory for robot. If planning is failed, only `failure_rate` is increased. If planning is successful, the trajectory_plan which move_group_server plan is sent via `move_group_interface` to start the execution of this planned trajectory. Then `success_number` is increased. For instance, the selected test_case includes 20 goal poses. These 20 goals is sent one by one to `move_group_server`. If the 5 goal poses out of 20 goal poses are failed, `success_number` equals 15 and `failure_number` equals 5. `success_number` and `failure_number` is important to observe the middlewares' behaviours. + +### [Basic Service Client Works Benchmark](scenarios/basic_service_client_benchmark.md) + +This benchmark measures the total elapsed time based on the time interval between sending the request by the client to the server and getting the response of server. This benchmark utilizes the [ros2/demos](https://github.com/ros2/demos) packages' [example server](https://github.com/ros2/demos/blob/rolling/demo_nodes_cpp/src/services/add_two_ints_server.cpp). + +In this benchmark scenario, the benchmarker node only has client interface. The necessary server for this client is run in [the launch file of this benchmark scenario](../launch/scenario_basic_service_client_benchmark.launch.py). Client sends a request to server and waits for the response from server. Client sends second request to server once the client receives response of first request from client. This actions are repeated `sending_request_number` times. You can configure this `sending_request_number` parameter in [this scenario's launch file]((../launch/scenario_basic_service_client_benchmark.launch.py)). diff --git a/docs/scenarios/basic_service_client_benchmark.md b/docs/scenarios/basic_service_client_benchmark.md new file mode 100644 index 0000000..a0ba2a6 --- /dev/null +++ b/docs/scenarios/basic_service_client_benchmark.md @@ -0,0 +1,38 @@ +## How To Run Basic Service Client Benchmark + +Firstly, source your ros version. It's suggested to test with rolling version of ROS 2. + +For instance, to test with rmw_zenoh, start to zenoh router using following command in the terminal. +```sh +# go to your workspace +cd ws +# Be sure that ros2 daemon is killed. +pkill -9 -f ros && ros2 daemon stop +# Then start zenoh router +source /opt/ros/rolling/setup.bash +source install/setup.bash +export RMW_IMPLEMENTATION=rmw_zenoh_cpp +ros2 run rmw_zenoh_cpp rmw_zenohd +``` + +Select your rmw_implementation as `rmw_zenoh_cpp` and run the perception benchmark launch file in the another terminal. +```sh +# go to your workspace +cd ws +source /opt/ros/rolling/setup.bash +source install/setup.bash +export RMW_IMPLEMENTATION=rmw_zenoh_cpp # select your rmw_implementation to benchmark +ros2 launch moveit_middleware_benchmark scenario_basic_service_client_benchmark.launch.py +``` + +It will be defaultly benchmarked with 6 repetitions. It will be created the json file named `middleware_benchmark_results.json` for benchmarking results after finishing benchmark code execution. You can see the benchmark results in more detail inside this json file. + +If you want to customize your benchmark arguments or select different test case, you can use below command. + +```shell +ros2 launch moveit_middleware_benchmark scenario_basic_service_client_benchmark.launch.py benchmark_command_args:="--benchmark_out=middleware_benchmark_results.json --benchmark_out_format=json --benchmark_repetitions=1" sending_request_number:=50000 +``` + +## How to benchmark the basic service client execution + +The main idea here is to send some client request in `example_interfaces::srv::AddTwoInts` format to `add_two_ints_server` which is one of the examples of [ros2/demos package](https://github.com/ros2/demos) and then to measure the elapsed time by waiting response from server. This logic helps us to measure elapsed time between sending request and receiving response. diff --git a/include/moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp b/include/moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp new file mode 100644 index 0000000..31c98b7 --- /dev/null +++ b/include/moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp @@ -0,0 +1,96 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2024, Cihat Kurtuluş Altıparmak + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of PickNik Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Cihat Kurtuluş Altıparmak + Description: Benchmarking module to compare the effects of middlewares + against basic service client works + */ + +#pragma once + +#include +#include +#include +#include +#include +#include + +#include + +namespace moveit +{ +namespace middleware_benchmark +{ + +class ScenarioBasicServiceClient +{ +public: + /** \brief Constructor + * \param [in] node The ros node for sending request and wait response from server + */ + ScenarioBasicServiceClient(const rclcpp::Node::SharedPtr& node); + + /** \brief the method to send the requests \e sending_request_number times + * \param [in] sending_request_number the number for how many request is sent by client + */ + void runTestCase(const int& sending_request_number); + +private: + rclcpp::Node::SharedPtr node_; + rclcpp::Client::SharedPtr client_; +}; + +class ScenarioBasicServiceClientFixture : public benchmark::Fixture +{ +public: + ScenarioBasicServiceClientFixture(); + + /** \brief This method runs once each benchmark starts + * \param [in] state + */ + void SetUp(::benchmark::State& /*state*/); + + /** \brief This method runs as soon as each benchmark finishes + * \param [in] state + */ + void TearDown(::benchmark::State& /*state*/); + +protected: + rclcpp::Node::SharedPtr node_; + /* The number to send request to server */ + int sending_request_number_; +}; + +} // namespace middleware_benchmark +} // namespace moveit diff --git a/launch/scenario_basic_service_client_benchmark.launch.py b/launch/scenario_basic_service_client_benchmark.launch.py new file mode 100644 index 0000000..9ab7b1d --- /dev/null +++ b/launch/scenario_basic_service_client_benchmark.launch.py @@ -0,0 +1,62 @@ +import os +from launch import LaunchDescription +from launch.substitutions import LaunchConfiguration +from ament_index_python.packages import get_package_share_directory +from launch.actions import ( + DeclareLaunchArgument, + ExecuteProcess, + Shutdown, + OpaqueFunction, +) +from launch_ros.substitutions import FindPackageShare +from launch_ros.actions import Node + + +def launch_setup(context, *args, **kwargs): + benchmark_command_args = context.perform_substitution( + LaunchConfiguration("benchmark_command_args") + ).split() + + sending_request_number = int( + context.perform_substitution(LaunchConfiguration("sending_request_number")) + ) + + add_two_ints_server_node = Node( + name="add_two_ints_server", + package="demo_nodes_cpp", + executable="add_two_ints_server", + ) + + benchmark_main_node = Node( + name="benchmark_main", + package="moveit_middleware_benchmark", + executable="scenario_basic_service_client_benchmark_main", + output="both", + arguments=benchmark_command_args, + parameters=[ + {"sending_request_number": sending_request_number}, + ], + on_exit=Shutdown(), + ) + + return [add_two_ints_server_node, benchmark_main_node] + + +def generate_launch_description(): + declared_arguments = [] + + benchmark_command_args = DeclareLaunchArgument( + "benchmark_command_args", + default_value="--benchmark_out=middleware_benchmark_results.json --benchmark_out_format=json --benchmark_repetitions=6", + description="Google Benchmark Tool Arguments", + ) + declared_arguments.append(benchmark_command_args) + + sending_request_number_arg = DeclareLaunchArgument( + "sending_request_number", default_value="10000" + ) + declared_arguments.append(sending_request_number_arg) + + return LaunchDescription( + declared_arguments + [OpaqueFunction(function=launch_setup)] + ) diff --git a/package.xml b/package.xml index 13e3fe6..750482e 100644 --- a/package.xml +++ b/package.xml @@ -16,10 +16,12 @@ nav_msgs ament_index_cpp yaml-cpp + example_interfaces rmw_zenoh_cpp rmw_fastrtps_cpp rmw_cyclonedds_cpp + demo_nodes_cpp ament_lint_auto ament_lint_common diff --git a/src/scenario_basic_service_client_benchmark_main.cpp b/src/scenario_basic_service_client_benchmark_main.cpp new file mode 100644 index 0000000..6653d55 --- /dev/null +++ b/src/scenario_basic_service_client_benchmark_main.cpp @@ -0,0 +1,50 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2024, Cihat Kurtuluş Altıparmak + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of PickNik Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Cihat Kurtuluş Altıparmak + Description: Benchmarking module to compare the effects of middlewares + against basic service client works + */ + +#include "moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp" + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + benchmark::Initialize(&argc, argv); + benchmark::RunSpecifiedBenchmarks(); + benchmark::Shutdown(); + rclcpp::shutdown(); + return 0; +} diff --git a/src/scenarios/scenario_basic_service_client.cpp b/src/scenarios/scenario_basic_service_client.cpp new file mode 100644 index 0000000..5141b0c --- /dev/null +++ b/src/scenarios/scenario_basic_service_client.cpp @@ -0,0 +1,124 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2024, Cihat Kurtuluş Altıparmak + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of PickNik Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Cihat Kurtuluş Altıparmak + Description: Benchmarking module to compare the effects of middlewares + against basic service client works + */ + +#include "moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp" + +namespace moveit +{ +namespace middleware_benchmark +{ + +using namespace std::chrono_literals; + +ScenarioBasicServiceClient::ScenarioBasicServiceClient(const rclcpp::Node::SharedPtr& node) : node_(node) +{ + client_ = node_->create_client("add_two_ints"); + + if (!client_->wait_for_service(5s)) + { + RCLCPP_FATAL(node_->get_logger(), "Server is not available !"); + } + + // TODO @CihatAltiparmak : add this time stopings to + // perception pipeline benchmark as well + // It should be waited even if server is okay due + // to the fact that server sometimes doesn't response + // request we sent in case that client sent request once server is ready + std::this_thread::sleep_for(1s); +} + +void ScenarioBasicServiceClient::runTestCase(const int& sending_request_number) +{ + for (int i = 0; i < sending_request_number; i++) + { + auto request = std::make_shared(); + request->a = 5; + request->b = 4; + + auto result = client_->async_send_request(request); + + if (rclcpp::spin_until_future_complete(node_, result) == rclcpp::FutureReturnCode::SUCCESS) + { + RCLCPP_DEBUG(node_->get_logger(), "Response %d is successfully returned by server!", i); + } + else + { + RCLCPP_ERROR(node_->get_logger(), "Request %d failed!", i); + } + } +} + +ScenarioBasicServiceClientFixture::ScenarioBasicServiceClientFixture() +{ +} + +void ScenarioBasicServiceClientFixture::SetUp(::benchmark::State& /*state*/) +{ + if (node_.use_count() == 0) + { + node_ = std::make_shared("test_scenario_basic_service_client", + rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)); + + node_->get_parameter("sending_request_number", sending_request_number_); + } +} + +void ScenarioBasicServiceClientFixture::TearDown(::benchmark::State& /*state*/) +{ + node_.reset(); +} + +BENCHMARK_DEFINE_F(ScenarioBasicServiceClientFixture, test_scenario_basic_service_client)(benchmark::State& st) +{ + for (auto _ : st) + { + // TODO @CihatAltiparmak : add this time stopings to + // perception pipeline benchmark as well + st.PauseTiming(); + auto sc = ScenarioBasicServiceClient(node_); + st.ResumeTiming(); + + sc.runTestCase(sending_request_number_); + } +} + +BENCHMARK_REGISTER_F(ScenarioBasicServiceClientFixture, test_scenario_basic_service_client); + +} // namespace middleware_benchmark +} // namespace moveit From b554c90f7cd858affd5e8bc4329b6e8f4876e78e Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Mon, 12 Aug 2024 17:45:45 +0300 Subject: [PATCH 4/5] Added middleware configs and some scripts to ease CI jobs for benchmarking and improve user experience (#19) * Added scripts related to visualization, running benchmarks etc. * Improved run_all_benchmarks script and fixed some typos in this script * Added basic service client benchmark to run_all_benchmarks.sh * Added documentations for scripts and made the configs for rmw_zenoh enabled * Fixed typo in documentation * Removed the unnecessary parameter (-m) from run_all_benchmarks.sh * Modified benchmark_args in run_all_benchmarks.sh and some style fix * Added title section per plot and used dot instead of sh for running initial_script * Delete unnecessary middleware_benchmark_results.json file * Update docs/how_to_run.md for directing to how_to_install Co-authored-by: Henning Kayser * Update docs/how_to_run.md for middleware-configuration related section Co-authored-by: Henning Kayser --------- Co-authored-by: Henning Kayser --- docs/how_to_run.md | 81 ++++++++++++++++++ docs/pictures/box_plot_example.png | Bin 0 -> 13780 bytes .../rmw_cyclonedds/config.sh | 3 + .../rmw_fastrtps/config.sh | 3 + middleware_configurations/rmw_zenoh/config.sh | 6 ++ scripts/box_plot_visualizer.py | 77 +++++++++++++++++ scripts/run_all_benchmarks.sh | 40 +++++++++ 7 files changed, 210 insertions(+) create mode 100644 docs/pictures/box_plot_example.png create mode 100644 middleware_configurations/rmw_cyclonedds/config.sh create mode 100644 middleware_configurations/rmw_fastrtps/config.sh create mode 100644 middleware_configurations/rmw_zenoh/config.sh create mode 100644 scripts/box_plot_visualizer.py create mode 100644 scripts/run_all_benchmarks.sh diff --git a/docs/how_to_run.md b/docs/how_to_run.md index db915ad..3767bf8 100644 --- a/docs/how_to_run.md +++ b/docs/how_to_run.md @@ -1,3 +1,84 @@ +## Run All Benchmarks +Before running the following benchmarks, please read and apply the instructions outlined in the [How To Install](how_to_install.md) section for providing the necessary requirements. + +To run all benchmarks, just select your middleware implementation and go ahead with `run_all_benchmarks.sh` bash script. This command initially will run the script you chose. In this example, it's used the default config scripts which the necessary middleware configuration is applied. This property serves the functionality for the users to apply some custom configurations freely. + +```shell +# go to workspace this repository is built +cd ws +source /opt/ros/rolling/setup.sh +source install/setup.sh +# go to moveit_middleware_benchmark package's directory +cd src/moveit_middleware_benchmark +# conduct all benchmarks +sh src/moveit_middleware_benchmark/scripts/run_all_benchmarks.sh -i ./src/moveit_middleware_benchmark/middleware_configurations/rmw_cyclonedds/config.sh -d /benchmark_results +``` + +Let's explain all operations at `run_all_benchmarks.sh`. + +#### selection of initial script +``` +-i ./src/moveit_middleware_benchmark/middleware_configurations/rmw_cyclonedds/config.sh +``` + +This argument is for selecting the initial scripts to be run. These initial scripts are used for configuring middleware-specific settings for improved performance. For example, you can use the initial script to configure TCP settings for rmw_zenoh like below. + +```shell +echo "The configurations for rmw_zenoh_cpp is started!" +export RMW_IMPLEMENTATION=rmw_zenoh_cpp +sudo sysctl -w "net.ipv4.tcp_rmem=4096 4096 4096" +sudo sysctl -w "net.ipv4.tcp_wmem=4096 4096 4096" +sudo sysctl -w "net.ipv4.tcp_mem=4096 4096 4096" +echo "The configurations for rmw_zenoh_cpp is finished!" +``` + +#### directory selection to save benchmark results +``` +-d /benchmark_results +``` + +This argument indicates where the benchmark results are saved. For scenario_perception_benchmark and scenario_basic_service_client, the results of these scenarios are written in the shape of the below directory tree. It should be added that `run_all_benchmarks.sh` script uses json format to save the benchmark results. + +``` +benchmark_results/ +├── scenario_basic_service_client +│   ├── rmw_cyclonedds_cpp.json +│   ├── rmw_fastrtps_cpp.json +│   └── rmw_zenoh_cpp.json +└── scenario_perception_pipeline + ├── rmw_cyclonedds_cpp.json + ├── rmw_fastrtps_cpp.json + └── rmw_zenoh_cpp.json +``` + +## Plot Visualization of Benchmark Results + +After running `run_all_benchmarks.sh`, you can also visualize the box plots of benchmark results. Suppose that you have some benchmark results stored in below directory and the directory named `benchmark_results` is located in `ws` directory which this repository is built. + + +``` +benchmark_results/ +├── scenario_basic_service_client +│   ├── rmw_cyclonedds_cpp.json +│   ├── rmw_fastrtps_cpp.json +│   └── rmw_zenoh_cpp.json +└── scenario_perception_pipeline + ├── rmw_cyclonedds_cpp.json + ├── rmw_fastrtps_cpp.json + └── rmw_zenoh_cpp.json +``` + +Just give the directory of benchmark results as argument and then visualize the benchmark results in plot. +```shell +cd ws +python3 src/moveit_middleware_benchmark/scripts/box_plot_visualizer.py benchmark_results + +``` + +**NOTE THAT THE BELOW PICTURE DOESN'T PRESENT REAL RESULTS. IT'S JUST FOR SHOWCASE** + +![](./pictures/box_plot_example.png) + ## Scenarios ### [Perception Pipeline Benchmark](scenarios/perception_pipeline_benchmark.md) diff --git a/docs/pictures/box_plot_example.png b/docs/pictures/box_plot_example.png new file mode 100644 index 0000000000000000000000000000000000000000..eaa3808761dad9838a1bcf19356c4a21a5970dae GIT binary patch literal 13780 zcmd^mXH*sGwrwHifNdj z_Y-OavCM}c7}{5_#7{(OS~~HUxZ_D3M|C?>N0;;VCWO*?$4l0Bj@A|zb~>BbJ6PD+ z3h|5cAKJgu+|lupgT%puHh({W-_G9bpz!kFb8(S1mwwlEAc&3U$v+H9vWXVB{!#f8 zM>VcQ47R%J2b(M|jZSUqBA)Z?&fp2(+D);_zZR6-rPJUq@*7)Qh@H~I@cO)GmrvQ; zx6ZS-wp=@AW$LHcCQvTOtVC1uZ}~;xl zEgz)qPSwtA_+!(ax@-&ee0}}{hDFob6H9%G(GTw3i>Zo~Om!Y?Vi&jXWV4wZY)*V+ zSE4)El%t-mmm_@s)eYX{?F8}pCZTgOV25l*hC!iaLz-?+JvA=w#MP@;*+p$5R&M0* zXgK`#?OV&wPakusM5W;%tpt67IQOhcnYEoSqh!|7z;mMB#P%RRe?#=ryjk(WWV3|Z zc#?!ue;k{TDGxutGDRcL*5G55^jS)_^Pt{#X}58IfhV!CA`acB`q?~XdQWv@_s2&fmUTQEwjMs+=0U$pi^oBDv#Cdwl>;b2K@(ryhb>Bd z7z#QmisS9qH>P+mEh;E0I~Pdd?%0?Zw67mHo1273!2{FvjP&)>R&HPy(_lfZurNGj z-zMpN+RMvJK~XU%Iy$;Bx4r$GZ^|-)$lXn7UAJv5NXD6~n6`cLVPK5lUxlg*AeU*o zWP%-ap&_fteabdIF_BM7N*|Y}9ms2WB4AwB`^79;GtahlydzN7^6ed#{@QrITN`)q z%QuyH7Ai-GJ$~)GF*PRUNMBzcC9aac@Pp7$pHq3jc3Pn9V$%4ycD@gCn;$I~F{|1(*jlK)Y15{H?|1lw zZJLCghFWxMtMgpHWSLd78PAVJzw5G(d{%5y8B$SIl~KUWNDvW6D}fXLxL;mt zmIkZp>7@))mkf99+GSQOhU4`;`~`SW(!gb#)3F64f&Ym7VUfv42d&?=DD(3lFR9N@{ zu^JC(Oz%7E%rTAoc)I1kWA~~z_u&P;xVLuQx*RN{ee-4(mVJ_vXKQL|)~;W_KhMUO zY5V5Qn>B*>E~^i~9gJ8=I{#1&S1I63;pNx#E#m z>%yhobM5WzH*ebXxNT{1NprGLR>_Fx~q|4WuJ%Lhc zcZ2bMG-RV6GU(@8hc((ODBRh-XHRfQNWxXdRZ%(BJ<;A7UJJ8*-H+@-I8VySS&jGB z%zpPf$bY36AgMfdo2_)|L1-wq{MwBh4`wN~m3Wfp9;D8zQL?QX`41QrXf*0OD1~|6 z@$(Cgjvk)CSxFWi7gmmhV%vzEf3 zh4k`>2M^*bXbA>?Jjd=$xm*2_;Ns%49B4=nm-Y6_A5>FU7xA2RTo|(T^r#E@kUNC3S25dd!cxTUYf($C_e`ac z<3M^|f0g9$15R=eln3r;^j@0s9;o(S%(ASP5ZYSUYMb9Wv`$SDCFwMJn=tpU@tkT+ zJn8q_J`oX3;Gu+B^s85|gpNf44a@)`gi#kW!yy5IGxY9{v{gGiV(#7hWw4EEMA`h? zZ{0Hr(b(=ux>=@pvlPy|TLg|(OHV}-NV|WB=Z+ zm=noQyx4+8umo^*e zWgHq3qGkKY-+%qv@^Y)8mi#-nZ;SU_0qCTy_VI~}iHTWT{rT;iH-`#W5lJ;KR-@1V zBVzr#TK~_7{DckcIMV)7Au#Cv{cjUyCMQpvNJ7DA3jRhA)Rhds$Q7%> z6*>=QJNDIDCT+ori(@rnc>e^c{`%BVGqVjfmHAlzsoBU|hrI%$cub!3#2FO!hy?$M3O(!>XKP@rvS7zq=q%(V* z`s?Iri7MLi^72l>Yp~B&0}SWmYire%9v(WnFgu~1s2o{god-1Yob5|2=n6TD=Th^W z8_X-1`s(g9)+w(PCfJomBAlka{tw-%>gvp~S!_Cf;plZf0Oh6vr&N$4b=yK*lzg^& zZ6jb|wA*;^<6`%zelRV5A%bh~UW=w|3)Uyrco&u(>b^eM9I1O1L(ID>f-S!mx#rtE z61I2(F802V(?5Mu&BQVvQR?^` zY&rB))fc(aH~;$UlZCk{tEI&SUS8g@Y)~?PE~W5J-NlX_OG)4(R`b)N6%`e=zB{~< z`e=!K0s=L+6H#QUHXh%%m4ZkpQoeuxUev(N&CR!K*HOxYprBa2oW)3&*e6fMYvgwH zfeUDd@*C8p=?dN5A#1o%cK(u6@P?o7Vzp1%Lx)^>B_(NNgJ>DgY&4^Fs+;g$-&S%n zF`#+HeEc1T{QrPCNO?_%ocP4|)mjpUU9;WywLOf(xPSoj$i;GKK895hU{{G#&k=d;0 zyLa!dd-C?JL(`g(Xe_x8`#uu7wl}3d?M>v}DkLLQqENPG?RwR+fYZlz^6NoG9k~na z19mOMzVt+xJX(8@VI;pNO5M>h8H*1Aa}GG}^JSNyTOm6a^Bho}Pa_4w|CjavNvLq&ID3u>1Vv zr(If_q4$tP0H92r+=r{zi3O}I1%g^Z=1}6$dfsn|1yJ|DWi_gU#4!AJSu0&H{>_^c z=|)t;%Fu(2SX7aV?|#`X>op(YnU$3_0bS(Qk1LHh1$hc+tIK%WbBE)qOc z*kk&V^!TUaEF5NEo|_m}?%TKTj=#T#o?iG$rfoW=R0`$SR{P2W;fHO)W#)bekL<#4?_GaRL*qe1`q{*e@<1z`%`SNH56-@K_xG$_y;^MeGJR}}voAt4*b5-R!p4>? zIrJj-SjTUytbDSvZ38F?RhpOtqZmje`3-BCn6xTG4zRGYa`*Kde;q05B9keg_|GIW zT*QhbzQzOxD0=-`1rA2Q`;b3FUKqDo^@-%M5e^5 zkx+Du9H#-Tblt3k4~JK*SWz(1aCV}}Ds$iN-A`T_tAq>7Gjl7C@9+7kR{D$j@g^_b z>1bQgl4Yhc@#724sueA&+A57i<@c1mdc|%z;i7hiriHjyUWkl6r~F6K_zoNh=B&>! zI2#rgM(Wb4-X7<|F6YAP)Wg7aznifPPa!L@%6iW(++^A&*1qO^BH5T&*vq%X&J7i+ z`2BW3&C)VOFUL~Tb`D(19E)N&Knm|`*Oq;Z5D(Io2C~vnVOVu-5PrzZ4D{po(0Pqw z=vTO>D4FSY#+x^8m;>`EaZjHfTCsAa0;SBKE!Om7IKEq+fq}s+Vuwzqp|m{jRMAnC zhf%vZ5h3ec^3`+7z`)_7NHDwE=w zzKKll1x0MQ$kjvUW#uWmAFg5k6m;-Mz`>uD2>M#C4;%ZY}|!UPvLw`9IM{=;`! zcR!ZUBt@EFf*~-_m?>*kNUq64f#aYWDYsH^(2p~NzCLny+2h+5hFn0FX{0fN_a}lo z#Y0Qjcm9!U*Onn-)nMLN8_zD|@gmA=wy&R`Y)OgO;6)t)lACwz$OJV|87`s+7(v*nwqUP(GBSn~h^fRUPj-u#e`@zX z`w|DlScKo20gNX>|$(HOhf->gwz?uZj>?4#5U(584*V5FvK? z$*;fuN`fBG&Yh)Mi{VxoH6U=?)5wdth_e%-)}LbvhfC)CCq9OY&=wcwwkLs8mQLZL zR@=NWI=xyaIygA~)`qPTWZ(7~b`T~E-3N2ru&GJ%BrogDdI@$6hu8FZEIHNT`A<~t zGABGHznD4w_$&a*l#-P6`?F`yENKaMj~zQU{)SmaOqU%OtF|BKZAW*uS%pHa22NN&u9)~tF= zR)9xnEW@SQ@xE{=*XK=ncA2N{vSVww<}Qp4Q8PrR&d19RFqH`bL=~ypjQmBL5k%JCdnp4z6S6cT5rl z>-r@2Ili=XcXB{1oy~9=qhFoaL;B~-m$6;}TSb-mv@_~rj$X$fM*ew%nCEqw8qq#I zX8_M+Z^C`YDH-p?N}_^XHu^`=oO3UiZP+2x@?H==Yu!&mz$I`eS-TMpUoe29v5i*J zkfY4H?7{0AVhaaHh9ZCdoA>BZBA*wHPn|q@Rju`0qT(nIFK_*#aao_BkG;5C?Hed^ z5%fZ|TM1q4HXlvYhsWq!)*Oc(Ww>m=!y_@%U;f;J#^uWkVm4xcmAb!2PU3Hy5A~3E zI_!Jr5O6!qakNE@+@JMNn#_pTuU`kFLjL$;b$zB0wZ(mDJ9ZU2A1?9qc+RR)SP-O@ z6h(EQo8epgHPNqgn{Day(z|v&E^yfh0V6F}%`i@<)8JWD>3H{k+6AF2{`YEQcbJrn zXJuurY>OT~15AGL%eMRtAN&rM@W|We>(7?UE0*TDVvK`pONpuWqi>qWSm;_5_;4 zIU?Q0{)Tk-1{u;ily=LWog7T{@gYd8B#9764cK}XZzi^M`-N}4cVkqVaSADSzrR_N zInik7ZgX??;Mv>{R^og2p1gnmKI|S^=~c$+rk?b?uVZ?Pm0grLx(rD?R4AJ{I1InZ0JbDt$1djoN5v(ZIg2%q z=UxlTWf!B)ldDzgktjlABN3V(@R z>dK`s8>}+v&bXd9c`{P_F0QF;FHB^>P7airO#%hhNYy$3DWwQOqzwvIc6Y0bq49t4 zqi)Vg&2$FAnJW41fL@%BkB?w81hKrUt80{;t?iI&J!$1|%57u_eei&Xlk)_H^!G@& zbg(&38*d~yENmvVe5<5$TF8FgCm?RAC=Hf=`Uj!v-uK+mb==V&_EmFC1wXwgBZHsB zYDhf zgA)cEBX||)*BeoE^)PCfquW#s#$Yqn{-{+Q!Qp6-B=d=fbE2Y|E z=z?g)j@Z>H28GTA-QiZ*c5O29wcA}<9NUQ}BOMw8ELGo_%Cn z(C2SAg^!QaUjnF?@9<7TarFA1&CRxH)^eZxaXE<>pSE@Pu5TahC@(f$RF?FZJ~Y*g zZ+>wEkIcAo{ig_V2dPT_P(@f6ZvDxLFz0u!A|Vf`$+64}KOt|;vZL&-1fF%V$9qw( zIoF1U=8=Q^gIke2Qa7NAaE5!KtE)@4wv56d39xp3(UwcsOJ@7|4D8?URSqF(QP#Fc z3{tLRap=Jbq%!edq(?`R5M3$}@R4XpR+oDuYUgZ8K2n4I__osN=_|#Hvjc8p@3|xQ zGZL!TO}0sE^$FZj4(6HDx&P!kBa2RR^{AWAx{qMY{dN0_N6WU(b_S``#ma50Pe0pe zHRn(*-J@y(x@vIZ#Eomq7&lWb{b=zKyLb*ALDZle%JATQ4e}$e0%mB9~~VHmvqUvaNz>4v>~pimu-Hg@3POjx46Wg z_?q;M{9*i2J}#~@ApwSIK{-1{JfBa$9054}UlZ)X9t)yS>Qc22g1hqw3aagq3(zn% z?G~Ra1|RMJ^!WO+Wy|XF9n9d%XS1gu0lgHWvb^-q763xrIM!83lClkKf+t{rAI$n0 z0Dw^r1V|2j(l+vpM?)taKX_VJB3kH1stcBq21hh?{xUuI5GEvI{rM0n4=Hiw9PXz{ zfeCjz4OQ56tq~NmeKYB{sQ?}+aU&xmg3W1wT2Qx1JyFMARWz@mYYk)x3;(q#2lWr; z@y^O1_SD^MP&~monB%E0UVP4qh>kXzxrPp%684XQL2zIs+9o(-^&Vc{l!_@Fa_RAm z27xf|C*%h6X_HY@SFTOVi)UWb-&SQh$9~3bC-N%pVlmhbVK`P6S z82gvOs)M%fqp8SZG1IHQB&tNqkOHl-psO-875_1ryjJG#^quDSZYLF&LRg%#Xe7y1g)XWsC#tgTmg{hn?qu=chZo?CdtdJ34 zH1`)bdsJ6fC)9A4T|@zkSwOJhGyNhYHORyXmVehiB3<$%CK%X!(x=Xht}*eRy8h&m zs9H>O+b9-F%xL+M>1+@~i0yrgFWHns?Qa2tVWNu}tRza0k)NW?@&F`OZRAKB*ZGH_ zO}%gQr)PE2Pa%+zD9t&psmXz>8PyRn1^+F+`2U0{_^*7&Xc+MVw1?Df z$Ewlt!$W}rh+6cv!z7B#j#VCXYBX>$XjedmL}(%~O{svRoeru|@M^FTZccBn`CTX$ zN?nR3Un?TAa0Fd95!VpyPuhiqe5hJ5avwZ;lp3!XTCpW|hu8E`5TKHb{O<6d`}hC4 zJ33p5xru?qysvJGqOFcW^9u|0FD@H{{{_3R7KaM~Q5+?wp`jt71t?J!N!#GloM+dF z9Wz044hstlxP4*Iv$C9!tUdVh4=(w$3)nj;--LRIMLk&m{qV&(+8iCz=a!R=nHa#ooJv}=$sA;nFx7KQcz_n zK(deJHz8jiQQMZJqt{ouhHxuK@W>Yo<~Bb-=7F8;`YMJKW=axf01&f2=eW|&0G6mi zo%v|@Vgr_8#8rlw==lD^~)n!A~LoCVFdPE6QNK zsZR~Hrdmr8J%LlAi_BDN7{hYTg?ZW8?Ck7+O4g+i+3_OLOAXSYWNFbI%@sot;s#9oPv_@7PM$ouPgGR<@#DwJp^PzW zM;CMb1Wp04ESs{yv!Bzg#Y_pl$513-%=t8vm~a@y>9v=kFw)8K0@Cp`4g}2`h20}; z-}!EBPM7S3k-Z+wt1C!Jhq)3-gOxshH)zpopf^dWEsPEgTP#~|$`iS>W$TVhj|CW4 z2flbAc6Ym^7BkmrRgkq7+dSM5=fd(av1kHZ5^NM9$#nfxGG#d&|x0#(ig`6ou zy;0&2cO@AXyYcSZcb^lpF>tc`RJ><{%w$Q~@x7yiPlMK!V+D&h5p4i&ff3Y0Jt&DV z=2&2v9l?~5;hO7IfgDXhvUo%F zzBXA#Oe1LO=sd(Nj)zj`Pg0A{YT)}h+ANvgO5PmRV7ZXf?dvD4Uj)#FO7@n`1#cl}TMJ=n=ULe+7$MAFs%|V)^pkJA4_R zphl$^RI2s(5wh4c=W62J++y0E($dnhc5sKx2V%*{+B$6w6Vu_1(&P8OKohz`2>Ek5 zyk*gT2-o!?x>*=(LbV zPnKos` zUkC~dv)~MaiSrPBDGWcL15LsbqrIBQwI%O8D!Tk&$@DAS7|PJjvN6L3v6pxjCf~AL z>83(f4g1wqRnNhu`2aiB9QxE0!vH;O4(J=FD7OOw4zK%d{~=5g2!8qUrTZqU;US=G zR4#TTLSZU5ruU?o+1V{a_zf(PH5ivne_xk5rQu5MX=WA{6Es?L=b;u0nVC*zA@4;G zV}Aj-sKS)fr%(IOOm_r+1pWSK=RJ3pdHZ%7%+{U9`eL!+bC!=IuJKr$=`n=@Pk?Qf z08@=+LBJ<)H}PuE;lmA%0}UUuJZ4{a1*yo4rYR~Y2vR=4bC4bwDw(qt0x(wF;~73e z57_t%m_jghV;1Mo;^HDUXQ>C;@hQstiV6ucX=HJSF=W8!Ft=lATFwFM<{lF5IjKv7 zz*5)K!z)jKdgu;0Yr8LN=^$e}iqm?2e*QEZbF(>kTmGE%u23U(V=pEj01g*|FYa^nHF7+c=59{xcteZqcNV#KzDD z&IVT|vE|oaFQ}=hRe0E%h&NiXZ{2DIn3l@?);CN3U5SxMVI&xmu_Z=}XG=x(t)tff zaRn$J5X@BCh$0T8mojeLV(c%ks3=4^?d&|M+x*qJ*`~W-AcL;wB0-d3xXo}NC@84- zt8ZfDfb=L*(s0Z*xE|9z8Oc-xjVL=XNn7GbWPB`8woStE-SU+y!_ffB)w4LseWXH8 z`|NqoOgWDUfY*u`zN^w{1j1CeZ56S^#Lvzg+twzlR&*$-N`wXqN=m^3r?94BeMYW10Z$Jp$D8I7PW8aEmVwFz#s2VNzG7$)72wD&R4eN)3TyT z^s#F5oE;aB4ROc`L##4XL|5LxA*G`tGZSYv?~we?${rYZ#qc$4ZV}^lQobWqT6p!I zMTXqd0e*c#->lJr#y=YeCSxuGVYfEEfb6TtY<{N{I1i@qWfrLc=^K*H#Ev7CbX9g0 z3yqR?*Lo2!_LUi$j?9tu@@&(|_!}W1Y4=u%o4UCbpq@5w-Fo($r?0PXDz>uWa5=gx zsDoit7tHX8(Jw3Kej&caW2DtAEmb`+pl6srw9;y3yZ{3&)%N=O5g2cY1>);rnC1*g z6w#pT>NEgE{SiA%6VV+*3X9L?+4eW(q>`pICM5y=N|;|`8S<8?a32Dr2;wBC_7qf9 zrlb(Cd6l{P1dBNJYmmp0x)-RDg3(!Wnx*H5%PvFa>D-@dg7nP-p{6=!MxJVA=qKY< zZrCoN0oHtv6BN&4W~^%#Vjv#p_9LTL177F2PYpQ)c;@za$vk=T#p2HX5sQBH!ea6-{qw#hPDM_&L>XG`cy<0<4>Q-C4vm`V!!$6u73bGf) zG2WjCM_R~o23T8RvqzpB2?oW;ga*+e9X*UDRO=d_Gz`ibEX0~1SL4fy!t5j*ukMIB z-^i4H6i7pcK`JU(86ZzCHTkmB()MQ_hR+C$p=Ddp#-Y^Sx3#s=cW`-oduM(b9DC3> zsXu(XwDbrm6#>>yFi(jMBw_RAd3?(P$s@ph$S^s7&?|o!h7u1SU!_$WhN8v_e%~)7 zqz*3AC2b|XY-fr-zJzS`#mL2@HcnzC5!fkVj3Q-ZX_8whJPvc%y#Vcc;4Y?XnaFu= z==SmK{F&}Y6X+d%IgN%i%ufu}dxQVFVOD|+oG=VWX4s^P)SV)8OY)}jTI~JM%j3vV zQz)x5*4EZHHd2K7ZSzosZ*oO%70cR_m$yw|!I8qz;;pRzS z8WDJ-7;v8U+@x}x^w~j2Ye<(0?c6n&m4(IP$7d2n>am%~>2n*5ksRC6&El%$U~eys zPHbXo+K;<#P&`;12gBF>ZWfLr&2@5u1S!clo;k8+rC55340BZi-kx5GM?Qij2RvCX zT=~fYw6p%BwHUyF1x4M0xg| z49AcPZWfsSU1e2?~*4eE@+~UaRvXTk3){IoeX_GOPuiKnC@h z&Sb1XUJ6zlFJ`mg&Kgb~PQxB2(*jSVd&q6nk#lCe_`Y@mLD#EHA&+}B?p@!%Z$e{0 z)-tRs<9Thg&yU$(d`|w8dctV|_~{dRq8L5i^Zw$+i&q+8C)5kuwoGf+KLCe8kYoi> zK(Z1x3CARD>9Q>jpqk+$BbVrCmytEzFR!iWeqPBhgl@^Td-toBORqOX*-(pCgWr%{ zKBIV2PaO)K8Ep#LtjXkXo6!)RY}QJs66s2m>rbkHKt&XIB!Hq52AvWCcOT21>5*L` z$Lx%83v7rqTs!WHR$Yk%J$IrNxjHa!*%|dY*@poBj^SZD zGz?2PeO7nw+~HjaFDokxcONcpY(YtJVN|^?)2K~q?A;zi)|=VZUusW3I{eX}U8G|9 ziWOmy_>YhoYniu!JLOj2$TC=N4_V;Q>eLv9Um9R$W3#|~hBf9ZI`W?y1ENfOKRr&s zOcTjZ(HX-q>+qhoghZ8lRE(C7VKYabc`ZHFVhn13jx%hZdcqdts)Z<> zZ1em1^JA4t5ID(a^D^==+h4>Vw@(EfAb)9bP6@LC{!}Uzmcw0g1^fk|0H?{N;V&Ln zBOldmYRIN!an?#@iMAv|k}%ZAVcWds^#HgZU$PRfWlDGiS3WdqXz|e=~`YMJS#^f)EWH!goj|rfCI!q2Xq(34x>Yq_3J8#Lf z=A_7qh>OkD!=y{vP2a%8gkRy976UsF0M=`sIa8yXchlDwziLqw&X+QCMd?h?mr43r z4UNwHz`iel#RT@$t2V2BAj3nx{qkSUR{YCm!@n|D`>%L=f1BOyUShD;F29i@kfVV6 PCge{lpU60N?%MwW{5Gve literal 0 HcmV?d00001 diff --git a/middleware_configurations/rmw_cyclonedds/config.sh b/middleware_configurations/rmw_cyclonedds/config.sh new file mode 100644 index 0000000..f9eba3b --- /dev/null +++ b/middleware_configurations/rmw_cyclonedds/config.sh @@ -0,0 +1,3 @@ +echo "The configurations for rmw_cyclonedds_cpp is started!" +export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp +echo "The configurations for rmw_cyclonedds_cpp is finished!" diff --git a/middleware_configurations/rmw_fastrtps/config.sh b/middleware_configurations/rmw_fastrtps/config.sh new file mode 100644 index 0000000..5cfb878 --- /dev/null +++ b/middleware_configurations/rmw_fastrtps/config.sh @@ -0,0 +1,3 @@ +echo "The configurations for rmw_fastrtps_cpp is started!" +export RMW_IMPLEMENTATION=rmw_fastrtps_cpp +echo "The configurations for rmw_fastrtps_cpp is finished!" diff --git a/middleware_configurations/rmw_zenoh/config.sh b/middleware_configurations/rmw_zenoh/config.sh new file mode 100644 index 0000000..ad969e5 --- /dev/null +++ b/middleware_configurations/rmw_zenoh/config.sh @@ -0,0 +1,6 @@ +echo "The configurations for rmw_zenoh_cpp is started!" +export RMW_IMPLEMENTATION=rmw_zenoh_cpp +sudo sysctl -w "net.ipv4.tcp_rmem=4096 4096 4096" +sudo sysctl -w "net.ipv4.tcp_wmem=4096 4096 4096" +sudo sysctl -w "net.ipv4.tcp_mem=4096 4096 4096" +echo "The configurations for rmw_zenoh_cpp is finished!" diff --git a/scripts/box_plot_visualizer.py b/scripts/box_plot_visualizer.py new file mode 100644 index 0000000..1eaa980 --- /dev/null +++ b/scripts/box_plot_visualizer.py @@ -0,0 +1,77 @@ +import matplotlib.pyplot as plt +import numpy as np +import json +import os +import sys + +BENCHMARK_RESULTS_DIR = sys.argv[1] + +middleware_colors = { + "rmw_zenoh_cpp": "orange", + "rmw_cyclonedds_cpp": "peachpuff", + "rmw_fastrtps_cpp": "tomato", +} + +middleware_list = ["rmw_zenoh_cpp", "rmw_cyclonedds_cpp", "rmw_fastrtps_cpp"] + + +def read_benchmark_json(file_name): + benchmark_json_data = None + with open(file_name) as f: + benchmark_json_data = json.load(f) + return benchmark_json_data + + +def get_real_time_list_from_benchmark_json(benchmark_json_data): + real_time_list = [] + for benchmark_info in benchmark_json_data["benchmarks"]: + if benchmark_info["run_type"] == "iteration": + real_time_list.append(benchmark_info["real_time"]) + return real_time_list + + +def get_middleware_dataset_for_scenario(scenario_name): + middleware_datasets = [] + for middleware_name in middleware_list: + file_name = os.path.join( + BENCHMARK_RESULTS_DIR, scenario_name, f"{middleware_name}.json" + ) + benchmark_json_data = read_benchmark_json(file_name) + dataset = get_real_time_list_from_benchmark_json(benchmark_json_data) + middleware_datasets.append( + { + "name": middleware_name, + "dataset": dataset, + "color": middleware_colors[middleware_name], + } + ) + return middleware_datasets + + +def plot_dataset_of_scenario(plt, scenario_name, middleware_datasets): + labels = [] + colors = [] + datasets = [] + + for x in middleware_datasets: + labels.append(x["name"]) + colors.append(x["color"]) + datasets.append(x["dataset"]) + + fig, ax = plt.subplots() + ax.set_title(scenario_name) + ax.set_ylabel("real time (ns)") + ax.set_xlabel("middlewares") + + bplot = ax.boxplot(datasets, patch_artist=True, tick_labels=labels) + + # fill with colors + for patch, color in zip(bplot["boxes"], colors): + patch.set_facecolor(color) + + +for scenario_name in os.listdir(BENCHMARK_RESULTS_DIR): + middleware_datasets = get_middleware_dataset_for_scenario(scenario_name) + plot_dataset_of_scenario(plt, scenario_name, middleware_datasets) + +plt.show() diff --git a/scripts/run_all_benchmarks.sh b/scripts/run_all_benchmarks.sh new file mode 100644 index 0000000..800d8b6 --- /dev/null +++ b/scripts/run_all_benchmarks.sh @@ -0,0 +1,40 @@ +# Inspired from https://unix.stackexchange.com/questions/31414/how-can-i-pass-a-command-line-argument-into-a-shell-script +helpFunction() +{ + echo "" + echo "Usage: $0 -i initial_script -d benchmark_results_directory" + echo -i "\t-i initial_script to run once all benchmarks are started" + echo -d "\t-d the directory the benchmark results is saved" + exit 1 # Exit script after printing help +} + +while getopts "i:m:d:" opt +do + case "$opt" in + i ) initial_script="$OPTARG" ;; + d ) benchmark_results_directory="$OPTARG" ;; + ? ) helpFunction ;; # Print helpFunction in case parameter is non-existent + esac +done + +# Print helpFunction in case parameters are empty +if [ -z "$initial_script" ] || [ -z "$benchmark_results_directory" ] +then + echo "Some or all of the parameters are empty"; + helpFunction +fi + +echo "benchmark results directory is $benchmark_results_directory" + +echo "Benchmarking is starting!" +echo "Starting initial scripts before benchmarks run!" +. "$initial_script" +echo "Initial script has finished! Now starting to benchmark middleware with scenarios!" + +mkdir ${benchmark_results_directory}/scenario_basic_service_client -p +ros2 daemon stop +ros2 launch moveit_middleware_benchmark scenario_basic_service_client_benchmark.launch.py benchmark_command_args:="--benchmark_out=${benchmark_results_directory}/scenario_basic_service_client/${RMW_IMPLEMENTATION}.json --benchmark_out_format=json --benchmark_repetitions=6" + +mkdir ${benchmark_results_directory}/scenario_perception_pipeline -p +ros2 daemon stop +ros2 launch moveit_middleware_benchmark scenario_perception_pipeline_benchmark.launch.py benchmark_command_args:="--benchmark_out=${benchmark_results_directory}/scenario_perception_pipeline/${RMW_IMPLEMENTATION}.json --benchmark_out_format=json --benchmark_repetitions=6" From a6e71c4bbe9f0bc8e092720fdaea638e507274cd Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Mon, 12 Aug 2024 17:46:04 +0300 Subject: [PATCH 5/5] Reconfigured run_benchmarks CI so that it can be conducted all moveit_benchmarks reliably (#21) --- .github/workflows/run_benchmarks.yml | 64 +++++++++++++++++++++++----- 1 file changed, 54 insertions(+), 10 deletions(-) diff --git a/.github/workflows/run_benchmarks.yml b/.github/workflows/run_benchmarks.yml index be2a9d4..be1f70f 100644 --- a/.github/workflows/run_benchmarks.yml +++ b/.github/workflows/run_benchmarks.yml @@ -1,10 +1,10 @@ -name: Run MoveIt Middleware Benchmarks and Push Results +name: Run MoveIt Middleware Benchmarks -on: [push] +on: [push, pull_request, workflow_dispatch] jobs: - run_middleware_benchmarks: - name: run_benchmarks + run_all_benchmarks: + name: run_all_benchmarks runs-on: ubuntu-latest strategy: fail-fast: false @@ -14,25 +14,69 @@ jobs: container: image: ghcr.io/cihataltiparmak/moveit_middleware_benchmark:latest steps: - - name: run perception benchmark + - name: run benchmarks for rmw_fastrtps run: | - cd /ws + cd ${ROS_UNDERLAY}/.. . /opt/ros/rolling/setup.sh . install/setup.sh - ros2 launch moveit_middleware_benchmark scenario_perception_pipeline_benchmark.launch.py + sh src/moveit_middleware_benchmark/scripts/run_all_benchmarks.sh -i ./src/moveit_middleware_benchmark/middleware_configurations/rmw_fastrtps/config_rmw_fastrtps.sh -d /benchmark_results -m rmw_fastrtps_cpp + - name: run benchmarks for rmw_cyclonedds + run: | + cd ${ROS_UNDERLAY}/.. + . /opt/ros/rolling/setup.sh + . install/setup.sh + sh src/moveit_middleware_benchmark/scripts/run_all_benchmarks.sh -i ./src/moveit_middleware_benchmark/middleware_configurations/rmw_cyclonedds/config_rmw_cyclonedds.sh -d /benchmark_results -m rmw_cyclonedds_cpp - name: clone repo uses: actions/checkout@v3 - name: add to safe directory run: | git config --global --add safe.directory /__w/moveit_middleware_benchmark/moveit_middleware_benchmark - - name: push perception benchmark results to github pages + - name: push perception benchmark results for rmw_fastrtps to github pages + uses: benchmark-action/github-action-benchmark@v1 + with: + name: Perception Pipeline Benchmark + tool: 'googlecpp' + output-file-path: /benchmark_results/scenario_perception_pipeline/rmw_fastrtps_cpp.json + # Access token to deploy GitHub Pages branch + github-token: ${{ secrets.GITHUB_TOKEN }} + # Push and deploy GitHub pages branch automatically + auto-push: true + gh-pages-branch: "gh-pages" + benchmark-data-dir-path: "rmw_fastrtps" + - name: push simple service client benchmark results for rmw_fastrtps to github pages + uses: benchmark-action/github-action-benchmark@v1 + with: + name: Basic Service Client Benchmark + tool: 'googlecpp' + output-file-path: /benchmark_results/scenario_basic_service_client/rmw_fastrtps_cpp.json + # Access token to deploy GitHub Pages branch + github-token: ${{ secrets.GITHUB_TOKEN }} + # Push and deploy GitHub pages branch automatically + auto-push: true + gh-pages-branch: "gh-pages" + benchmark-data-dir-path: "rmw_fastrtps" + + - name: push perception benchmark results for rmw_cyclonedds to github pages + uses: benchmark-action/github-action-benchmark@v1 + with: + name: Perception Pipeline Benchmark + tool: 'googlecpp' + output-file-path: /benchmark_results/scenario_perception_pipeline/rmw_cyclonedds_cpp.json + # Access token to deploy GitHub Pages branch + github-token: ${{ secrets.GITHUB_TOKEN }} + # Push and deploy GitHub pages branch automatically + auto-push: true + gh-pages-branch: "gh-pages" + benchmark-data-dir-path: "rmw_cyclonedds" + - name: push simple service client benchmark results for rme_cyclonedds to github pages uses: benchmark-action/github-action-benchmark@v1 with: - name: Movet Middleware Benchmark Project Perception Pipeline Benchmark + name: Basic Service Client Benchmark tool: 'googlecpp' - output-file-path: /ws/middleware_benchmark_results.json + output-file-path: /benchmark_results/scenario_basic_service_client/rmw_cyclonedds_cpp.json # Access token to deploy GitHub Pages branch github-token: ${{ secrets.GITHUB_TOKEN }} # Push and deploy GitHub pages branch automatically auto-push: true gh-pages-branch: "gh-pages" + benchmark-data-dir-path: "rmw_cyclonedds"