Skip to content
Snippets Groups Projects
Commit 90ca2533 authored by Angel Santamaria-Navarro's avatar Angel Santamaria-Navarro
Browse files

working with opencv3.1

parent c2fcc6dc
No related branches found
No related tags found
No related merge requests found
......@@ -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})
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment