Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion image_proc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ 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 4 REQUIRED)
find_package(image_geometry REQUIRED)

include_directories(
Expand Down
4 changes: 0 additions & 4 deletions image_proc/src/crop_decimate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,7 @@ void debayer2x2toBGR(
int R, int G1, int G2, int B)
{
typedef cv::Vec<T, 3> DstPixel; // 8- or 16-bit BGR
#if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION > 2
dst.create(src.rows / 2, src.cols / 2, cv::traits::Type<DstPixel>::value);
#else
dst.create(src.rows / 2, src.cols / 2, cv::DataType<DstPixel>::type);
#endif

int src_row_step = src.step1();
int dst_row_step = dst.step1();
Expand Down
8 changes: 1 addition & 7 deletions image_publisher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,9 @@ set( DEPENDENCIES
cv_bridge
)

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 4 REQUIRED COMPONENTS ${opencv_4_components})
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The variable opencv_4_components doesn't seem to be set anywhere?


include_directories(include)

Expand Down
6 changes: 3 additions & 3 deletions image_publisher/src/image_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ void ImagePublisher::doWork()
try {
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 All @@ -149,7 +149,7 @@ void ImagePublisher::onInit()
{
RCLCPP_INFO(this->get_logger(), "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 not exist, open video device
try { // if filename is number
int num = std::stoi(filename_); // num is 1234798797
Expand All @@ -159,7 +159,7 @@ void ImagePublisher::onInit()
}
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());
} catch (cv::Exception & e) {
Expand Down
1 change: 0 additions & 1 deletion image_view/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@ ament_target_dependencies(image_view_nodes
stereo_msgs
)
target_link_libraries(image_view_nodes
${GTK_LIBRARIES}
${GTK2_LIBRARIES}
${OpenCV_LIBRARIES}
${Boost_LIBRARIES}
Expand Down