diff --git a/image_proc/CMakeLists.txt b/image_proc/CMakeLists.txt index e4dffcf33..756b737e1 100644 --- a/image_proc/CMakeLists.txt +++ b/image_proc/CMakeLists.txt @@ -18,7 +18,10 @@ find_package(rcutils REQUIRED) find_package(cv_bridge REQUIRED) find_package(image_transport REQUIRED) find_package(sensor_msgs REQUIRED) -find_package(OpenCV 3 REQUIRED) +find_package(OpenCV REQUIRED) +if(OpenCV_VERSION VERSION_LESS "3.2.0") + message(FATAL "Minimum OpenCV version is 3.2.0 (found version ${OpenCV_VERSION})") +endif() find_package(image_geometry REQUIRED) include_directories( diff --git a/image_proc/src/crop_decimate.cpp b/image_proc/src/crop_decimate.cpp index 68a6eb871..3e8261dac 100644 --- a/image_proc/src/crop_decimate.cpp +++ b/image_proc/src/crop_decimate.cpp @@ -46,11 +46,12 @@ void debayer2x2toBGR( int R, int G1, int G2, int B) { typedef cv::Vec DstPixel; // 8- or 16-bit BGR - #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION > 2 +#if CV_VERSION_MAJOR >= 4 dst.create(src.rows / 2, src.cols / 2, cv::traits::Type::value); - #else +#else + // Assume OpenCV 3 API dst.create(src.rows / 2, src.cols / 2, cv::DataType::type); - #endif +#endif int src_row_step = src.step1(); int dst_row_step = dst.step1(); diff --git a/image_publisher/CMakeLists.txt b/image_publisher/CMakeLists.txt index 439e7aa5c..045454414 100644 --- a/image_publisher/CMakeLists.txt +++ b/image_publisher/CMakeLists.txt @@ -29,15 +29,8 @@ set( DEPENDENCIES cv_bridge ) -set(opencv_2_components core highgui) -set(opencv_3_components core imgcodecs videoio) -find_package(OpenCV REQUIRED COMPONENTS core) +find_package(OpenCV REQUIRED COMPONENTS core imgcodecs videoio) message(STATUS "opencv version ${OpenCV_VERSION}") -if(OpenCV_VERSION VERSION_LESS "3.0.0") - find_package(OpenCV 2 REQUIRED COMPONENTS ${opencv_2_components}) -else() - find_package(OpenCV 3 REQUIRED COMPONENTS ${opencv_3_components}) -endif() include_directories(include) diff --git a/image_view/CMakeLists.txt b/image_view/CMakeLists.txt index a357a1ff1..315b288ca 100644 --- a/image_view/CMakeLists.txt +++ b/image_view/CMakeLists.txt @@ -33,10 +33,6 @@ if(ANDROID) return() endif() -find_package(GTK2) -add_definitions(-DHAVE_GTK) -include_directories(${GTK2_INCLUDE_DIRS}) - add_library(image_view_nodes SHARED src/disparity_view_node.cpp src/extract_images_node.cpp @@ -56,8 +52,6 @@ ament_target_dependencies(image_view_nodes stereo_msgs ) target_link_libraries(image_view_nodes - ${GTK_LIBRARIES} - ${GTK2_LIBRARIES} ${OpenCV_LIBRARIES} ${Boost_LIBRARIES} ) diff --git a/image_view/package.xml b/image_view/package.xml index 418513d4f..ead92c393 100644 --- a/image_view/package.xml +++ b/image_view/package.xml @@ -18,7 +18,6 @@ camera_calibration_parsers cv_bridge - gtk2 image_transport message_filters rclcpp