Skip to content

Commit 9585f93

Browse files
authored
Use OpenCV 3.2 on Buster (#536)
Signed-off-by: Shane Loretz <[email protected]>
1 parent 309cf99 commit 9585f93

File tree

1 file changed

+5
-2
lines changed

1 file changed

+5
-2
lines changed

image_publisher/CMakeLists.txt

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,13 @@ project(image_publisher)
33

44
find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure camera_info_manager sensor_msgs image_transport nodelet roscpp)
55

6-
set(opencv_4_components core imgcodecs videoio)
76
find_package(OpenCV REQUIRED COMPONENTS core)
87
message(STATUS "opencv version ${OpenCV_VERSION}")
9-
find_package(OpenCV 4 REQUIRED COMPONENTS ${opencv_4_components})
8+
if(OpenCV_VERSION VERSION_LESS "4.0.0")
9+
find_package(OpenCV 3 REQUIRED COMPONENTS core imgcodecs videoio)
10+
else()
11+
find_package(OpenCV 4 REQUIRED COMPONENTS core imgcodecs videoio)
12+
endif()
1013

1114
# generate the dynamic_reconfigure config file
1215
generate_dynamic_reconfigure_options(cfg/ImagePublisher.cfg)

0 commit comments

Comments
 (0)