diff --git a/cv_bridge/CMakeLists.txt b/cv_bridge/CMakeLists.txt index d93e3d208..06c64db09 100644 --- a/cv_bridge/CMakeLists.txt +++ b/cv_bridge/CMakeLists.txt @@ -37,7 +37,7 @@ find_package(OpenCV 3 REQUIRED CONFIG ) -include_directories(include) +include_directories(include ${Boost_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}) if(NOT ANDROID) add_subdirectory(python) diff --git a/cv_bridge/src/CMakeLists.txt b/cv_bridge/src/CMakeLists.txt index dc40f1ae2..2d6742905 100644 --- a/cv_bridge/src/CMakeLists.txt +++ b/cv_bridge/src/CMakeLists.txt @@ -5,6 +5,7 @@ ament_target_dependencies(${PROJECT_NAME} "sensor_msgs" ) target_link_libraries(${PROJECT_NAME} ${Boost_LIBRARIES} ${OpenCV_LIBRARIES}) +set_target_properties(${PROJECT_NAME} PROPERTIES WINDOWS_EXPORT_ALL_SYMBOLS ON) install(TARGETS ${PROJECT_NAME} DESTINATION lib)