diff --git a/launch/face_detection.launch b/launch/face_detection.launch index aa75ca81..d42a244f 100644 --- a/launch/face_detection.launch +++ b/launch/face_detection.launch @@ -2,7 +2,8 @@ - + + @@ -17,6 +18,10 @@ name="face_cascade_name" default="$(find opencv3)/../OpenCV-3.2.0-dev/haarcascades/haarcascade_frontalface_alt.xml" doc="Face dtection cascade Filename" /> + + + @@ -18,6 +19,7 @@ + = 3 && CV_MINOR_VERSION >= 3 + model_ = face::EigenFaceRecognizer::create(config.model_num_components, + config.model_threshold); +#else model_ = face::createEigenFaceRecognizer(config.model_num_components, config.model_threshold); +#endif } else if (config.model_method == "fisher") { +#if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3 + model_ = face::FisherFaceRecognizer::create(config.model_num_components, + config.model_threshold); +#else model_ = face::createFisherFaceRecognizer(config.model_num_components, config.model_threshold); +#endif } else if (config.model_method == "LBPH") { +#if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 3 + model_ = face::LBPHFaceRecognizer::create(config.lbph_radius, + config.lbph_neighbors, + config.lbph_grid_x, + config.lbph_grid_y); +#else model_ = face::createLBPHFaceRecognizer(config.lbph_radius, config.lbph_neighbors, config.lbph_grid_x, config.lbph_grid_y); +#endif } need_retrain = true; } catch (cv::Exception &e) { diff --git a/src/nodelet/lk_flow_nodelet.cpp b/src/nodelet/lk_flow_nodelet.cpp index 24825adc..533e5ab8 100644 --- a/src/nodelet/lk_flow_nodelet.cpp +++ b/src/nodelet/lk_flow_nodelet.cpp @@ -159,7 +159,7 @@ class LKFlowNodelet : public opencv_apps::Nodelet if( needToInit ) { // automatic initialization - cv::goodFeaturesToTrack(gray, points[1], MAX_COUNT, 0.01, 10, cv::Mat(), 3, 0, 0.04); + cv::goodFeaturesToTrack(gray, points[1], MAX_COUNT, 0.01, 10, cv::Mat(), 3, false, 0.04); cv::cornerSubPix(gray, points[1], subPixWinSize, cv::Size(-1,-1), termcrit); addRemovePt = false; } diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 8d0e7b23..5f713e7c 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -43,14 +43,15 @@ if(cv_bridge_VERSION VERSION_LESS "1.11.9") # hydro skip face_detection.test elseif(OpenCV_VERSION VERSION_LESS "3.0") add_rostest(test-face_detection.test ARGS gui:=false) add_rostest(test-face_recognition.test ARGS gui:=false) +elseif(OpenCV_VERSION VERSION_LESS "3.2") + add_rostest(test-face_detection.test ARGS gui:=false use_opencv3:=true use_opencv3_1:=true) + add_rostest(test-face_recognition.test ARGS gui:=false use_opencv3:=true use_opencv3_1:=true) +elseif(OpenCV_VERSION VERSION_LESS "3.3") + add_rostest(test-face_detection.test ARGS gui:=false use_opencv3:=true use_opencv3_2:=true) + add_rostest(test-face_recognition.test ARGS gui:=false use_opencv3:=true use_opencv3_2:=true) else() - if(OpenCV_VERSION VERSION_LESS "3.2") - add_rostest(test-face_detection.test ARGS gui:=false use_opencv3:=true use_opencv3_1:=true) - add_rostest(test-face_recognition.test ARGS gui:=false use_opencv3:=true use_opencv3_1:=true) - else() - add_rostest(test-face_detection.test ARGS gui:=false use_opencv3:=true use_opencv3_2:=true) - add_rostest(test-face_recognition.test ARGS gui:=false use_opencv3:=true use_opencv3_2:=true) - endif() + add_rostest(test-face_detection.test ARGS gui:=false use_opencv3:=true use_opencv3_3:=true) + add_rostest(test-face_recognition.test ARGS gui:=false use_opencv3:=true use_opencv3_3:=true) endif() add_rostest(test-goodfeature_track.test ARGS gui:=false) add_rostest(test-corner_harris.test ARGS gui:=false) diff --git a/test/test-face_detection.test b/test/test-face_detection.test index decd9b9e..fb604056 100644 --- a/test/test-face_detection.test +++ b/test/test-face_detection.test @@ -3,6 +3,7 @@ + @@ -16,6 +17,7 @@ + diff --git a/test/test-face_recognition.test b/test/test-face_recognition.test index fd8a1b21..a4606b4b 100644 --- a/test/test-face_recognition.test +++ b/test/test-face_recognition.test @@ -3,6 +3,7 @@ + @@ -18,6 +19,7 @@ +