From c37032614040eb8d82647f66f490987deabede32 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 11 May 2021 15:46:43 -0700 Subject: [PATCH] update image_tools library so it can be reused outside if desired Signed-off-by: William Woodall --- image_tools/CMakeLists.txt | 27 ++++++++++++++++++++------- 1 file changed, 20 insertions(+), 7 deletions(-) diff --git a/image_tools/CMakeLists.txt b/image_tools/CMakeLists.txt index 115ef9013..a82ee1074 100644 --- a/image_tools/CMakeLists.txt +++ b/image_tools/CMakeLists.txt @@ -20,29 +20,42 @@ find_package(OpenCV REQUIRED) include_directories(include) -add_library(imagetools SHARED +add_library(${PROJECT_NAME} SHARED src/burger.cpp src/cam2image.cpp src/cv_mat_sensor_msgs_image_type_adapter.cpp src/showimage.cpp ) -target_compile_definitions(imagetools +target_compile_definitions(${PROJECT_NAME} PRIVATE "IMAGE_TOOLS_BUILDING_DLL") -ament_target_dependencies(imagetools +target_include_directories(${PROJECT_NAME} PUBLIC + "$" + "$") +ament_target_dependencies(${PROJECT_NAME} "rclcpp" "sensor_msgs" "std_msgs" "rclcpp_components" "OpenCV") -rclcpp_components_register_node(imagetools PLUGIN "image_tools::Cam2Image" EXECUTABLE cam2image) -rclcpp_components_register_node(imagetools PLUGIN "image_tools::ShowImage" EXECUTABLE showimage) +rclcpp_components_register_node(${PROJECT_NAME} PLUGIN "image_tools::Cam2Image" EXECUTABLE cam2image) +rclcpp_components_register_node(${PROJECT_NAME} PLUGIN "image_tools::ShowImage" EXECUTABLE showimage) -install(TARGETS - imagetools +install( + TARGETS ${PROJECT_NAME} EXPORT ${PROJECT_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin) +install( + DIRECTORY include/ + DESTINATION include +) + +ament_export_libraries(${PROJECT_NAME}) +ament_export_targets(${PROJECT_NAME}) + +ament_export_dependencies(rclcpp_components) + if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies()