Skip to content

Commit

Permalink
Renamed the files related to scenario_percpetion_pipeline
Browse files Browse the repository at this point in the history
  • Loading branch information
CihatAltiparmak committed Jul 2, 2024
1 parent a682568 commit 3a25bdc
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 10 deletions.
20 changes: 12 additions & 8 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,13 @@ find_package(nav_msgs REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(yaml-cpp REQUIRED)

add_executable(benchmark_main src/benchmark_main.cpp
src/scenarios/scenario_perception_pipeline.cpp)
add_executable(
scenario_perception_pipeline_benchmark_main
src/scenario_perception_pipeline_benchmark_main.cpp
src/scenarios/scenario_perception_pipeline.cpp)

ament_target_dependencies(
benchmark_main
scenario_perception_pipeline_benchmark_main
PUBLIC
"moveit_ros_planning_interface"
"rclcpp"
Expand All @@ -29,13 +31,15 @@ ament_target_dependencies(
"yaml-cpp")

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

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

install(TARGETS benchmark_main DESTINATION lib/${PROJECT_NAME})
install(TARGETS scenario_perception_pipeline_benchmark_main
DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME})

Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ colcon build --mixin release
source /opt/ros/rolling/setup.bash
source install/setup.bash
export RMW_IMPLEMENTATION=rmw_fastrtps_cpp # select your rmw_implementation to benchmark
ros2 launch moveit_middleware_benchmark moveit_middleware_benchmark_demo.launch.py
ros2 launch moveit_middleware_benchmark scenario_perception_pipeline_benchmark.launch.py

```

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ def generate_launch_description():
benchmark_main_node = Node(
name="benchmark_main",
package="moveit_middleware_benchmark",
executable="benchmark_main",
executable="scenario_perception_pipeline_benchmark_main",
output="both",
arguments=[
"--benchmark_out=middleware_benchmark_results.json",
Expand Down
File renamed without changes.

0 comments on commit 3a25bdc

Please sign in to comment.