Skip to content

Commit

Permalink
Compile benchmarks as separate modules and fix broken compilations of…
Browse files Browse the repository at this point in the history
… executable files (#44)

* Compile benchmarks as separate modules

* Decrease diff

* Fix Prefix
  • Loading branch information
CihatAltiparmak authored Dec 14, 2024
1 parent eda9ff1 commit 60d8748
Show file tree
Hide file tree
Showing 9 changed files with 56 additions and 44 deletions.
42 changes: 2 additions & 40 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,46 +17,8 @@ find_package(yaml-cpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(example_interfaces REQUIRED)

add_library(
moveit_middleware_benchmark_lib SHARED
src/scenarios/scenario_perception_pipeline.cpp
src/scenarios/scenario_basic_service_client.cpp)

ament_target_dependencies(
moveit_middleware_benchmark_lib
PUBLIC
moveit_ros_planning_interface
rclcpp
benchmark
dynmsg
nav_msgs
std_msgs
yaml-cpp
example_interfaces)

target_include_directories(
moveit_middleware_benchmark_lib
PUBLIC $<INSTALL_INTERFACE:include>
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>)

target_link_libraries(moveit_middleware_benchmark_lib
PUBLIC benchmark::benchmark ${YAML_CPP_LIBRARIES})

add_executable(scenario_perception_pipeline_benchmark_main
src/scenario_perception_pipeline_benchmark_main.cpp)

target_link_libraries(scenario_perception_pipeline_benchmark_main
PUBLIC moveit_middleware_benchmark_lib)

add_executable(scenario_basic_service_client_benchmark_main
src/scenario_basic_service_client_benchmark_main.cpp)

target_link_libraries(scenario_basic_service_client_benchmark_main
PUBLIC moveit_middleware_benchmark_lib)

install(TARGETS scenario_perception_pipeline_benchmark_main
scenario_basic_service_client_benchmark_main
DESTINATION lib/moveit_middleware_benchmark)
add_subdirectory(src/scenario_basic_service_client)
add_subdirectory(src/scenario_perception_pipeline)

install(DIRECTORY launch config DESTINATION share/moveit_middleware_benchmark)

Expand Down
24 changes: 24 additions & 0 deletions src/scenario_basic_service_client/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
add_executable(
scenario_basic_service_client_benchmark_main
scenario_basic_service_client_benchmark_main.cpp
scenario_basic_service_client.cpp)

ament_target_dependencies(
scenario_basic_service_client_benchmark_main
PUBLIC
rclcpp
benchmark
std_msgs
example_interfaces
ament_index_cpp)

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_basic_service_client_benchmark_main
DESTINATION lib/moveit_middleware_benchmark)
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
against basic service client works
*/

#include "moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp"
#include "moveit_middleware_benchmark/scenario_basic_service_client/scenario_basic_service_client.hpp"

namespace moveit
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
against basic service client works
*/

#include "moveit_middleware_benchmark/scenarios/scenario_basic_service_client.hpp"
#include "moveit_middleware_benchmark/scenario_basic_service_client/scenario_basic_service_client.hpp"

int main(int argc, char** argv)
{
Expand Down
26 changes: 26 additions & 0 deletions src/scenario_perception_pipeline/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
add_executable(
scenario_perception_pipeline_benchmark_main
scenario_perception_pipeline_benchmark_main.cpp
scenario_perception_pipeline.cpp)

ament_target_dependencies(
scenario_perception_pipeline_benchmark_main
PUBLIC
moveit_ros_planning_interface
rclcpp
benchmark
dynmsg
nav_msgs
yaml-cpp
example_interfaces)

target_include_directories(
scenario_perception_pipeline_benchmark_main
PUBLIC $<INSTALL_INTERFACE:include>
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/../../include>)

target_link_libraries(scenario_perception_pipeline_benchmark_main
PUBLIC benchmark::benchmark ${YAML_CPP_LIBRARIES})

install(TARGETS scenario_perception_pipeline_benchmark_main
DESTINATION lib/moveit_middleware_benchmark)
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
against perception pipeline
*/

#include "moveit_middleware_benchmark/scenarios/scenario_perception_pipeline.hpp"
#include "moveit_middleware_benchmark/scenario_perception_pipeline/scenario_perception_pipeline.hpp"

namespace moveit
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
against perception pipeline
*/

#include "moveit_middleware_benchmark/scenarios/scenario_perception_pipeline.hpp"
#include "moveit_middleware_benchmark/scenario_perception_pipeline/scenario_perception_pipeline.hpp"

int main(int argc, char** argv)
{
Expand Down

0 comments on commit 60d8748

Please sign in to comment.