From aa56a1e38594e7da4f57d38c11818adeaeefd367 Mon Sep 17 00:00:00 2001 From: Lewis Liu Date: Wed, 8 Apr 2020 15:19:28 +0800 Subject: [PATCH 1/2] add opencv4 into the dependency list. Signed-off-by: Lewis Liu --- cv_bridge/CMakeLists.txt | 2 +- cv_bridge/src/CMakeLists.txt | 10 +++++++--- cv_bridge/src/module_opencv3.cpp | 9 +++++++-- 3 files changed, 15 insertions(+), 6 deletions(-) diff --git a/cv_bridge/CMakeLists.txt b/cv_bridge/CMakeLists.txt index ed9f023e7..01d284668 100644 --- a/cv_bridge/CMakeLists.txt +++ b/cv_bridge/CMakeLists.txt @@ -37,7 +37,7 @@ else() endif() find_package(sensor_msgs REQUIRED) -find_package(OpenCV 3 REQUIRED +find_package(OpenCV 4 REQUIRED COMPONENTS opencv_core opencv_imgproc diff --git a/cv_bridge/src/CMakeLists.txt b/cv_bridge/src/CMakeLists.txt index 39db925d7..9e2cf45e3 100644 --- a/cv_bridge/src/CMakeLists.txt +++ b/cv_bridge/src/CMakeLists.txt @@ -44,10 +44,14 @@ if(PYTHON_VERSION_MAJOR VERSION_EQUAL 3) add_definitions(-DPYTHON3) endif() -if(OpenCV_VERSION_MAJOR VERSION_EQUAL 3) - add_library(${PROJECT_NAME}_boost module.cpp module_opencv3.cpp) -else() +if(OpenCV_VERSION_MAJOR VERSION_EQUAL 4) + add_definitions(-DOPENCV_VERSION_4) +endif() + +if(OpenCV_VERSION_MAJOR VERSION_LESS 3) add_library(${PROJECT_NAME}_boost module.cpp module_opencv2.cpp) +else() + add_library(${PROJECT_NAME}_boost module.cpp module_opencv3.cpp) endif() target_link_libraries(${PROJECT_NAME}_boost ${PYTHON_LIBRARIES} diff --git a/cv_bridge/src/module_opencv3.cpp b/cv_bridge/src/module_opencv3.cpp index 2aa56021f..ac93f0897 100644 --- a/cv_bridge/src/module_opencv3.cpp +++ b/cv_bridge/src/module_opencv3.cpp @@ -99,6 +99,11 @@ class NumpyAllocator : public MatAllocator NumpyAllocator() {stdAllocator = Mat::getStdAllocator();} ~NumpyAllocator() {} +// To compile openCV3 with OpenCV4 APIs. +#ifndef OPENCV_VERSION_4 +#define AccessFlag int +#endif + UMatData * allocate(PyObject * o, int dims, const int * sizes, int type, size_t * step) const { UMatData * u = new UMatData(this); @@ -115,7 +120,7 @@ class NumpyAllocator : public MatAllocator } UMatData * allocate( - int dims0, const int * sizes, int type, void * data, size_t * step, int flags, + int dims0, const int * sizes, int type, void * data, size_t * step, AccessFlag flags, UMatUsageFlags usageFlags) const { if (data != 0) { @@ -148,7 +153,7 @@ class NumpyAllocator : public MatAllocator return allocate(o, dims0, sizes, type, step); } - bool allocate(UMatData * u, int accessFlags, UMatUsageFlags usageFlags) const + bool allocate(UMatData * u, AccessFlag accessFlags, UMatUsageFlags usageFlags) const { return stdAllocator->allocate(u, accessFlags, usageFlags); } From e8c1d37ec62c526b3f67f22c6be499baa31ea294 Mon Sep 17 00:00:00 2001 From: Lewis Liu Date: Wed, 8 Apr 2020 16:57:40 +0800 Subject: [PATCH 2/2] update CMakefile for automatically selecting openCV4 or openCV3 judging from openCV installation situation. --- cv_bridge/CMakeLists.txt | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/cv_bridge/CMakeLists.txt b/cv_bridge/CMakeLists.txt index 01d284668..642d32fdc 100644 --- a/cv_bridge/CMakeLists.txt +++ b/cv_bridge/CMakeLists.txt @@ -37,13 +37,23 @@ else() endif() find_package(sensor_msgs REQUIRED) -find_package(OpenCV 4 REQUIRED + +find_package(OpenCV 4 QUIET COMPONENTS opencv_core opencv_imgproc opencv_imgcodecs CONFIG ) +if(NOT OpenCV_FOUND) + find_package(OpenCV 3 REQUIRED + COMPONENTS + opencv_core + opencv_imgproc + opencv_imgcodecs + CONFIG + ) +endif() if(NOT ANDROID) add_subdirectory(python)