Skip to content

Commit

Permalink
get opencv_apps to compile with OpenCV3
Browse files Browse the repository at this point in the history
  • Loading branch information
vrabaud committed Jan 4, 2015
1 parent d1808c7 commit 89a933a
Show file tree
Hide file tree
Showing 13 changed files with 129 additions and 8 deletions.
17 changes: 13 additions & 4 deletions opencv_apps/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,16 @@ project(opencv_apps)

find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure message_generation image_transport nodelet roscpp)

find_package(OpenCV REQUIRED)
if (OpenCV_VERSION VERSION_EQUAL "3")
add_definitions("-DOPENCV3=1")
set(${PROJECT_NAME}_EXTRA_CFG)
set(${PROJECT_NAME}_EXTRA_FILES)
else()
set(${PROJECT_NAME}_EXTRA_CFG cfg/SimpleFlow.cfg)
set(${PROJECT_NAME}_EXTRA_FILES src/nodelet/simple_flow_nodelet.cpp)
endif()

# generate the dynamic_reconfigure config file
generate_dynamic_reconfigure_options(
cfg/EdgeDetection.cfg cfg/HoughLines.cfg cfg/HoughCircles.cfg
Expand All @@ -16,8 +26,8 @@ generate_dynamic_reconfigure_options(
cfg/PeopleDetect.cfg
cfg/PhaseCorr.cfg
cfg/SegmentObjects.cfg
cfg/SimpleFlow.cfg
cfg/WatershedSegmentation.cfg
${${PROJECT_NAME}_EXTRA_CFG}
)

## Generate messages in the 'msg' folder
Expand Down Expand Up @@ -65,8 +75,6 @@ generate_messages(

catkin_package()

find_package(OpenCV REQUIRED)

include_directories( ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS})

## Declare a cpp library
Expand Down Expand Up @@ -155,7 +163,7 @@ add_library(${PROJECT_NAME} SHARED
# rgbdodometry.cpp
src/nodelet/segment_objects_nodelet.cpp
## select3dobj.cpp
src/nodelet/simple_flow_nodelet.cpp
# src/nodelet/simple_flow_nodelet.cpp
# squares.cpp
# starter_imagelist.cpp
# starter_video.cpp
Expand All @@ -169,6 +177,7 @@ add_library(${PROJECT_NAME} SHARED
# video_homography.cpp
# videostab.cpp
src/nodelet/watershed_segmentation_nodelet.cpp
${${PROJECT_NAME}_EXTRA_FILES}
)

target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
Expand Down
28 changes: 28 additions & 0 deletions opencv_apps/src/nodelet/camshift_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,12 +190,20 @@ class CamShiftNodelet : public nodelet::Nodelet

switch( event )
{
#if OPENCV3
case cv::EVENT_LBUTTONDOWN:
#else
case CV_EVENT_LBUTTONDOWN:
#endif
origin = cv::Point(x,y);
selection = cv::Rect(x,y,0,0);
selectObject = true;
break;
#if OPENCV3
case cv::EVENT_LBUTTONUP:
#else
case CV_EVENT_LBUTTONUP:
#endif
selectObject = false;
if( selection.width > 0 && selection.height > 0 )
trackObject = -1;
Expand Down Expand Up @@ -223,7 +231,11 @@ class CamShiftNodelet : public nodelet::Nodelet
{
cv::Mat roi(hue, selection), maskroi(mask, selection);
cv::calcHist(&roi, 1, 0, maskroi, hist, 1, &hsize, &phranges);
#if OPENCV3
cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX);
#else
cv::normalize(hist, hist, 0, 255, CV_MINMAX);
#endif
std::vector<float> hist_value;
hist_value.resize(hsize);
for(int i = 0; i < hsize; i ++) { hist_value[i] = hist.at<float>(i);}
Expand All @@ -237,7 +249,11 @@ class CamShiftNodelet : public nodelet::Nodelet
cv::Mat buf(1, hsize, CV_8UC3);
for( int i = 0; i < hsize; i++ )
buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i*180./hsize), 255, 255);
#if OPENCV3
cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
#else
cv::cvtColor(buf, buf, CV_HSV2BGR);
#endif

for( int i = 0; i < hsize; i++ )
{
Expand All @@ -251,7 +267,11 @@ class CamShiftNodelet : public nodelet::Nodelet
cv::calcBackProject(&hue, 1, 0, hist, backproj, &phranges);
backproj &= mask;
cv::RotatedRect trackBox = cv::CamShift(backproj, trackWindow,
#if OPENCV3
cv::TermCriteria( cv::TermCriteria::EPS + cv::TermCriteria::MAX_ITER, 10, 1 ));
#else
cv::TermCriteria( CV_TERMCRIT_EPS | CV_TERMCRIT_ITER, 10, 1 ));
#endif
if( trackWindow.area() <= 1 )
{
int cols = backproj.cols, rows = backproj.rows, r = (MIN(cols, rows) + 5)/6;
Expand All @@ -264,7 +284,11 @@ class CamShiftNodelet : public nodelet::Nodelet

if( backprojMode )
cv::cvtColor( backproj, frame, cv::COLOR_GRAY2BGR );
#if OPENCV3
cv::ellipse( frame, trackBox, cv::Scalar(0,0,255), 3, cv::LINE_AA );
#else
cv::ellipse( frame, trackBox, cv::Scalar(0,0,255), 3, CV_AA );
#endif

rect_msg.rect.angle = trackBox.angle;
opencv_apps::Point2D point_msg;
Expand Down Expand Up @@ -431,7 +455,11 @@ class CamShiftNodelet : public nodelet::Nodelet
cv::Mat buf(1, hsize, CV_8UC3);
for( int i = 0; i < hsize; i++ )
buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i*180./hsize), 255, 255);
#if OPENCV3
cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
#else
cv::cvtColor(buf, buf, CV_HSV2BGR);
#endif

for( int i = 0; i < hsize; i++ )
{
Expand Down
4 changes: 4 additions & 0 deletions opencv_apps/src/nodelet/contour_moments_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@
#include "opencv_apps/MomentArray.h"
#include "opencv_apps/MomentArrayStamped.h"

#if OPENCV3
#include <opencv2/imgproc/types_c.h>
#endif

namespace contour_moments {
class ContourMomentsNodelet : public nodelet::Nodelet
{
Expand Down
4 changes: 4 additions & 0 deletions opencv_apps/src/nodelet/convex_hull_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@
#include "opencv_apps/ContourArray.h"
#include "opencv_apps/ContourArrayStamped.h"

#if OPENCV3
#include <opencv2/imgproc/types_c.h>
#endif

namespace convex_hull {
class ConvexHullNodelet : public nodelet::Nodelet
{
Expand Down
8 changes: 8 additions & 0 deletions opencv_apps/src/nodelet/face_detection_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,11 @@ class FaceDetectionNodelet : public nodelet::Nodelet
cv::cvtColor( frame, frame_gray, cv::COLOR_BGR2GRAY );
cv::equalizeHist( frame_gray, frame_gray );
//-- Detect faces
#if OPENCV3
face_cascade_.detectMultiScale( frame_gray, faces, 1.1, 2, 0, cv::Size(30, 30) );
#else
face_cascade_.detectMultiScale( frame_gray, faces, 1.1, 2, 0 | CV_HAAR_SCALE_IMAGE, cv::Size(30, 30) );
#endif

for( size_t i = 0; i < faces.size(); i++ )
{
Expand All @@ -137,7 +141,11 @@ class FaceDetectionNodelet : public nodelet::Nodelet
std::vector<cv::Rect> eyes;

//-- In each face, detect eyes
#if OPENCV3
eyes_cascade_.detectMultiScale( faceROI, eyes, 1.1, 2, 0, cv::Size(30, 30) );
#else
eyes_cascade_.detectMultiScale( faceROI, eyes, 1.1, 2, 0 | CV_HAAR_SCALE_IMAGE, cv::Size(30, 30) );
#endif

for( size_t j = 0; j < eyes.size(); j++ )
{
Expand Down
4 changes: 4 additions & 0 deletions opencv_apps/src/nodelet/find_contours_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@
#include "opencv_apps/ContourArray.h"
#include "opencv_apps/ContourArrayStamped.h"

#if OPENCV3
#include <opencv2/imgproc/types_c.h>
#endif

namespace find_contours {
class FindContoursNodelet : public nodelet::Nodelet
{
Expand Down
8 changes: 6 additions & 2 deletions opencv_apps/src/nodelet/general_contours_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@
#include "opencv_apps/RotatedRectArray.h"
#include "opencv_apps/RotatedRectArrayStamped.h"

#if OPENCV3
#include <opencv2/imgproc/types_c.h>
#endif

namespace general_contours {
class GeneralContoursNodelet : public nodelet::Nodelet
{
Expand Down Expand Up @@ -148,8 +152,8 @@ class GeneralContoursNodelet : public nodelet::Nodelet
cv::findContours( threshold_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0) );

/// Find the rotated rectangles and ellipses for each contour
cv::vector<cv::RotatedRect> minRect( contours.size() );
cv::vector<cv::RotatedRect> minEllipse( contours.size() );
std::vector<cv::RotatedRect> minRect( contours.size() );
std::vector<cv::RotatedRect> minEllipse( contours.size() );

for( size_t i = 0; i < contours.size(); i++ )
{ minRect[i] = cv::minAreaRect( cv::Mat(contours[i]) );
Expand Down
5 changes: 5 additions & 0 deletions opencv_apps/src/nodelet/hough_circles_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,10 @@
#include "opencv_apps/CircleArray.h"
#include "opencv_apps/CircleArrayStamped.h"

#if OPENCV3
#include <opencv2/imgproc/types_c.h>
#endif

namespace hough_circles {
class HoughCirclesNodelet : public nodelet::Nodelet
{
Expand Down Expand Up @@ -164,6 +168,7 @@ class HoughCirclesNodelet : public nodelet::Nodelet
// runs the actual detection
cv::HoughCircles( src_gray, circles, CV_HOUGH_GRADIENT, 1, src_gray.rows/8, canny_threshold_, accumulator_threshold_, 0, 0 );


// clone the colour, input image for displaying purposes
for( size_t i = 0; i < circles.size(); i++ )
{
Expand Down
12 changes: 12 additions & 0 deletions opencv_apps/src/nodelet/hough_lines_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,11 @@ class HoughLinesNodelet : public nodelet::Nodelet
}

/// Initialize
#if OPENCV3
cv::cvtColor( edges, frame, cv::COLOR_GRAY2BGR );
#else
cv::cvtColor( edges, frame, CV_GRAY2BGR );
#endif

switch (config_.hough_type) {
case hough_lines::HoughLines_Standard_Hough_Transform:
Expand All @@ -166,7 +170,11 @@ class HoughLinesNodelet : public nodelet::Nodelet

cv::Point pt1( cvRound(x0 + alpha*(-sin_t)), cvRound(y0 + alpha*cos_t) );
cv::Point pt2( cvRound(x0 - alpha*(-sin_t)), cvRound(y0 - alpha*cos_t) );
#if OPENCV3
cv::line( frame, pt1, pt2, cv::Scalar(255,0,0), 3, cv::LINE_AA);
#else
cv::line( frame, pt1, pt2, cv::Scalar(255,0,0), 3, CV_AA);
#endif
opencv_apps::Line line_msg;
line_msg.pt1.x = pt1.x;
line_msg.pt1.y = pt1.y;
Expand All @@ -189,7 +197,11 @@ class HoughLinesNodelet : public nodelet::Nodelet
for( size_t i = 0; i < p_lines.size(); i++ )
{
cv::Vec4i l = p_lines[i];
#if OPENCV3
cv::line( frame, cv::Point(l[0], l[1]), cv::Point(l[2], l[3]), cv::Scalar(255,0,0), 3, cv::LINE_AA);
#else
cv::line( frame, cv::Point(l[0], l[1]), cv::Point(l[2], l[3]), cv::Scalar(255,0,0), 3, CV_AA);
#endif
opencv_apps::Line line_msg;
line_msg.pt1.x = l[0];
line_msg.pt1.y = l[1];
Expand Down
6 changes: 5 additions & 1 deletion opencv_apps/src/nodelet/lk_flow_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,11 @@ class LKFlowNodelet : public nodelet::Nodelet
}

// Do the work
#if OPENCV3
cv::TermCriteria termcrit(cv::TermCriteria::MAX_ITER + cv::TermCriteria::EPS, 20, 0.03);
#else
cv::TermCriteria termcrit(CV_TERMCRIT_ITER|CV_TERMCRIT_EPS, 20, 0.03);
#endif
cv::Size subPixWinSize(10,10), winSize(31,31);

cv::cvtColor(image, gray, cv::COLOR_BGR2GRAY);
Expand Down Expand Up @@ -207,7 +211,7 @@ class LKFlowNodelet : public nodelet::Nodelet
{
std::vector<cv::Point2f> tmp;
tmp.push_back(point);
cv::cornerSubPix( gray, tmp, winSize, cvSize(-1,-1), termcrit);
cv::cornerSubPix( gray, tmp, winSize, cv::Size(-1,-1), termcrit);
points[1].push_back(tmp[0]);
addRemovePt = false;
}
Expand Down
5 changes: 5 additions & 0 deletions opencv_apps/src/nodelet/phase_corr_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,8 +145,13 @@ class PhaseCorrNodelet : public nodelet::Nodelet
{
// draw a circle and line indicating the shift direction...
cv::Point center(curr.cols >> 1, curr.rows >> 1);
#if OPENCV3
cv::circle(frame, center, (int)radius, cv::Scalar(0, 255, 0), 3, cv::LINE_AA);
cv::line(frame, center, cv::Point(center.x + (int)shift.x, center.y + (int)shift.y), cv::Scalar(0, 255, 0), 3, cv::LINE_AA);
#else
cv::circle(frame, center, (int)radius, cv::Scalar(0, 255, 0), 3, CV_AA);
cv::line(frame, center, cv::Point(center.x + (int)shift.x, center.y + (int)shift.y), cv::Scalar(0, 255, 0), 3, CV_AA);
#endif

//
shift_msg.point.x = shift.x;
Expand Down
20 changes: 19 additions & 1 deletion opencv_apps/src/nodelet/segment_objects_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,12 @@
#include "opencv_apps/ContourArray.h"
#include "opencv_apps/ContourArrayStamped.h"

#if OPENCV3
#include <opencv2/imgproc/types_c.h>
#include <opencv2/imgproc/imgproc_c.h>
#include <opencv2/video.hpp>
#endif

namespace segment_objects {
class SegmentObjectsNodelet : public nodelet::Nodelet
{
Expand All @@ -76,7 +82,11 @@ class SegmentObjectsNodelet : public nodelet::Nodelet
std::string window_name_;
static bool need_config_update_;

cv::BackgroundSubtractorMOG bgsubtractor;
#if OPENCV3
cv::Ptr<cv::BackgroundSubtractorMOG2> bgsubtractor;
#else
cv::BackgroundSubtractorMOG2 bgsubtractor;
#endif
bool update_bg_model = true;

void reconfigureCallback(segment_objects::SegmentObjectsConfig &new_config, uint32_t level)
Expand Down Expand Up @@ -135,7 +145,11 @@ class SegmentObjectsNodelet : public nodelet::Nodelet
}
}

#if OPENCV3
bgsubtractor->apply(frame, bgmask, update_bg_model ? -1 : 0);
#else
bgsubtractor(frame, bgmask, update_bg_model ? -1 : 0);
#endif
//refineSegments(tmp_frame, bgmask, out_frame);
int niters = 3;

Expand Down Expand Up @@ -277,7 +291,11 @@ class SegmentObjectsNodelet : public nodelet::Nodelet
prev_stamp_ = ros::Time(0, 0);

window_name_ = "segmented";
#if OPENCV3
bgsubtractor = cv::createBackgroundSubtractorMOG2();
#else
bgsubtractor.set("noiseSigma", 10);
#endif

image_transport::SubscriberStatusCallback img_connect_cb = boost::bind(&SegmentObjectsNodelet::img_connectCb, this, _1);
image_transport::SubscriberStatusCallback img_disconnect_cb = boost::bind(&SegmentObjectsNodelet::img_disconnectCb, this, _1);
Expand Down
16 changes: 16 additions & 0 deletions opencv_apps/src/nodelet/watershed_segmentation_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,10 @@
#include <dynamic_reconfigure/server.h>
#include "opencv_apps/WatershedSegmentationConfig.h"

#if OPENCV3
#include <opencv2/imgproc/types_c.h>
#endif

namespace watershed_segmentation {
class WatershedSegmentationNodelet : public nodelet::Nodelet
{
Expand Down Expand Up @@ -157,11 +161,23 @@ class WatershedSegmentationNodelet : public nodelet::Nodelet

if( x < 0 || x >= frame.cols || y < 0 || y >= frame.rows )
return;
#if OPENCV3
if( event == cv::EVENT_LBUTTONUP || !(flags & cv::EVENT_FLAG_LBUTTON) )
#else
if( event == CV_EVENT_LBUTTONUP || !(flags & CV_EVENT_FLAG_LBUTTON) )
#endif
prevPt = cv::Point(-1,-1);
#if OPENCV3
else if( event == cv::EVENT_LBUTTONDOWN )
#else
else if( event == CV_EVENT_LBUTTONDOWN )
#endif
prevPt = cv::Point(x,y);
#if OPENCV3
else if( event == cv::EVENT_MOUSEMOVE && (flags & cv::EVENT_FLAG_LBUTTON) )
#else
else if( event == CV_EVENT_MOUSEMOVE && (flags & CV_EVENT_FLAG_LBUTTON) )
#endif
{
cv::Point pt(x, y);
if( prevPt.x < 0 )
Expand Down

0 comments on commit 89a933a

Please sign in to comment.