From 90ca25334f96a3b0562e76f8a1dea5b999138fdf Mon Sep 17 00:00:00 2001 From: asantamaria <asantamaria@iri.upc.edu> Date: Tue, 13 Dec 2016 18:22:41 +0100 Subject: [PATCH] working with opencv3.1 --- CMakeLists.txt | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 45718d7..68d5c73 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,8 +10,8 @@ find_package(catkin REQUIRED COMPONENTS iri_base_driver sensor_msgs image_transp # find_package(catkin REQUIRED COMPONENTS iri_base_driver cv_bridge image_transport camera_info_manager sensor_msgs) find_package(mvbluefox3 REQUIRED) find_package(mvIMPACT REQUIRED) -FIND_PACKAGE(OpenCV 3 REQUIRED) -# find_package(OpenCV 2.4.8 REQUIRED) +# FIND_PACKAGE(OpenCV 3 REQUIRED) +# find_package(OpenCV 2.4 REQUIRED) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) @@ -70,8 +70,8 @@ catkin_package( # ******************************************************************** # Add system and labrobotica run time dependencies here # ******************************************************************** - # DEPENDS mvbluefox3 mvIMPACT - DEPENDS mvbluefox3 mvIMPACT OpenCV + DEPENDS mvbluefox3 mvIMPACT + # DEPENDS mvbluefox3 mvIMPACT OpenCV ) ########### @@ -85,7 +85,7 @@ include_directories(include) include_directories(${catkin_INCLUDE_DIRS}) include_directories(${mvbluefox3_INCLUDE_DIR}) include_directories(${mvIMPACT_INCLUDE_DIR}) -INCLUDE_DIRECTORIES(${OpenCV_INCLUDE_DIRS}) +# INCLUDE_DIRECTORIES(${OpenCV_INCLUDE_DIRS}) # include_directories(${<dependency>_INCLUDE_DIR}) ## Declare a cpp library @@ -100,7 +100,7 @@ add_executable(${PROJECT_NAME} src/mvbluefox3_camera_driver.cpp src/mvbluefox3_c target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) target_link_libraries(${PROJECT_NAME} ${mvbluefox3_LIBRARY}) target_link_libraries(${PROJECT_NAME} ${mvIMPACT_LIBRARY}) -TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${OpenCV_LIBRARIES}) +# TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${OpenCV_LIBRARIES}) # TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${OpenCV_LIBS}) # target_link_libraries(${PROJECT_NAME} ${<dependency>_LIBRARY}) -- GitLab