Skip to content

Commit

Permalink
Implemented the benchmark to observe the effect of middleware over se…
Browse files Browse the repository at this point in the history
…rvice-client jobs
  • Loading branch information
CihatAltiparmak committed Jul 20, 2024
1 parent bc0d06a commit b91a243
Show file tree
Hide file tree
Showing 5 changed files with 343 additions and 4 deletions.
34 changes: 30 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ 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
Expand All @@ -29,7 +30,8 @@ ament_target_dependencies(
"benchmark"
"dynmsg"
"nav_msgs"
"yaml-cpp")
"yaml-cpp"
"example_interfaces")

target_include_directories(
scenario_perception_pipeline_benchmark_main
Expand All @@ -56,9 +58,33 @@ target_include_directories(
target_link_libraries(scenario_basic_subscription_benchmark_main
PUBLIC "benchmark::benchmark" ${YAML_CPP_LIBRARIES})

install(TARGETS scenario_perception_pipeline_benchmark_main
scenario_basic_subscription_benchmark_main
DESTINATION lib/moveit_middleware_benchmark)
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 $<INSTALL_INTERFACE:include>
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>)

target_link_libraries(scenario_basic_service_client_benchmark_main
PUBLIC "benchmark::benchmark" ${YAML_CPP_LIBRARIES})

install(
TARGETS scenario_perception_pipeline_benchmark_main
scenario_basic_subscription_benchmark_main
scenario_basic_service_client_benchmark_main
DESTINATION lib/moveit_middleware_benchmark)

install(DIRECTORY launch config DESTINATION share/moveit_middleware_benchmark)

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
/*********************************************************************
* 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 <rclcpp/rclcpp.hpp>
#include <benchmark/benchmark.h>
#include <memory>
#include <chrono>
#include <std_msgs/msg/string.hpp>
#include <example_interfaces/srv/add_two_ints.hpp>

#include <ament_index_cpp/get_package_share_directory.hpp>

namespace moveit
{
namespace middleware_benchmark
{

class ScenarioBasicServiceClient
{
public:
ScenarioBasicServiceClient(rclcpp::Node::SharedPtr node);

void runTestCase(const int& sending_request_number);

private:
rclcpp::Node::SharedPtr node_;
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
};

class ScenarioBasicServiceClientFixture : public benchmark::Fixture
{
public:
ScenarioBasicServiceClientFixture();

void SetUp(::benchmark::State& /*state*/);

void TearDown(::benchmark::State& /*state*/);

protected:
rclcpp::Node::SharedPtr node_;
int sending_request_number_;
};

} // namespace middleware_benchmark
} // namespace moveit
65 changes: 65 additions & 0 deletions launch/scenario_basic_service_client_benchmark.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
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 = ExecuteProcess(
cmd=[
[
"ros2 run demo_nodes_cpp add_two_ints_server"
]
],
shell=True,
)

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)]
)
50 changes: 50 additions & 0 deletions src/scenario_basic_service_client_benchmark_main.cpp
Original file line number Diff line number Diff line change
@@ -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;
}
115 changes: 115 additions & 0 deletions src/scenarios/scenario_basic_service_client.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
/*********************************************************************
* 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(rclcpp::Node::SharedPtr node) : node_(node) {
client_ = node_->create_client<example_interfaces::srv::AddTwoInts>("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<example_interfaces::srv::AddTwoInts::Request>();
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 successfuly 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<rclcpp::Node>("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

0 comments on commit b91a243

Please sign in to comment.