From 5d860be899abc66ea6a58b12ce071c8e56de157c Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 5 Jan 2022 13:18:16 -0800 Subject: [PATCH 1/3] Install includes to ${PROJECT_NAME} folder and use modern CMake Signed-off-by: Shane Loretz --- CMakeLists.txt | 46 +++++++++++++++++++++++----------------------- 1 file changed, 23 insertions(+), 23 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 005c46c..afe79bf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,7 @@ endif() find_package(ament_cmake_ros REQUIRED) find_package(image_geometry REQUIRED) -find_package(OpenCV REQUIRED) +find_package(OpenCV REQUIRED COMPONENTS core) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(sensor_msgs REQUIRED) @@ -22,32 +22,30 @@ find_package(sensor_msgs REQUIRED) add_library(DepthImageToLaserScan src/DepthImageToLaserScan.cpp ) -ament_target_dependencies(DepthImageToLaserScan - "image_geometry" - "OpenCV" - "sensor_msgs" -) +target_link_libraries(DepthImageToLaserScan PUBLIC + image_geometry::image_geometry + opencv_core + ${sensor_msgs_TARGETS}) + generate_export_header(DepthImageToLaserScan EXPORT_FILE_NAME ${PROJECT_NAME}/DepthImageToLaserScan_export.h) target_include_directories(DepthImageToLaserScan PUBLIC "$" "$" - "$" + "$" ) add_library(DepthImageToLaserScanROS src/DepthImageToLaserScanROS.cpp ) -ament_target_dependencies(DepthImageToLaserScanROS - "rclcpp" - "rclcpp_components" -) -target_link_libraries(DepthImageToLaserScanROS DepthImageToLaserScan) +target_link_libraries(DepthImageToLaserScanROS PUBLIC + rclcpp::rclcpp) +target_link_libraries(DepthImageToLaserScanROS PRIVATE + rcutils::rcutils + rclcpp_components::component) + +target_link_libraries(DepthImageToLaserScanROS PUBLIC + DepthImageToLaserScan) generate_export_header(DepthImageToLaserScanROS EXPORT_FILE_NAME ${PROJECT_NAME}/DepthImageToLaserScanROS_export.h) -target_include_directories(DepthImageToLaserScanROS PUBLIC - "$" - "$" - "$" -) rclcpp_components_register_nodes(DepthImageToLaserScanROS "depthimage_to_laserscan::DepthImageToLaserScanROS") @@ -60,9 +58,7 @@ target_link_libraries(depthimage_to_laserscan_node DepthImageToLaserScanROS ) -install(DIRECTORY include/ - DESTINATION include -) +install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME}) install(DIRECTORY launch @@ -71,6 +67,7 @@ install(DIRECTORY ) install(TARGETS DepthImageToLaserScan DepthImageToLaserScanROS + EXPORT export_${PROJECT_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin @@ -83,7 +80,7 @@ install(TARGETS depthimage_to_laserscan_node install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}/DepthImageToLaserScan_export.h ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}/DepthImageToLaserScanROS_export.h - DESTINATION include/${PROJECT_NAME}) + DESTINATION include/${PROJECT_NAME}/${PROJECT_NAME}) if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) @@ -92,6 +89,9 @@ if(BUILD_TESTING) target_link_libraries(${PROJECT_NAME}-test DepthImageToLaserScan) endif() -ament_export_include_directories(include) -ament_export_libraries(DepthImageToLaserScan DepthImageToLaserScanROS) +ament_export_targets(export_${PROJECT_NAME}) +ament_export_dependencies(rclcpp) +ament_export_dependencies(image_geometry) +ament_export_dependencies(OpenCV) +ament_export_dependencies(sensor_msgs) ament_package() From 8d1d513b8f093e2f84fe5589ee74f25b3b7ecf58 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 19 Jan 2022 15:28:07 -0800 Subject: [PATCH 2/3] Add back old-style CMake variables Signed-off-by: Shane Loretz --- CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index afe79bf..9cd1d75 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -89,6 +89,10 @@ if(BUILD_TESTING) target_link_libraries(${PROJECT_NAME}-test DepthImageToLaserScan) endif() +# TODO(sloretz) stop exporting old-style CMake variables in the future +ament_export_include_directories("include/${PROJECT_NAME}") +ament_export_libraries(DepthImageToLaserScan DepthImageToLaserScanROS) + ament_export_targets(export_${PROJECT_NAME}) ament_export_dependencies(rclcpp) ament_export_dependencies(image_geometry) From 9926f0997b5d8a68768dfd0745585ffe27e09162 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 20 Jan 2022 09:09:01 -0800 Subject: [PATCH 3/3] Remove traces of rcutils Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 - src/DepthImageToLaserScanROS.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9cd1d75..1fbd8d4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -40,7 +40,6 @@ add_library(DepthImageToLaserScanROS target_link_libraries(DepthImageToLaserScanROS PUBLIC rclcpp::rclcpp) target_link_libraries(DepthImageToLaserScanROS PRIVATE - rcutils::rcutils rclcpp_components::component) target_link_libraries(DepthImageToLaserScanROS PUBLIC diff --git a/src/DepthImageToLaserScanROS.cpp b/src/DepthImageToLaserScanROS.cpp index 945a662..ae435b7 100644 --- a/src/DepthImageToLaserScanROS.cpp +++ b/src/DepthImageToLaserScanROS.cpp @@ -37,7 +37,6 @@ #include #include -#include #include #include #include