-
Notifications
You must be signed in to change notification settings - Fork 411
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge remote-tracking branch 'origin/master' into ahcorde/rclcpp-benc…
…hmark-executors
- Loading branch information
Showing
4 changed files
with
321 additions
and
67 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,73 +1,33 @@ | ||
find_package(performance_test_fixture REQUIRED) | ||
|
||
# | ||
# Add a rmw-specific performance benchmark test from performance_test_fixture | ||
# | ||
# :param NAME: the target name which will also be used as the test name | ||
# :type NAME: string | ||
# :param SOURCE: the benchmark test target's source file | ||
# :type SOURCE: string | ||
# :param AMENT_DEPENDS: the ament dependincies for the benchmark test target | ||
# :type list of strings | ||
# :param LIBRARIES: the additional libraries the target needs to be linked | ||
# against | ||
# :type list of strings | ||
# :param TEST_OPTIONS: arguments to pass directly to add_performance_test | ||
# :type list of strings | ||
function(add_rclcpp_benchmark NAME SOURCE) | ||
set(multiValueArgs AMENT_DEPENDS LIBRARIES TEST_OPTIONS) | ||
cmake_parse_arguments( | ||
RCLCPP_BENCHMARK | ||
"" | ||
"" | ||
"${multiValueArgs}" | ||
"${ARGN}") | ||
if(RCLCPP_BENCHMARK_UNPARSED_ARGUMENTS) | ||
message( | ||
FATAL_ERROR | ||
"Unrecognized arguments for 'add_rclcpp_benchmark'" | ||
" (${RCLCPP_BENCHMARK_UNPARSED_ARGUMENTS})") | ||
return() | ||
endif() | ||
find_package(${rmw_implementation} REQUIRED) | ||
message(STATUS "Adding ${NAME} for '${rmw_implementation}'") | ||
set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation}) | ||
# These benchmarks are only being created and run for the default RMW | ||
# implementation. We are looking to test the performance of the ROS 2 code, not | ||
# the underlying middleware. | ||
|
||
set(full_benchmark_name ${NAME}${target_suffix}) | ||
add_performance_test( | ||
${full_benchmark_name} | ||
${SOURCE} | ||
${RCLCPP_BENCHMARK_TEST_OPTIONS} | ||
ENV ${rmw_implementation_env_var}) | ||
if(TARGET ${full_benchmark_name}) | ||
if(RCLCPP_BENCHMARK_AMENT_DEPENDS) | ||
ament_target_dependencies( | ||
${full_benchmark_name} | ||
${RCLCPP_BENCHMARK_AMENT_DEPENDS}) | ||
endif() | ||
target_link_libraries( | ||
${full_benchmark_name} | ||
${PROJECT_NAME} | ||
${RCLCPP_BENCHMARK_LIBRARIES}) | ||
endif() | ||
endfunction() | ||
add_performance_test(benchmark_client benchmark_client.cpp) | ||
if(TARGET benchmark_client) | ||
target_link_libraries(benchmark_client ${PROJECT_NAME}) | ||
ament_target_dependencies(benchmark_client test_msgs rcl_interfaces) | ||
endif() | ||
|
||
# Add new benchmarks inside this macro | ||
macro(rclcpp_benchmarks) | ||
add_rclcpp_benchmark(benchmark_init_shutdown benchmark_init_shutdown.cpp) | ||
add_performance_test(benchmark_executor benchmark_executor.cpp) | ||
if(TARGET benchmark_executor) | ||
target_link_libraries(benchmark_executor ${PROJECT_NAME}) | ||
ament_target_dependencies(benchmark_executor test_msgs) | ||
endif() | ||
|
||
set(SKIP_TEST "") | ||
if(${rmw_implementation} MATCHES "(.*)connext(.*)") | ||
set(SKIP_TEST "SKIP_TEST") | ||
endif() | ||
add_rclcpp_benchmark( | ||
benchmark_node | ||
benchmark_node.cpp | ||
TEST_OPTIONS ${SKIP_TEST}) | ||
add_performance_test(benchmark_init_shutdown benchmark_init_shutdown.cpp) | ||
if(TARGET benchmark_init_shutdown) | ||
target_link_libraries(benchmark_init_shutdown ${PROJECT_NAME}) | ||
endif() | ||
|
||
add_rclcpp_benchmark(benchmark_executor benchmark_executor.cpp | ||
AMENT_DEPENDS | ||
test_msgs) | ||
endmacro() | ||
add_performance_test(benchmark_node benchmark_node.cpp) | ||
if(TARGET benchmark_node) | ||
target_link_libraries(benchmark_node ${PROJECT_NAME}) | ||
endif() | ||
|
||
call_for_each_rmw_implementation(rclcpp_benchmarks) | ||
add_performance_test(benchmark_service benchmark_service.cpp) | ||
if(TARGET benchmark_service) | ||
target_link_libraries(benchmark_service ${PROJECT_NAME}) | ||
ament_target_dependencies(benchmark_service test_msgs rcl_interfaces) | ||
endif() |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,153 @@ | ||
// Copyright 2020 Open Source Robotics Foundation, Inc. | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#include <memory> | ||
#include <string> | ||
|
||
#include "performance_test_fixture/performance_test_fixture.hpp" | ||
#include "rclcpp/rclcpp.hpp" | ||
#include "test_msgs/srv/empty.hpp" | ||
|
||
using performance_test_fixture::PerformanceTest; | ||
|
||
constexpr char empty_service_name[] = "empty_service"; | ||
|
||
class ClientPerformanceTest : public PerformanceTest | ||
{ | ||
public: | ||
explicit ClientPerformanceTest(rclcpp::NodeOptions = rclcpp::NodeOptions()) {} | ||
void SetUp(benchmark::State & state) | ||
{ | ||
rclcpp::init(0, nullptr); | ||
node = std::make_unique<rclcpp::Node>("node", "ns"); | ||
|
||
auto empty_service_callback = | ||
[]( | ||
const test_msgs::srv::Empty::Request::SharedPtr, | ||
test_msgs::srv::Empty::Response::SharedPtr) {}; | ||
empty_service = | ||
node->create_service<test_msgs::srv::Empty>(empty_service_name, empty_service_callback); | ||
|
||
performance_test_fixture::PerformanceTest::SetUp(state); | ||
} | ||
|
||
void TearDown(benchmark::State & state) | ||
{ | ||
performance_test_fixture::PerformanceTest::TearDown(state); | ||
empty_service.reset(); | ||
node.reset(); | ||
rclcpp::shutdown(); | ||
} | ||
|
||
protected: | ||
std::unique_ptr<rclcpp::Node> node; | ||
std::shared_ptr<rclcpp::Service<test_msgs::srv::Empty>> empty_service; | ||
}; | ||
|
||
BENCHMARK_F(ClientPerformanceTest, construct_client_no_service)(benchmark::State & state) { | ||
// Prime cache | ||
auto outer_client = node->create_client<test_msgs::srv::Empty>("not_an_existing_service"); | ||
outer_client.reset(); | ||
|
||
reset_heap_counters(); | ||
for (auto _ : state) { | ||
auto client = node->create_client<test_msgs::srv::Empty>("not_an_existing_service"); | ||
benchmark::DoNotOptimize(client); | ||
benchmark::ClobberMemory(); | ||
|
||
state.PauseTiming(); | ||
client.reset(); | ||
state.ResumeTiming(); | ||
} | ||
} | ||
|
||
BENCHMARK_F(ClientPerformanceTest, construct_client_empty_srv)(benchmark::State & state) { | ||
// Prime cache | ||
auto outer_client = node->create_client<test_msgs::srv::Empty>(empty_service_name); | ||
outer_client.reset(); | ||
|
||
reset_heap_counters(); | ||
for (auto _ : state) { | ||
auto client = node->create_client<test_msgs::srv::Empty>(empty_service_name); | ||
benchmark::DoNotOptimize(client); | ||
benchmark::ClobberMemory(); | ||
|
||
state.PauseTiming(); | ||
client.reset(); | ||
state.ResumeTiming(); | ||
} | ||
} | ||
|
||
BENCHMARK_F(ClientPerformanceTest, destroy_client_empty_srv)(benchmark::State & state) { | ||
// Prime cache | ||
auto outer_client = node->create_client<test_msgs::srv::Empty>(empty_service_name); | ||
outer_client.reset(); | ||
|
||
reset_heap_counters(); | ||
for (auto _ : state) { | ||
state.PauseTiming(); | ||
auto client = node->create_client<test_msgs::srv::Empty>(empty_service_name); | ||
state.ResumeTiming(); | ||
benchmark::DoNotOptimize(client); | ||
benchmark::ClobberMemory(); | ||
|
||
client.reset(); | ||
} | ||
} | ||
|
||
BENCHMARK_F(ClientPerformanceTest, wait_for_service)(benchmark::State & state) { | ||
int count = 0; | ||
for (auto _ : state) { | ||
state.PauseTiming(); | ||
const std::string service_name = std::string("service_") + std::to_string(count++); | ||
// Create client before service so it has to 'discover' the service after construction | ||
auto client = node->create_client<test_msgs::srv::Empty>(service_name); | ||
auto callback = | ||
[]( | ||
const test_msgs::srv::Empty::Request::SharedPtr, | ||
test_msgs::srv::Empty::Response::SharedPtr) {}; | ||
auto service = | ||
node->create_service<test_msgs::srv::Empty>(service_name, callback); | ||
state.ResumeTiming(); | ||
|
||
client->wait_for_service(std::chrono::seconds(1)); | ||
benchmark::ClobberMemory(); | ||
} | ||
} | ||
|
||
BENCHMARK_F(ClientPerformanceTest, async_send_request_only)(benchmark::State & state) { | ||
auto client = node->create_client<test_msgs::srv::Empty>(empty_service_name); | ||
auto shared_request = std::make_shared<test_msgs::srv::Empty::Request>(); | ||
|
||
reset_heap_counters(); | ||
for (auto _ : state) { | ||
auto future = client->async_send_request(shared_request); | ||
benchmark::DoNotOptimize(future); | ||
benchmark::ClobberMemory(); | ||
} | ||
} | ||
|
||
BENCHMARK_F(ClientPerformanceTest, async_send_request_and_response)(benchmark::State & state) { | ||
auto client = node->create_client<test_msgs::srv::Empty>(empty_service_name); | ||
auto shared_request = std::make_shared<test_msgs::srv::Empty::Request>(); | ||
|
||
reset_heap_counters(); | ||
for (auto _ : state) { | ||
auto future = client->async_send_request(shared_request); | ||
rclcpp::spin_until_future_complete( | ||
node->get_node_base_interface(), future, std::chrono::seconds(1)); | ||
benchmark::DoNotOptimize(future); | ||
benchmark::ClobberMemory(); | ||
} | ||
} |
Oops, something went wrong.