Skip to content

Commit

Permalink
adapt to OpenCV4 (#537)
Browse files Browse the repository at this point in the history
  • Loading branch information
timonegk committed May 21, 2020
1 parent 275b246 commit 2f27cd0
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 12 deletions.
10 changes: 1 addition & 9 deletions image_publisher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,7 @@ project(image_publisher)

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

set(opencv_2_components core highgui)
set(opencv_3_components core imgcodecs videoio)
find_package(OpenCV REQUIRED COMPONENTS core)
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()
find_package(OpenCV REQUIRED COMPONENTS core imgcodecs videoio)

# generate the dynamic_reconfigure config file
generate_dynamic_reconfigure_options(cfg/ImagePublisher.cfg)
Expand Down
6 changes: 3 additions & 3 deletions image_publisher/src/nodelet/image_publisher_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ class ImagePublisherNodelet : public nodelet::Nodelet
{
if ( cap_.isOpened() ) {
if ( ! cap_.read(image_) ) {
cap_.set(CV_CAP_PROP_POS_FRAMES, 0);
cap_.set(cv::CAP_PROP_POS_FRAMES, 0);
}
}
if (flip_image_)
Expand Down Expand Up @@ -136,7 +136,7 @@ class ImagePublisherNodelet : public nodelet::Nodelet
nh_.param("filename", filename_, std::string(""));
NODELET_INFO("File name for publishing image is : %s", filename_.c_str());
try {
image_ = cv::imread(filename_, CV_LOAD_IMAGE_COLOR);
image_ = cv::imread(filename_, cv::IMREAD_COLOR);
if ( image_.empty() ) { // if filename is motion file or device file
try { // if filename is number
int num = boost::lexical_cast<int>(filename_);//num is 1234798797
Expand All @@ -146,7 +146,7 @@ class ImagePublisherNodelet : public nodelet::Nodelet
}
CV_Assert(cap_.isOpened());
cap_.read(image_);
cap_.set(CV_CAP_PROP_POS_FRAMES, 0);
cap_.set(cv::CAP_PROP_POS_FRAMES, 0);
}
CV_Assert(!image_.empty());
}
Expand Down

0 comments on commit 2f27cd0

Please sign in to comment.