Skip to content

Commit

Permalink
update image_tools library so it can be reused outside if desired
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed May 11, 2021
1 parent 3a8bf68 commit 07debb3
Showing 1 changed file with 20 additions and 7 deletions.
27 changes: 20 additions & 7 deletions image_tools/CMakeLists.txt
Expand Up @@ -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
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>")
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()
Expand Down

0 comments on commit 07debb3

Please sign in to comment.