From 94ef334a38ccefa9b2a3e51ac28e488bf11817a8 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 11 Dec 2024 09:53:46 +0100 Subject: [PATCH] Introduce compat with OpenCV 5.0.0 - where instead of opencv_calib3d we use opencv_calib and opencv_3d modules - where instead of opencv_features2d we use opencv_features - clean a lot OpenCV modules detection Clean also known non optimal behavior of command line options --- CMakeLists.txt | 18 +- apps/CMakeLists.txt | 2 +- apps/calibration/CMakeLists.txt | 2 +- .../visp-compute-chessboard-poses.cpp | 53 ++- cmake/templates/VISPConfig.cmake.in | 3 +- cmake/templates/vpConfig.h.in | 10 +- doc/config-doxygen.in | 6 +- ...rial-tracking-mb-generic-apriltag-live.dox | 4 +- .../visual-servo/tutorial-franka-ibvs.dox | 2 +- .../visual-servo/tutorial-franka-pbvs.dox | 2 +- .../tutorial-universal-robot-ibvs.dox | 4 +- .../tutorial-universal-robot-pbvs.dox | 4 +- example/calibration/calibrate-camera.cpp | 33 +- example/math/quadprog.cpp | 8 +- example/math/quadprog_eq.cpp | 8 +- example/reflex-takktile/takktile2-control.cpp | 38 +- .../reflex-takktile/takktile2-read-data.cpp | 30 +- example/servo-bebop2/servoBebop2.cpp | 2 +- .../servoUniversalRobotsIBVS.cpp | 6 +- .../servoUniversalRobotsPBVS.cpp | 6 +- modules/core/CMakeLists.txt | 2 +- modules/core/include/visp3/core/vpConvert.h | 11 +- .../core/include/visp3/core/vpImageConvert.h | 2 + .../core/include/visp3/core/vpImageFilter.h | 2 + .../visp3/core/vpMeterPixelConversion.h | 6 +- .../visp3/core/vpPixelMeterConversion.h | 9 +- .../src/camera/vpMeterPixelConversion.cpp | 10 +- .../src/camera/vpPixelMeterConversion.cpp | 33 +- modules/core/src/tools/convert/vpConvert.cpp | 7 +- .../camera/testCameraParametersConversion.cpp | 4 +- .../core/test/tools/serial/testSerialRead.cpp | 18 +- .../test/tools/serial/testSerialWrite.cpp | 11 +- modules/detection/CMakeLists.txt | 4 +- .../include/visp3/detection/vpDetectorFace.h | 13 +- modules/detection/src/face/vpDetectorFace.cpp | 26 +- modules/gui/src/display/vpDisplayOpenCV.cpp | 3 +- .../testDisplayScaled.cpp | 13 +- modules/robot/test/virtuose/testVirtuose.cpp | 12 +- .../test/virtuose/testVirtuoseHapticBox.cpp | 12 +- .../test/virtuose/testVirtuoseJointLimits.cpp | 17 +- .../testForceTorqueAtiNetFTSensor.cpp | 18 +- .../force-torque/testForceTorqueIitSensor.cpp | 15 +- .../mbt/include/visp3/mbt/vpMbEdgeTracker.h | 2 + .../tracker/me/src/moving-edges/vpMeNurbs.cpp | 2 + modules/vision/CMakeLists.txt | 4 +- .../vision/include/visp3/vision/vpKeyPoint.h | 202 ++++++--- modules/vision/src/key-point/vpKeyPoint.cpp | 404 +++++++++++------- .../src/pose-estimation/vpPoseRansac.cpp | 1 - .../keypoint-with-dataset/testKeyPoint-2.cpp | 48 +-- .../keypoint-with-dataset/testKeyPoint-3.cpp | 37 +- .../keypoint-with-dataset/testKeyPoint-4.cpp | 62 ++- .../keypoint-with-dataset/testKeyPoint-5.cpp | 60 ++- .../keypoint-with-dataset/testKeyPoint-6.cpp | 52 +-- .../keypoint-with-dataset/testKeyPoint-7.cpp | 8 +- .../keypoint-with-dataset/testKeyPoint.cpp | 62 ++- tutorial/bridge/opencv/CMakeLists.txt | 2 +- .../tutorial-bridge-opencv-camera-param.cpp | 30 +- .../opencv/tutorial-bridge-opencv-image.cpp | 67 +-- .../opencv/tutorial-bridge-opencv-matrix.cpp | 15 +- .../tutorial-pose-from-planar-object.cpp | 6 +- .../tutorial-pose-from-points-live.cpp | 63 +-- ...torial-pose-from-points-realsense-T265.cpp | 13 +- .../tutorial-barcode-detector-live.cpp | 17 +- .../barcode/tutorial-barcode-detector.cpp | 11 +- .../tutorial-face-detector-live-threaded.cpp | 63 ++- .../face/tutorial-face-detector-live.cpp | 43 +- .../detection/face/tutorial-face-detector.cpp | 37 +- .../tutorial-matching-keypoint-SIFT.cpp | 6 +- .../tutorial-matching-keypoint-homography.cpp | 9 +- .../matching/tutorial-matching-keypoint.cpp | 2 +- tutorial/detection/object/cube.cao | 32 +- ...torial-detection-object-mbt-deprecated.cpp | 22 +- .../object/tutorial-detection-object-mbt.cpp | 20 +- ...orial-detection-object-mbt2-deprecated.cpp | 29 +- .../object/tutorial-detection-object-mbt2.cpp | 32 +- ...-apriltag-detector-live-T265-realsense.cpp | 54 +-- ...-apriltag-detector-live-rgbd-realsense.cpp | 52 +-- ...ltag-detector-live-rgbd-structure-core.cpp | 54 +-- .../tag/tutorial-apriltag-detector-live.cpp | 68 +-- .../tag/tutorial-apriltag-detector.cpp | 58 +-- tutorial/grabber/tutorial-grabber-1394.cpp | 10 +- .../grabber/tutorial-grabber-basler-pylon.cpp | 18 +- tutorial/grabber/tutorial-grabber-bebop2.cpp | 10 +- .../grabber/tutorial-grabber-flycapture.cpp | 8 +- .../grabber/tutorial-grabber-ids-ueye.cpp | 42 +- .../tutorial-grabber-multiple-realsense.cpp | 16 +- .../tutorial-grabber-opencv-threaded.cpp | 9 +- tutorial/grabber/tutorial-grabber-opencv.cpp | 19 +- .../tutorial-grabber-realsense-T265.cpp | 12 +- .../grabber/tutorial-grabber-realsense.cpp | 25 +- .../tutorial-grabber-structure-core.cpp | 15 +- .../tutorial-grabber-v4l2-threaded.cpp | 15 +- tutorial/grabber/tutorial-grabber-v4l2.cpp | 20 +- tutorial/grabber/tutorial-video-reader.cpp | 10 +- tutorial/grabber/tutorial-video-recorder.cpp | 8 +- .../visp/mbot-apriltag-2D-half-vs.cpp | 20 +- .../tutorial-klt-tracker-live-v4l2.cpp | 10 +- .../keypoint/tutorial-klt-tracker.cpp | 17 +- ...torial-mb-generic-tracker-apriltag-rs2.cpp | 18 +- ...ial-mb-generic-tracker-apriltag-webcam.cpp | 20 +- ...rial-mb-generic-tracker-rgbd-realsense.cpp | 15 +- ...mb-generic-tracker-rgbd-structure-core.cpp | 18 +- ...utorial-mb-generic-tracker-stereo-mono.cpp | 18 +- .../tutorial-mb-generic-tracker-stereo.cpp | 16 +- .../model-based/generic/CMakeLists.txt | 2 +- .../tutorial-mb-generic-tracker-full.cpp | 18 +- .../tutorial-mb-generic-tracker-live.cpp | 49 +-- .../generic/tutorial-mb-generic-tracker.cpp | 23 +- .../old/edges/tutorial-mb-edge-tracker.cpp | 11 +- .../old/generic/tutorial-mb-tracker-full.cpp | 23 +- .../old/generic/tutorial-mb-tracker.cpp | 25 +- .../old/hybrid/tutorial-mb-hybrid-tracker.cpp | 7 +- .../old/keypoint/tutorial-mb-klt-tracker.cpp | 13 +- .../tutorial-template-tracker.cpp | 20 +- 114 files changed, 1594 insertions(+), 1224 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6635e2b875..9ec0d3afa7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1214,25 +1214,9 @@ if(USE_LIBFREENECT AND USE_LIBUSB_1 AND USE_THREADS) endif() endif() -# check OpenCV nonfree modules and version +# OpenCV version if(USE_OPENCV) set(VISP_HAVE_OPENCV_VERSION "(${OpenCV_VERSION_MAJOR}<<16 | ${OpenCV_VERSION_MINOR}<<8 | ${OpenCV_VERSION_PATCH})") # for vpConfig.h - if(OpenCV_VERSION) - if(OpenCV_VERSION VERSION_LESS "2.4.0") - message(STATUS "opencv nonfree module found") - set(VISP_HAVE_OPENCV_NONFREE TRUE) # for header vpConfig.h - elseif(OPENCV_NONFREE_FOUND) # OpenCV < 3.0.0 - message(STATUS "opencv xfeatures2d module found") - set(VISP_HAVE_OPENCV_NONFREE TRUE) # for header vpConfig.h - elseif(OPENCV_XFEATURES2D_FOUND) # OpenCV >= 3.0.0 - set(VISP_HAVE_OPENCV_XFEATURES2D TRUE) # for header vpConfig.h - else() - message(STATUS "opencv nonfree or xfeature2d module not found") - endif() - else() - message(STATUS "opencv nonfree not found") - set(VISP_HAVE_OPENCV_VERSION "(0)") # for vpConfig.h - endif() endif() # coin and gui diff --git a/apps/CMakeLists.txt b/apps/CMakeLists.txt index 2737090285..44742ba031 100644 --- a/apps/CMakeLists.txt +++ b/apps/CMakeLists.txt @@ -1,7 +1,7 @@ ############################################################################# # # ViSP, open source Visual Servoing Platform software. -# Copyright (C) 2005 - 2023 by Inria. All rights reserved. +# Copyright (C) 2005 - 2024 by Inria. All rights reserved. # # This software is free software; you can redistribute it and/or modify # it under the terms of the GNU General Public License as published by diff --git a/apps/calibration/CMakeLists.txt b/apps/calibration/CMakeLists.txt index 952dacffee..cfe1f34b37 100644 --- a/apps/calibration/CMakeLists.txt +++ b/apps/calibration/CMakeLists.txt @@ -17,7 +17,7 @@ if(VISP_HAVE_UR_RTDE) list(APPEND apps_cpp visp-acquire-universal-robots-calib-data.cpp) endif() -file(GLOB apps_data "*.yaml" "*.py" "camera.xml" "*.png") +file(GLOB apps_data "*.yaml" "*.py" "camera.xml" "*.jpg") foreach(cpp ${apps_cpp}) visp_add_app(${cpp}) diff --git a/apps/calibration/visp-compute-chessboard-poses.cpp b/apps/calibration/visp-compute-chessboard-poses.cpp index a13cd6776a..311df186e8 100644 --- a/apps/calibration/visp-compute-chessboard-poses.cpp +++ b/apps/calibration/visp-compute-chessboard-poses.cpp @@ -1,6 +1,6 @@ /* * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -36,9 +36,14 @@ #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) && defined(VISP_HAVE_PUGIXML) +#if defined(VISP_HAVE_PUGIXML) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_HIGHGUI) && \ + (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_CALIB))) +#if defined(HAVE_OPENCV_CALIB3D) #include +#elif defined(HAVE_OPENCV_CALIB) +#include +#endif #include #include #include @@ -101,7 +106,7 @@ void usage(const char **argv, int error) << std::endl << " --input Generic name of the images to process." << std::endl << " Default: empty" << std::endl - << " Example: \"image-%d.png\"" << std::endl + << " Example: \"image-%d.jpg\"" << std::endl << std::endl << " --intrinsic XML file that contains" << std::endl << " camera parameters. " << std::endl @@ -120,6 +125,11 @@ void usage(const char **argv, int error) #endif << " --help, -h Print this helper message." << std::endl << std::endl; + std::cout << "Example" << std::endl + << " " + << argv[0] + << " --input image-%d.jpg" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl << " " @@ -140,32 +150,25 @@ int main(int argc, const char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "-w" && i + 1 < argc) { - opt_chessboard_width = atoi(argv[i + 1]); - i++; + opt_chessboard_width = atoi(argv[++i]); } else if (std::string(argv[i]) == "-h" && i + 1 < argc) { - opt_chessboard_height = atoi(argv[i + 1]); - i++; + opt_chessboard_height = atoi(argv[++i]); } else if (std::string(argv[i]) == "--square-size" && i + 1 < argc) { - opt_chessboard_square_size = atof(argv[i + 1]); - i++; + opt_chessboard_square_size = atof(argv[++i]); } else if (std::string(argv[i]) == "--input" && i + 1 < argc) { - opt_input_img_files = std::string(argv[i + 1]); - i++; + opt_input_img_files = std::string(argv[++i]); } else if (std::string(argv[i]) == "--intrinsic" && i + 1 < argc) { - opt_intrinsic_file = std::string(argv[i + 1]); - i++; + opt_intrinsic_file = std::string(argv[++i]); } else if (std::string(argv[i]) == "--output" && i + 1 < argc) { - opt_output_pose_files = std::string(argv[i + 1]); - i++; + opt_output_pose_files = std::string(argv[++i]); } else if (std::string(argv[i]) == "--camera-name" && i + 1 < argc) { - opt_camera_name = std::string(argv[i + 1]); - i++; + opt_camera_name = std::string(argv[++i]); } #if defined(VISP_HAVE_MODULE_GUI) else if (std::string(argv[i]) == "--no-interactive") { @@ -213,7 +216,6 @@ int main(int argc, const char **argv) std::cout << " Output camera poses : " << opt_output_pose_files << std::endl; std::cout << " Interactive mode : " << (opt_interactive ? "yes" : "no") << std::endl << std::endl; - #if defined(VISP_HAVE_MODULE_GUI) vpDisplay *display = nullptr; if (opt_interactive) { @@ -228,7 +230,7 @@ int main(int argc, const char **argv) #elif defined(VISP_HAVE_GTK) display = new vpDisplayGTK(I); #endif - } + } #endif std::vector corners_pts; @@ -339,7 +341,7 @@ int main(int argc, const char **argv) } } #endif -} + } catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } @@ -349,9 +351,18 @@ int main(int argc, const char **argv) #else int main() { -#if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D)) +#if !defined(HAVE_OPENCV_IMGPROC) + std::cerr << "OpenCV imgproc module is requested to run the calibration." << std::endl; +#endif +#if !defined(HAVE_OPENCV_HIGHGUI) + std::cerr << "OpenCV highgui module is requested to run the calibration." << std::endl; +#endif +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) && !defined(HAVE_OPENCV_CALIB3D) std::cerr << "OpenCV calib3d module is requested to run the calibration." << std::endl; #endif +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) && !defined(HAVE_OPENCV_3D) + std::cerr << "OpenCV 3d module is requested to run the calibration." << std::endl; +#endif #if !defined(VISP_HAVE_PUGIXML) std::cout << "pugixml built-in 3rdparty is requested to run the calibration." << std::endl; #endif diff --git a/cmake/templates/VISPConfig.cmake.in b/cmake/templates/VISPConfig.cmake.in index 2e3f786289..1fe371669e 100644 --- a/cmake/templates/VISPConfig.cmake.in +++ b/cmake/templates/VISPConfig.cmake.in @@ -240,11 +240,10 @@ set(VISP_HAVE_OGRE "@VISP_HAVE_OGRE@") set(VISP_HAVE_OIS "@VISP_HAVE_OIS@") set(VISP_HAVE_OPENBLAS "@VISP_HAVE_OPENBLAS@") set(VISP_HAVE_OPENCV "@VISP_HAVE_OPENCV@") -set(VISP_HAVE_OPENCV_NONFREE "@VISP_HAVE_OPENCV_NONFREE@") set(VISP_HAVE_OPENCV_VERSION "@VISP_HAVE_OPENCV_VERSION@") set(VISP_HAVE_OPENGL "@VISP_HAVE_OPENGL@") set(VISP_HAVE_OPENMP "@VISP_HAVE_OPENMP@") -set(VISP_HAVE_PANDA3D "@VISP_HAVE_PANDA3D@") +set(VISP_HAVE_PANDA3D "@VISP_HAVE_PANDA3D@") set(VISP_HAVE_PARPORT "@VISP_HAVE_PARPORT@") set(VISP_HAVE_PCL "@VISP_HAVE_PCL@") set(VISP_HAVE_PIONEER "@VISP_HAVE_PIONEER@") diff --git a/cmake/templates/vpConfig.h.in b/cmake/templates/vpConfig.h.in index 1703725de2..6750fa4b31 100644 --- a/cmake/templates/vpConfig.h.in +++ b/cmake/templates/vpConfig.h.in @@ -177,12 +177,6 @@ namespace vp = VISP_NAMESPACE_NAME; // Defined if OpenCV available. #cmakedefine VISP_HAVE_OPENCV -// Defined if OpenCV nonfree module available. Only with OpenCV < 3.0.0 -#cmakedefine VISP_HAVE_OPENCV_NONFREE - -// Defined if OpenCV xfeatures2d module available. Only since OpenCV >= 3.0.0 -#cmakedefine VISP_HAVE_OPENCV_XFEATURES2D - // OpenCV version in hexadecimal (for example 2.1.0 gives 0x020100). #ifdef VISP_HAVE_OPENCV # define VISP_HAVE_OPENCV_VERSION ${VISP_HAVE_OPENCV_VERSION} @@ -190,6 +184,10 @@ namespace vp = VISP_NAMESPACE_NAME; #endif // For compat with previous releases +#if defined(HAVE_OPENCV_XFEATURES2D) +#define VISP_HAVE_OPENCV_XFEATURES2D +#endif + #if defined(HAVE_OPENCV_OBJDETECT) #define VISP_HAVE_OPENCV_OBJDETECT #endif diff --git a/doc/config-doxygen.in b/doc/config-doxygen.in index 8aa93cba61..972492467e 100644 --- a/doc/config-doxygen.in +++ b/doc/config-doxygen.in @@ -2400,10 +2400,12 @@ PREDEFINED = @DOXYGEN_SHOULD_SKIP_THIS@ \ VISP_HAVE_OGRE_RESOURCES_PATH \ VISP_HAVE_OIS \ VISP_HAVE_OPENCV \ - VISP_HAVE_OPENCV_NONFREE \ VISP_HAVE_OPENCV_VERSION=0x030403 \ + HAVE_OPENCV_3D \ + HAVE_OPENCV_CALIB \ HAVE_OPENCV_CALIB3D \ HAVE_OPENCV_DNN \ + HAVE_OPENCV_FEATURES \ HAVE_OPENCV_FEATURES2D \ HAVE_OPENCV_HIGHGUI \ HAVE_OPENCV_IMGCODECS \ @@ -2411,6 +2413,8 @@ PREDEFINED = @DOXYGEN_SHOULD_SKIP_THIS@ \ HAVE_OPENCV_OBJDETECT \ HAVE_OPENCV_VIDEO \ HAVE_OPENCV_VIDEOIO \ + HAVE_OPENCV_XFEATURES2D \ + HAVE_OPENCV_XOBJDETECT \ VISP_HAVE_OPENGL \ VISP_HAVE_PANDA3D \ VISP_HAVE_PARPORT \ diff --git a/doc/tutorial/tracking/tutorial-tracking-mb-generic-apriltag-live.dox b/doc/tutorial/tracking/tutorial-tracking-mb-generic-apriltag-live.dox index 700796faed..7addccd264 100644 --- a/doc/tutorial/tracking/tutorial-tracking-mb-generic-apriltag-live.dox +++ b/doc/tutorial/tracking/tutorial-tracking-mb-generic-apriltag-live.dox @@ -105,7 +105,7 @@ tutorials given in \ref tutorial_install_src. Once build, to see the options that are available, just run: \code $ ./tutorial-mb-generic-tracker-apriltag-webcam --help -Usage: ./tutorial-mb-generic-tracker-apriltag-webcam [--input ] [--cube_size ] [--tag_size ] [--quad_decimate ] [--nthreads ] [--intrinsic ] [--camera_name ] [--tag_family <0: TAG_36h11, 1: TAG_36h10, 2: TAG_36ARTOOLKIT, 3: TAG_25h9, 4: TAG_25h7, 5: TAG_16h5>] [--display_off] [--texture] [--projection_error <30 - 100>] [--help] +Usage: ./tutorial-mb-generic-tracker-apriltag-webcam [--input ] [--cube_size ] [--tag-size ] [--quad-decimate ] [--nthreads ] [--intrinsic ] [--camera-name ] [--tag-family <0: TAG_36h11, 1: TAG_36h10, 2: TAG_36ARTOOLKIT, 3: TAG_25h9, 4: TAG_25h7, 5: TAG_16h5>] [--display-off] [--texture] [--projection_error <30 - 100>] [--help] \endcode To test the tracker on a 12.5 cm wide cube that has an AprilTag of size 8 by 8 cm, and enable moving-edges and @@ -202,7 +202,7 @@ provided in the tutorials available from \ref tutorial_install_src. Once build, to see the options that are available, just run: \code $ ./tutorial-mb-generic-tracker-apriltag-rs2 --help -Usage: ./tutorial-mb-generic-tracker-apriltag-rs2 [--cube_size ] [--tag_size ] [--quad_decimate ] [--nthreads ] [--tag_family <0: TAG_36h11, 1: TAG_36h10, 2: TAG_36ARTOOLKIT, 3: TAG_25h9, 4: TAG_25h7, 5: TAG_16h5>] [--display_off] [--texture] [--depth] [--projection_error <30 - 100>] [--help] +Usage: ./tutorial-mb-generic-tracker-apriltag-rs2 [--cube_size ] [--tag-size ] [--quad-decimate ] [--nthreads ] [--tag-family <0: TAG_36h11, 1: TAG_36h10, 2: TAG_36ARTOOLKIT, 3: TAG_25h9, 4: TAG_25h7, 5: TAG_16h5>] [--display-off] [--texture] [--depth] [--projection_error <30 - 100>] [--help] \endcode To test the tracker on a 12.5 cm wide cube that has an AprilTag of size 8 by 8 cm, and enable moving-edges, keypoints diff --git a/doc/tutorial/visual-servo/tutorial-franka-ibvs.dox b/doc/tutorial/visual-servo/tutorial-franka-ibvs.dox index 3e8014e71b..99755ddc99 100644 --- a/doc/tutorial/visual-servo/tutorial-franka-ibvs.dox +++ b/doc/tutorial/visual-servo/tutorial-franka-ibvs.dox @@ -22,7 +22,7 @@ Now enter in `example/servo-franka folder` and run `servoFrankaIBVS` binary usin $ cd example/servo-franka $ ./servoFrankaIBVS --help - ./servoFrankaIBVS [--ip ] [--tag_size ] [--eMc ] [--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h] + ./servoFrankaIBVS [--ip ] [--tag-size ] [--eMc ] [--quad-decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h] Run the binary activating the plot and using a constant gain: diff --git a/doc/tutorial/visual-servo/tutorial-franka-pbvs.dox b/doc/tutorial/visual-servo/tutorial-franka-pbvs.dox index 40d2999005..ef836365f6 100644 --- a/doc/tutorial/visual-servo/tutorial-franka-pbvs.dox +++ b/doc/tutorial/visual-servo/tutorial-franka-pbvs.dox @@ -264,7 +264,7 @@ Now enter in `example/servo-franka folder` and run `servoFrankaPBVS` binary usin $ cd example/servo-franka $ ./servoFrankaPBVS --help - ./servoFrankaPBVS [--ip ] [--tag_size ] [--eMc ] [--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h] + ./servoFrankaPBVS [--ip ] [--tag-size ] [--eMc ] [--quad-decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h] Run the binary activating the plot and using a constant gain: diff --git a/doc/tutorial/visual-servo/tutorial-universal-robot-ibvs.dox b/doc/tutorial/visual-servo/tutorial-universal-robot-ibvs.dox index 715f2dad90..27a918b08a 100644 --- a/doc/tutorial/visual-servo/tutorial-universal-robot-ibvs.dox +++ b/doc/tutorial/visual-servo/tutorial-universal-robot-ibvs.dox @@ -135,8 +135,8 @@ Now enter in `example/servo-universal-robots folder` and run `servoUniversalRobo \verbatim $ cd example/servo-universal-robots $ ./servoUniversalRobotsIBVS --help -./servoUniversalRobotsIBVS [--ip ] [--tag_size ] \ - [--eMc ] [--quad_decimate ] \ +./servoUniversalRobotsIBVS [--ip ] [--tag-size ] \ + [--eMc ] [--quad-decimate ] \ [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] \ [--verbose] [--help] [-h] \endverbatim diff --git a/doc/tutorial/visual-servo/tutorial-universal-robot-pbvs.dox b/doc/tutorial/visual-servo/tutorial-universal-robot-pbvs.dox index e388bdde50..3128828df3 100644 --- a/doc/tutorial/visual-servo/tutorial-universal-robot-pbvs.dox +++ b/doc/tutorial/visual-servo/tutorial-universal-robot-pbvs.dox @@ -18,8 +18,8 @@ Now enter in `example/servo-universal-robots folder` and run `servoUniversalRobo \verbatim $ cd example/servo-universal-robots $ ./servoUniversalRobotsPBVS --help -./servoUniversalRobotsPBVS [--ip ] [--tag_size ] \ - [--eMc ] [--quad_decimate ] \ +./servoUniversalRobotsPBVS [--ip ] [--tag-size ] \ + [--eMc ] [--quad-decimate ] \ [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] \ [--verbose] [--help] [-h] \endverbatim diff --git a/example/calibration/calibrate-camera.cpp b/example/calibration/calibrate-camera.cpp index dc6059fa6f..8ba5462ea5 100644 --- a/example/calibration/calibrate-camera.cpp +++ b/example/calibration/calibrate-camera.cpp @@ -1,7 +1,6 @@ -/**************************************************************************** - * +/* * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -30,18 +29,21 @@ * * Description: * Camera calibration with chessboard or circle calibration grid. - * -*****************************************************************************/ + */ #include #include -#if (VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_CALIB3D) && defined(HAVE_OPENCV_HIGHGUI) && \ - defined(HAVE_OPENCV_IMGPROC) && defined(VISP_HAVE_PUGIXML) +#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(VISP_HAVE_PUGIXML) \ + && (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_3D))) #include +#if defined(HAVE_OPENCV_CALIB3D) #include +#elif defined(HAVE_OPENCV_CALIB) +#include +#endif #include #include #include @@ -674,14 +676,21 @@ int main(int argc, const char *argv[]) #else int main() { -#if !((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_CALIB3D) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) - std::cout << "OpenCV calib3d, highgui and imgproc modules are requested to run the calibration." << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Install OpenCV, configure again ViSP using cmake and build again this example" << std::endl; +#if !defined(HAVE_OPENCV_IMGPROC) + std::cout << "This example requires OpenCV imgproc module." << std::endl; +#endif +#if !defined(HAVE_OPENCV_HIGHGUI) + std::cout << "This example requires OpenCV highgui module." << std::endl; +#endif +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) && !defined(HAVE_OPENCV_CALIB3D) + std::cout << "This example requires OpenCV calib3d module." << std::endl; +#endif +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) && !defined(HAVE_OPENCV_3D) + std::cout << "This example requires OpenCV 3d module." << std::endl; #endif #if !defined(VISP_HAVE_PUGIXML) std::cout << "pugixml built-in 3rdparty is requested to run the calibration." << std::endl; #endif return EXIT_SUCCESS; - } +} #endif diff --git a/example/math/quadprog.cpp b/example/math/quadprog.cpp index 617d08f31e..754d1e3b4f 100644 --- a/example/math/quadprog.cpp +++ b/example/math/quadprog.cpp @@ -69,12 +69,14 @@ int main(int argc, char **argv) bool opt_click_allowed = true; #endif - for (int i = 0; i < argc; i++) { + for (int i = 1; i < argc; i++) { #ifdef VISP_HAVE_DISPLAY - if (std::string(argv[i]) == "-d") + if (std::string(argv[i]) == "-d") { opt_display = false; - else if (std::string(argv[i]) == "-c") + } + else if (std::string(argv[i]) == "-c") { opt_click_allowed = false; + } else #endif if (std::string(argv[i]) == "-h" || std::string(argv[i]) == "--help") { diff --git a/example/math/quadprog_eq.cpp b/example/math/quadprog_eq.cpp index 6c3cf66c51..3171b8962e 100644 --- a/example/math/quadprog_eq.cpp +++ b/example/math/quadprog_eq.cpp @@ -67,12 +67,14 @@ int main(int argc, char **argv) bool opt_click_allowed = true; #endif - for (int i = 0; i < argc; i++) { + for (int i = 1; i < argc; i++) { #ifdef VISP_HAVE_DISPLAY - if (std::string(argv[i]) == "-d") + if (std::string(argv[i]) == "-d") { opt_display = false; - else if (std::string(argv[i]) == "-c") + } + else if (std::string(argv[i]) == "-c") { opt_click_allowed = false; + } else #endif if (std::string(argv[i]) == "-h") { diff --git a/example/reflex-takktile/takktile2-control.cpp b/example/reflex-takktile/takktile2-control.cpp index 92d9611d49..a223e13077 100644 --- a/example/reflex-takktile/takktile2-control.cpp +++ b/example/reflex-takktile/takktile2-control.cpp @@ -1,7 +1,6 @@ -/**************************************************************************** - * +/* * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -30,8 +29,7 @@ * * Description: * Interface for the Reflex Takktile 2 hand from Right Hand Robotics. - * -*****************************************************************************/ + */ /*! \example takktile2-control.cpp @@ -57,22 +55,26 @@ int main(int argc, char *argv[]) std::string opt_tactile_file_name = "yaml/tactile_calibrate.yaml"; std::string opt_motor_file_name = "yaml/motor_constants.yaml"; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--network") - opt_network_interface = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--finger") - opt_finger_file_name = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--tactile") - opt_tactile_file_name = atoi(argv[i + 1]); - else if (std::string(argv[i]) == "--motor") - opt_motor_file_name = atoi(argv[i + 1]); + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--network" && i + 1 < argc) { + opt_network_interface = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--finger" && i + 1 < argc) { + opt_finger_file_name = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--tactile" && i + 1 < argc) { + opt_tactile_file_name = atoi(argv[++i]); + } + else if (std::string(argv[i]) == "--motor" && i + 1 < argc) { + opt_motor_file_name = atoi(argv[++i]); + } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] << " [--network ] " - " [--finger ]" - " [--tactile ]" - " [--motor ]" - " [--help] [-h]\n" + << " [--finger ]" + << " [--tactile ]" + << " [--motor ]" + << " [--help] [-h]\n" << std::endl; std::cout << "Options:" << std::endl; std::cout << " --network " << std::endl; diff --git a/example/reflex-takktile/takktile2-read-data.cpp b/example/reflex-takktile/takktile2-read-data.cpp index 8a04cb7aa8..da98cfb65f 100644 --- a/example/reflex-takktile/takktile2-read-data.cpp +++ b/example/reflex-takktile/takktile2-read-data.cpp @@ -57,22 +57,26 @@ int main(int argc, char *argv[]) std::string opt_tactile_file_name = "yaml/tactile_calibrate.yaml"; std::string opt_motor_file_name = "yaml/motor_constants.yaml"; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--network") - opt_network_interface = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--finger") - opt_finger_file_name = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--tactile") - opt_tactile_file_name = atoi(argv[i + 1]); - else if (std::string(argv[i]) == "--motor") - opt_motor_file_name = atoi(argv[i + 1]); + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--network" && i + 1 < argc) { + opt_network_interface = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--finger" && i + 1 < argc) { + opt_finger_file_name = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--tactile" && i + 1 < argc) { + opt_tactile_file_name = atoi(argv[++i]); + } + else if (std::string(argv[i]) == "--motor" && i + 1 < argc) { + opt_motor_file_name = atoi(argv[++i]); + } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] << " [--network ] " - " [--finger ]" - " [--tactile ]" - " [--motor ]" - " [--help] [-h]\n" + << " [--finger ]" + << " [--tactile ]" + << " [--motor ]" + << " [--help] [-h]\n" << std::endl; std::cout << "Options:" << std::endl; std::cout << " --network " << std::endl; diff --git a/example/servo-bebop2/servoBebop2.cpp b/example/servo-bebop2/servoBebop2.cpp index 69e94fec9d..f5cb8964c7 100644 --- a/example/servo-bebop2/servoBebop2.cpp +++ b/example/servo-bebop2/servoBebop2.cpp @@ -161,7 +161,7 @@ int main(int argc, char **argv) else if (argc >= 2 && (std::string(argv[1]) == "--help" || std::string(argv[1]) == "-h")) { std::cout << "\nUsage:\n" << " " << argv[0] - << " [--tag_size ] [--ip ] [--distance_to_tag ] [--intrinsic ] " + << " [--tag-size ] [--ip ] [--distance_to_tag ] [--intrinsic ] " << "[--hd_stream] [--verbose] [-v] [--help] [-h]\n" << std::endl << "Description:\n" diff --git a/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp b/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp index 2a94b25689..c5991e8372 100644 --- a/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp +++ b/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp @@ -134,7 +134,7 @@ int main(int argc, char **argv) else if (std::string(argv[i]) == "--task_sequencing") { opt_task_sequencing = true; } - else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) { + else if (std::string(argv[i]) == "--quad-decimate" && i + 1 < argc) { opt_quad_decimate = std::stoi(argv[i + 1]); } else if (std::string(argv[i]) == "--no-convergence-threshold") { @@ -142,9 +142,9 @@ int main(int argc, char **argv) } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout - << argv[0] << " [--ip ] [--tag_size ] [--tag-size ] [--eMc ] " - << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" << "\n"; return EXIT_SUCCESS; diff --git a/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp b/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp index 0af04753a1..49423ac938 100644 --- a/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp +++ b/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp @@ -132,7 +132,7 @@ int main(int argc, char **argv) else if (std::string(argv[i]) == "--task_sequencing") { opt_task_sequencing = true; } - else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) { + else if (std::string(argv[i]) == "--quad-decimate" && i + 1 < argc) { opt_quad_decimate = std::stoi(argv[i + 1]); } else if (std::string(argv[i]) == "--no-convergence-threshold") { @@ -141,9 +141,9 @@ int main(int argc, char **argv) } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout - << argv[0] << " [--ip ] [--tag_size ] [--tag-size ] [--eMc ] " - << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" << "\n"; return EXIT_SUCCESS; diff --git a/modules/core/CMakeLists.txt b/modules/core/CMakeLists.txt index 3b2063d25d..404aad8c25 100644 --- a/modules/core/CMakeLists.txt +++ b/modules/core/CMakeLists.txt @@ -76,7 +76,7 @@ if(USE_OPENCV) set(OpenCV_REQUIRED_LIB_COMPONENTS ${OpenCV_LIB_COMPONENTS}) vp_list_filterout(OpenCV_REQUIRED_LIB_COMPONENTS "opencv_*") # We import only required OpenCV libraries - list(APPEND OpenCV_REQUIRED_LIB_COMPONENTS "opencv_core" "opencv_imgproc" "opencv_highgui" "opencv_calib3d" "opencv_features2d") + list(APPEND OpenCV_REQUIRED_LIB_COMPONENTS "opencv_core" "opencv_imgproc" "opencv_highgui" "opencv_calib3d" "opencv_features2d" "opencv_calib" "opencv_3d" ) if(OpenCV_VERSION AND OpenCV_VERSION VERSION_LESS 2.4.8) list(APPEND OpenCV_REQUIRED_LIB_COMPONENTS "opencv_legacy") endif() diff --git a/modules/core/include/visp3/core/vpConvert.h b/modules/core/include/visp3/core/vpConvert.h index eb012e5759..0bf0b04db4 100644 --- a/modules/core/include/visp3/core/vpConvert.h +++ b/modules/core/include/visp3/core/vpConvert.h @@ -36,13 +36,18 @@ \brief Tools for type or general conversion. */ -#ifndef _vpConvert_h_ -#define _vpConvert_h_ +#ifndef VP_CONVERT_H +#define VP_CONVERT_H #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_FEATURES2D) +#if defined(VISP_HAVE_OPENCV) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES)) + +#if defined(HAVE_OPENCV_FEATURES2D) #include +#elif defined(HAVE_OPENCV_FEATURES) +#include +#endif #include #include diff --git a/modules/core/include/visp3/core/vpImageConvert.h b/modules/core/include/visp3/core/vpImageConvert.h index e2cbf19f1a..30131a2bbd 100644 --- a/modules/core/include/visp3/core/vpImageConvert.h +++ b/modules/core/include/visp3/core/vpImageConvert.h @@ -49,8 +49,10 @@ #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) #include +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) #include #endif +#endif #ifdef VISP_HAVE_YARP #include diff --git a/modules/core/include/visp3/core/vpImageFilter.h b/modules/core/include/visp3/core/vpImageFilter.h index 6fd6bdad8c..01616fb11b 100644 --- a/modules/core/include/visp3/core/vpImageFilter.h +++ b/modules/core/include/visp3/core/vpImageFilter.h @@ -56,8 +56,10 @@ #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) #include +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) #include #endif +#endif BEGIN_VISP_NAMESPACE /*! diff --git a/modules/core/include/visp3/core/vpMeterPixelConversion.h b/modules/core/include/visp3/core/vpMeterPixelConversion.h index eeee75f8d4..8e620ce6e1 100644 --- a/modules/core/include/visp3/core/vpMeterPixelConversion.h +++ b/modules/core/include/visp3/core/vpMeterPixelConversion.h @@ -46,8 +46,8 @@ #include #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) -#include +#if defined(VISP_HAVE_OPENCV) +#include #endif BEGIN_VISP_NAMESPACE @@ -343,7 +343,7 @@ class VISP_EXPORT vpMeterPixelConversion #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS //@} -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) +#if (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_CALIB) && defined(HAVE_OPENCV_3D))) /** @name Using OpenCV camera parameters */ //@{ static void convertEllipse(const cv::Mat &cameraMatrix, const vpCircle &circle, vpImagePoint ¢er, double &n20_p, diff --git a/modules/core/include/visp3/core/vpPixelMeterConversion.h b/modules/core/include/visp3/core/vpPixelMeterConversion.h index ee06703cf0..be6bb66ebd 100644 --- a/modules/core/include/visp3/core/vpPixelMeterConversion.h +++ b/modules/core/include/visp3/core/vpPixelMeterConversion.h @@ -44,9 +44,8 @@ #include #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) && defined(HAVE_OPENCV_IMGPROC) -#include -#include +#if defined(VISP_HAVE_OPENCV) +#include #endif BEGIN_VISP_NAMESPACE @@ -398,7 +397,9 @@ class VISP_EXPORT vpPixelMeterConversion #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS //@} -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) && defined(HAVE_OPENCV_IMGPROC) +#if defined(HAVE_OPENCV_IMGPROC) && \ + (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_CALIB) && defined(HAVE_OPENCV_3D))) + /** @name Using OpenCV camera parameters */ //@{ static void convertEllipse(const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, const vpImagePoint ¢er_p, diff --git a/modules/core/src/camera/vpMeterPixelConversion.cpp b/modules/core/src/camera/vpMeterPixelConversion.cpp index 520daf3586..cee3d50a67 100644 --- a/modules/core/src/camera/vpMeterPixelConversion.cpp +++ b/modules/core/src/camera/vpMeterPixelConversion.cpp @@ -42,6 +42,14 @@ #include #include +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D) +#include +#endif +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_CALIB) && defined(HAVE_OPENCV_3D) +#include +#include +#endif + BEGIN_VISP_NAMESPACE /*! Line parameters conversion from normalized coordinates \f$(\rho_m,\theta_m)\f$ expressed in the image plane @@ -194,7 +202,7 @@ void vpMeterPixelConversion::convertEllipse(const vpCameraParameters &cam, doubl n02_p = n02_m * vpMath::sqr(cam.get_py()); } -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) +#if (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_CALIB) && defined(HAVE_OPENCV_3D))) /*! Line parameters conversion from normalized coordinates \f$(\rho_m,\theta_m)\f$ expressed in the image plane to pixel coordinates \f$(\rho_p,\theta_p)\f$ using OpenCV camera parameters. This function doesn't use distortion diff --git a/modules/core/src/camera/vpPixelMeterConversion.cpp b/modules/core/src/camera/vpPixelMeterConversion.cpp index 62e254f2cc..2f04a503dc 100644 --- a/modules/core/src/camera/vpPixelMeterConversion.cpp +++ b/modules/core/src/camera/vpPixelMeterConversion.cpp @@ -29,8 +29,7 @@ * * Description: * Pixel to meter conversion. - * -*****************************************************************************/ + */ /*! \file vpPixelMeterConversion.cpp @@ -41,6 +40,21 @@ #include #include +#if defined(HAVE_OPENCV_IMGPROC) && \ + (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_CALIB) && defined(HAVE_OPENCV_3D))) + +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) +#include +#endif + +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) +#include +#include +#endif + +#include +#endif + BEGIN_VISP_NAMESPACE /*! * Convert ellipse parameters (ie ellipse center and normalized centered moments) @@ -132,7 +146,7 @@ void vpPixelMeterConversion::convertMoment(const vpCameraParameters &cam, unsign double yc = -cam.m_v0; double xc = -cam.m_u0; - for (unsigned int k = 0; k < order; ++k) { // iteration correspondant e l'ordre du moment + for (unsigned int k = 0; k < order; ++k) { // iteration corresponding to moment order for (unsigned int p = 0; p < order; ++p) { // iteration en X for (unsigned int q = 0; q < order; ++q) { // iteration en Y if ((p + q) == k) { // on est bien dans la matrice triangulaire superieure @@ -148,7 +162,7 @@ void vpPixelMeterConversion::convertMoment(const vpCameraParameters &cam, unsign } } - for (unsigned int k = 0; k < order; ++k) { // iteration correspondant e l'ordre du moment + for (unsigned int k = 0; k < order; ++k) { // iteration corresponding to moment order for (unsigned int p = 0; p < order; ++p) { for (unsigned int q = 0; q < order; ++q) { if ((p + q) == k) { @@ -158,7 +172,7 @@ void vpPixelMeterConversion::convertMoment(const vpCameraParameters &cam, unsign } } - for (unsigned int k = 0; k < order; ++k) { // iteration correspondant e l'ordre du moment + for (unsigned int k = 0; k < order; ++k) { // iteration corresponding to moment order for (unsigned int p = 0; p < order; ++p) { for (unsigned int q = 0; q < order; ++q) { if ((p + q) == k) { @@ -169,7 +183,8 @@ void vpPixelMeterConversion::convertMoment(const vpCameraParameters &cam, unsign } } -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) && defined(HAVE_OPENCV_IMGPROC) +#if defined(HAVE_OPENCV_IMGPROC) && \ + (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_CALIB) && defined(HAVE_OPENCV_3D))) /*! * Convert ellipse parameters (ie ellipse center and normalized centered moments) * from pixels \f$(u_c, v_c, n_{{20}_p}, n_{{11}_p}, n_{{02}_p})\f$ @@ -246,7 +261,7 @@ void vpPixelMeterConversion::convertMoment(const cv::Mat &cameraMatrix, unsigned double yc = -v0; double xc = -u0; - for (unsigned int k = 0; k < order; ++k) { // iteration correspondant e l'ordre du moment + for (unsigned int k = 0; k < order; ++k) { // iteration corresponding to moment order for (unsigned int p = 0; p < order; ++p) { // iteration en X for (unsigned int q = 0; q < order; ++q) { // iteration en Y if (p + q == k) { // on est bien dans la matrice triangulaire superieure @@ -262,7 +277,7 @@ void vpPixelMeterConversion::convertMoment(const cv::Mat &cameraMatrix, unsigned } } - for (unsigned int k = 0; k < order; ++k) { // iteration correspondant e l'ordre du moment + for (unsigned int k = 0; k < order; ++k) { // iteration corresponding to moment order for (unsigned int p = 0; p < order; ++p) { for (unsigned int q = 0; q < order; ++q) { if (p + q == k) { @@ -272,7 +287,7 @@ void vpPixelMeterConversion::convertMoment(const cv::Mat &cameraMatrix, unsigned } } - for (unsigned int k = 0; k < order; ++k) { // iteration correspondant e l'ordre du moment + for (unsigned int k = 0; k < order; ++k) { // iteration corresponding to moment order for (unsigned int p = 0; p < order; ++p) { for (unsigned int q = 0; q < order; ++q) { if (p + q == k) { diff --git a/modules/core/src/tools/convert/vpConvert.cpp b/modules/core/src/tools/convert/vpConvert.cpp index 3b1ce481b9..6d54183d28 100644 --- a/modules/core/src/tools/convert/vpConvert.cpp +++ b/modules/core/src/tools/convert/vpConvert.cpp @@ -38,12 +38,15 @@ \brief Tools for type or general conversion. */ +#include + +#if defined(VISP_HAVE_OPENCV) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES)) + #include // std::transform #include // std::vector #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_FEATURES2D) BEGIN_VISP_NAMESPACE /*! Unary function used to transform a cv::KeyPoint to a vpImagePoint. @@ -52,7 +55,7 @@ BEGIN_VISP_NAMESPACE \return A vpImagePoint with the 2D coordinates corresponding to the location of the KeyPoint. */ -vpImagePoint vpConvert::keyPointToVpImagePoint(const cv::KeyPoint &keypoint) + vpImagePoint vpConvert::keyPointToVpImagePoint(const cv::KeyPoint &keypoint) { return vpImagePoint(keypoint.pt.y, keypoint.pt.x); } diff --git a/modules/core/test/camera/testCameraParametersConversion.cpp b/modules/core/test/camera/testCameraParametersConversion.cpp index a60814cbda..9a64871c52 100644 --- a/modules/core/test/camera/testCameraParametersConversion.cpp +++ b/modules/core/test/camera/testCameraParametersConversion.cpp @@ -119,7 +119,9 @@ int main() return EXIT_FAILURE; } -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) && defined(HAVE_OPENCV_IMGPROC) +#if defined(HAVE_OPENCV_IMGPROC) && \ + (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_CALIB))) + { std::cout << "* Compare ViSP and OpenCV point pixel meter conversion without distortion" << std::endl; cv::Mat cameraMatrix = (cv::Mat_(3, 3) << px, 0, u0, 0, py, v0, 0, 0, 1); diff --git a/modules/core/test/tools/serial/testSerialRead.cpp b/modules/core/test/tools/serial/testSerialRead.cpp index 8054ddb8a5..a78a8fce68 100644 --- a/modules/core/test/tools/serial/testSerialRead.cpp +++ b/modules/core/test/tools/serial/testSerialRead.cpp @@ -51,14 +51,18 @@ int main(int argc, char **argv) std::string port; unsigned long baud = 9600; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--port") - port = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--baud") { - baud = (unsigned long)atol(argv[i + 1]); + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--port" && i + 1 < argc) { + port = std::string(argv[++i]); } - else if (std::string(argv[i]) == "--help") { - std::cout << "\nUsage: " << argv[0] << " [--port ] [--baud ] [--help]\n" << std::endl; + else if (std::string(argv[i]) == "--baud" && i + 1 < argc) { + baud = (unsigned long)atol(argv[++i]); + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + std::cout << "\nUsage: " << argv[0] + << " [--port ]" + << " [--baud ]" + << " [--help,-h]\n" << std::endl; return EXIT_SUCCESS; } } diff --git a/modules/core/test/tools/serial/testSerialWrite.cpp b/modules/core/test/tools/serial/testSerialWrite.cpp index 92ab7d0118..db036b4bb4 100644 --- a/modules/core/test/tools/serial/testSerialWrite.cpp +++ b/modules/core/test/tools/serial/testSerialWrite.cpp @@ -49,11 +49,12 @@ int main(int argc, char **argv) std::string port; unsigned long baud = 9600; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--port") - port = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--baud") { - baud = (unsigned long)atol(argv[i + 1]); + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--port" && i + 1 < argc) { + port = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--baud" && i + 1 < argc) { + baud = (unsigned long)atol(argv[++i]); } else if (std::string(argv[i]) == "--help") { std::cout << "\nUsage: " << argv[0] << " [--port ] [--baud ] [--help]\n" << std::endl; diff --git a/modules/detection/CMakeLists.txt b/modules/detection/CMakeLists.txt index 8e289ebd9f..f3287bebb8 100644 --- a/modules/detection/CMakeLists.txt +++ b/modules/detection/CMakeLists.txt @@ -101,7 +101,9 @@ if(USE_OPENCV) if(OpenCV_VERSION AND ((OpenCV_VERSION VERSION_EQUAL 3.4.3) OR (OpenCV_VERSION VERSION_GREATER 3.4.3))) list(APPEND OpenCV_REQUIRED_LIB_COMPONENTS "opencv_dnn") endif() - + if(OpenCV_VERSION AND ((OpenCV_VERSION GREATER_EQUAL 5.0.0))) + list(APPEND OpenCV_REQUIRED_LIB_COMPONENTS "opencv_xobjdetect") + endif() if(USE_TENSORRT) list(APPEND OpenCV_REQUIRED_LIB_COMPONENTS "opencv_cudaarithm" "opencv_cudawarping") endif() diff --git a/modules/detection/include/visp3/detection/vpDetectorFace.h b/modules/detection/include/visp3/detection/vpDetectorFace.h index 46e3e8c3fe..7eec8a0e56 100644 --- a/modules/detection/include/visp3/detection/vpDetectorFace.h +++ b/modules/detection/include/visp3/detection/vpDetectorFace.h @@ -1,6 +1,6 @@ /* * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -31,18 +31,23 @@ * Detect faces. */ -#ifndef _vpDetectorFace_h_ -#define _vpDetectorFace_h_ +#ifndef VP_DETECTOR_FACE_H +#define VP_DETECTOR_FACE_H #include -#if defined(HAVE_OPENCV_OBJDETECT) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_OBJDETECT)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XOBJDETECT)) #include // needed by (std::min) in opencv2/objdetect/objdetect.hpp #include #include + +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) #include +#elif (VISP_HAVE_OPENCV_VERSION >= 0x050000) +#include +#endif #include diff --git a/modules/detection/src/face/vpDetectorFace.cpp b/modules/detection/src/face/vpDetectorFace.cpp index 1cccd1f4a1..eff49d45bb 100644 --- a/modules/detection/src/face/vpDetectorFace.cpp +++ b/modules/detection/src/face/vpDetectorFace.cpp @@ -1,7 +1,6 @@ -/**************************************************************************** - * +/* * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -30,11 +29,10 @@ * * Description: * Detect faces. - * -*****************************************************************************/ + */ #include -#if defined(HAVE_OPENCV_OBJDETECT) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_OBJDETECT)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XOBJDETECT)) #include @@ -47,14 +45,14 @@ BEGIN_VISP_NAMESPACE /*! Default constructor. */ -vpDetectorFace::vpDetectorFace() : m_faces(), m_face_cascade(), m_frame_gray() { } - -/*! - Set the name of the OpenCV cascade classifier file used for face detection. - \param filename : Full path to access to the file. Such a file can be found - in OpenCV. Within the last versions it was name - "haarcascade_frontalface_alt.xml". - */ + vpDetectorFace::vpDetectorFace() : m_faces(), m_face_cascade(), m_frame_gray() { } + + /*! + Set the name of the OpenCV cascade classifier file used for face detection. + \param filename : Full path to access to the file. Such a file can be found + in OpenCV. Within the last versions it was name + "haarcascade_frontalface_alt.xml". + */ void vpDetectorFace::setCascadeClassifierFile(const std::string &filename) { if (!m_face_cascade.load(filename)) { diff --git a/modules/gui/src/display/vpDisplayOpenCV.cpp b/modules/gui/src/display/vpDisplayOpenCV.cpp index cfbe2b170a..cbe89ab15e 100644 --- a/modules/gui/src/display/vpDisplayOpenCV.cpp +++ b/modules/gui/src/display/vpDisplayOpenCV.cpp @@ -58,8 +58,9 @@ #include #include +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) #include // for CV_FILLED versus cv::FILLED - +#endif #if defined(HAVE_OPENCV_IMGPROC) #include #endif diff --git a/modules/gui/test/display-with-dataset/testDisplayScaled.cpp b/modules/gui/test/display-with-dataset/testDisplayScaled.cpp index 8fb37971ac..9a77cef7da 100644 --- a/modules/gui/test/display-with-dataset/testDisplayScaled.cpp +++ b/modules/gui/test/display-with-dataset/testDisplayScaled.cpp @@ -279,13 +279,16 @@ int main(int argc, const char *argv[]) std::string env_ipath; std::string ipath; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "-c") + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "-c") { opt_click = false; - else if (std::string(argv[i]) == "-d") + } + else if (std::string(argv[i]) == "-d") { opt_display = false; - else if (std::string(argv[i]) == "-i") - opt_ipath = std::string(argv[i + 1]); + } + else if (std::string(argv[i]) == "-i" && i + 1 < argc) { + opt_ipath = std::string(argv[++i]); + } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] << " [-i ] [-c] [-d] [--help]\n" << std::endl; std::cout << "\nOptions: " << std::endl; diff --git a/modules/robot/test/virtuose/testVirtuose.cpp b/modules/robot/test/virtuose/testVirtuose.cpp index 40cbc46739..a896a58a04 100644 --- a/modules/robot/test/virtuose/testVirtuose.cpp +++ b/modules/robot/test/virtuose/testVirtuose.cpp @@ -47,11 +47,13 @@ int main(int argc, char **argv) #if defined(VISP_HAVE_VIRTUOSE) std::string opt_ip = "localhost"; int opt_port = 5000; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--ip") - opt_ip = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--port") - opt_port = std::atoi(argv[i + 1]); + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--ip" && i + 1 < argc) { + opt_ip = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--port" && i + 1 < argc) { + opt_port = std::atoi(argv[++i]); + } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] << " [--ip ] [--port ]" diff --git a/modules/robot/test/virtuose/testVirtuoseHapticBox.cpp b/modules/robot/test/virtuose/testVirtuoseHapticBox.cpp index 67f8cc8fbf..173e0676bf 100644 --- a/modules/robot/test/virtuose/testVirtuoseHapticBox.cpp +++ b/modules/robot/test/virtuose/testVirtuoseHapticBox.cpp @@ -241,11 +241,13 @@ int main(int argc, char **argv) { std::string opt_ip = "localhost"; int opt_port = 5000; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--ip") - opt_ip = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--port") - opt_port = std::atoi(argv[i + 1]); + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--ip" && i + 1 < argc) { + opt_ip = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--port" && i + 1 < argc) { + opt_port = std::atoi(argv[++i]); + } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] << " [--ip ] [--port ]" diff --git a/modules/robot/test/virtuose/testVirtuoseJointLimits.cpp b/modules/robot/test/virtuose/testVirtuoseJointLimits.cpp index ba0231050f..c1070ef5f9 100644 --- a/modules/robot/test/virtuose/testVirtuoseJointLimits.cpp +++ b/modules/robot/test/virtuose/testVirtuoseJointLimits.cpp @@ -99,15 +99,18 @@ int main(int argc, char **argv) { std::string opt_ip = "localhost"; int opt_port = 5000; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--ip") - opt_ip = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--port") - opt_port = std::atoi(argv[i + 1]); + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--ip" && i + 1 < argc) { + opt_ip = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--port" && i + 1 < argc) { + opt_port = std::atoi(argv[++i]); + } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] - << " [--ip ] [--port ]" - " [--help] [-h]\n" + << " [--ip ]" + << " [--port ]" + << " [--help] [-h]\n" << std::endl << "Description: " << std::endl << " --ip " << std::endl diff --git a/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp b/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp index b6b1b167fd..12d5b71b8b 100644 --- a/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp +++ b/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp @@ -55,16 +55,20 @@ int main(int argc, char **argv) int opt_port = 49152; bool opt_no_display = false; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--ip") - opt_ip = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--port") - opt_port = atoi(argv[i + 1]); - else if (std::string(argv[i]) == "--no-display" || std::string(argv[i]) == "-d") + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--ip" && i + 1 < argc) { + opt_ip = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--port" && i + 1 < argc) { + opt_port = atoi(argv[++i]); + } + else if (std::string(argv[i]) == "--no-display" || std::string(argv[i]) == "-d") { opt_no_display = true; + } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] - << " [--ip ] [--port ]" + << " [--ip ]" + << " [--port ]" << " [--no-display] [-d] [--help] [-h]\n" << std::endl; return EXIT_SUCCESS; diff --git a/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp b/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp index 271e19b7cc..16abcf90cb 100644 --- a/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp +++ b/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp @@ -51,13 +51,20 @@ int main(int argc, char **argv) bool opt_no_display = false; bool opt_filtered = false; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--no-display" || std::string(argv[i]) == "-d") + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--no-display" || std::string(argv[i]) == "-d") { opt_no_display = true; - if (std::string(argv[i]) == "--filtered" || std::string(argv[i]) == "-f") + } + else if (std::string(argv[i]) == "--filtered" || std::string(argv[i]) == "-f") { opt_filtered = true; + } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { - std::cout << "\nUsage: " << argv[0] << " [--no-display] [--filtered] [--help] [-d] [-f] [-h]\n" << std::endl; + std::cout << "\nUsage: " << argv[0] + << " [--no-display]" + << " [--filtered]" + << " [-d]" + << " [-f]" + << " [--help,-h]\n" << std::endl; return 0; } } diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h index f8073a0205..d107f838ad 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h @@ -71,8 +71,10 @@ #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) #include +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) #include #endif +#endif BEGIN_VISP_NAMESPACE diff --git a/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp b/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp index 6dd895580a..25dfec5905 100644 --- a/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp @@ -53,8 +53,10 @@ #include #if defined(HAVE_OPENCV_IMGPROC) #include +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) #include #endif +#endif BEGIN_VISP_NAMESPACE double computeDelta(double deltai, double deltaj); diff --git a/modules/vision/CMakeLists.txt b/modules/vision/CMakeLists.txt index c5d52386ac..9bd28a1f80 100644 --- a/modules/vision/CMakeLists.txt +++ b/modules/vision/CMakeLists.txt @@ -1,7 +1,7 @@ ############################################################################# # # ViSP, open source Visual Servoing Platform software. -# Copyright (C) 2005 - 2023 by Inria. All rights reserved. +# Copyright (C) 2005 - 2024 by Inria. All rights reserved. # # This software is free software; you can redistribute it and/or modify # it under the terms of the GNU General Public License as published by @@ -68,7 +68,7 @@ if(USE_OPENCV) set(OpenCV_REQUIRED_LIB_COMPONENTS ${OpenCV_LIB_COMPONENTS}) vp_list_filterout(OpenCV_REQUIRED_LIB_COMPONENTS "opencv_*") # We import only required OpenCV libraries - list(APPEND OpenCV_REQUIRED_LIB_COMPONENTS "opencv_legacy" "opencv_xfeatures2d" "opencv_nonfree" "opencv_flann") + list(APPEND OpenCV_REQUIRED_LIB_COMPONENTS "opencv_legacy" "opencv_xfeatures2d" "opencv_features" "opencv_3d" "opencv_calib" "opencv_calib3d" "opencv_nonfree" "opencv_flann") foreach(component_ ${OpenCV_REQUIRED_LIB_COMPONENTS}) string(TOUPPER "${component_}" component_UP) diff --git a/modules/vision/include/visp3/vision/vpKeyPoint.h b/modules/vision/include/visp3/vision/vpKeyPoint.h index 8571bd98c0..824cbfeaef 100644 --- a/modules/vision/include/visp3/vision/vpKeyPoint.h +++ b/modules/vision/include/visp3/vision/vpKeyPoint.h @@ -1,6 +1,6 @@ /* * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -30,8 +30,12 @@ * Description: * Key point functionalities. */ -#ifndef _vpKeyPoint_h_ -#define _vpKeyPoint_h_ +#ifndef VP_KEYPOINT_H +#define VP_KEYPOINT_H + +#include + +#if (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES) || defined(HAVE_OPENCV_XFEATURES2D) || defined(HAVE_OPENCV_NONFREE)) #include // std::transform #include // DBL_MAX @@ -43,7 +47,6 @@ #include // time #include // std::vector -#include #include #include #include @@ -60,16 +63,22 @@ #include #include -// Require at least OpenCV >= 2.1.1 -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#include + +#if defined(HAVE_OPENCV_FEATURES2D) #include -#include -#include +#endif -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) // OpenCV >= 3.0.0 +#if defined(HAVE_OPENCV_XFEATURES2D) #include -#elif defined(VISP_HAVE_OPENCV_NONFREE) && (VISP_HAVE_OPENCV_VERSION >= 0x020400) && \ - (VISP_HAVE_OPENCV_VERSION < 0x030000) +#endif + +#if defined(HAVE_OPENCV_IMGPROC) +#include +//#include +#endif + +#if defined(HAVE_OPENCV_NONFREE) #include #endif @@ -78,7 +87,7 @@ BEGIN_VISP_NAMESPACE * \class vpKeyPoint * \ingroup group_vision_keypoints group_detection_keypoint group_detection_mbt_object * - * \brief Class that allows keypoints detection (and descriptors extraction) + * \brief Class that allows keypoints 2D features detection (and descriptors extraction) * and matching thanks to OpenCV library. Thus to enable this class OpenCV should * be installed. Installation instructions are provided here * https://visp.inria.fr/3rd_opencv. @@ -93,6 +102,43 @@ BEGIN_VISP_NAMESPACE * from 3.0.0. You have to check you have the corresponding module to use SIFT * and SURF. * + * Depending on OpenCV version, the table below shows which OpenCV module + * is required to be able to use a given 2D features detectors. + * + * 2D features detectors | OpenCV < 5.0 | OpenCV >= 5.0 + * :-------------------: | :----------: | :-----------: + * AGAST | features2d | xfeatures2d + * AKAZE | features2d | xfeatures2d + * BRISK | features2d | xfeatures2d + * GFTTDetector | features2d | features + * FAST | features2d | features + * KAZE | features2d | xfeatures2d + * MSDDetector | xfeatures2d | xfeatures2d + * MSER | features2d | features + * ORB | features2d | features + * SIFT | xfeatures2d | features + * SimpleBlobDetector | features2d | features + * STAR | xfeatures2d | xfeatures2d + * SURF | xfeatures2d | xfeatures2d + * + * Depending on OpenCV version, the table below shows which OpenCV module + * is required to be able to use a given 2D features descriptor. + * + * 2D features descriptors | OpenCV < 5.0 | OpenCV >= 5.0 + * :---------------------: | :----------: | :-----------: + * AKAZE | features2d | xfeatures2d + * BRIEF | xfeatures2d | xfeatures2d + * BRISK | features2d | xfeatures2d + * BoostDesc | xfeatures2d | xfeatures2d + * DAISY | xfeatures2d | xfeatures2d + * FREAK | xfeatures2d | xfeatures2d + * KAZE | features2d | xfeatures2d + * LATCH | xfeatures2d | xfeatures2d + * ORB | features2d | features + * SIFT | xfeatures2d | features + * SURF | xfeatures2d | xfeatures2d + * VGG | xfeatures2d | xfeatures2d + * * The goal of this class is to provide a tool to match reference keypoints * from a reference image (or train keypoints in OpenCV terminology) and detected * keypoints from a current image (or query keypoints in OpenCV terminology). @@ -257,65 +303,96 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint /*! Predefined constant for feature detection type. */ enum vpFeatureDetectorType { -#if (VISP_HAVE_OPENCV_VERSION >= 0x020403) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) +# if defined(HAVE_OPENCV_FEATURES) DETECTOR_FAST, //!< FAST detector + DETECTOR_GFTT, //!< GFTT detector DETECTOR_MSER, //!< MSER detector DETECTOR_ORB, //!< ORB detector - DETECTOR_BRISK, //!< BRISK detector - DETECTOR_GFTT, //!< GFTT detector + DETECTOR_SIFT, //!< SIFT detector DETECTOR_SimpleBlob, //!< SimpleBlob detector -#if (VISP_HAVE_OPENCV_VERSION < 0x030000) || (defined(VISP_HAVE_OPENCV_XFEATURES2D)) +# endif +# if defined(HAVE_OPENCV_XFEATURES2D) + DETECTOR_AGAST, //!< AGAST detector + DETECTOR_AKAZE, //!< AKAZE detector + DETECTOR_BRISK, //!< BRISK detector + DETECTOR_KAZE, //!< KAZE detector + DETECTOR_MSD, //!< MSD detector DETECTOR_STAR, //!< STAR detector -#endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) - DETECTOR_SIFT, //!< SIFT detector -#endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) +# endif +# if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D) DETECTOR_SURF, //!< SURF detector -#endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030000) - DETECTOR_KAZE, //!< KAZE detector - DETECTOR_AKAZE, //!< AKAZE detector +# endif +#else // OpenCV < 5.0.0 +# if defined(HAVE_OPENCV_FEATURES2D) DETECTOR_AGAST, //!< AGAST detector -#endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030100) && defined(VISP_HAVE_OPENCV_XFEATURES2D) + DETECTOR_AKAZE, //!< AKAZE detector + DETECTOR_BRISK, //!< BRISK detector + DETECTOR_FAST, //!< FAST detector + DETECTOR_GFTT, //!< GFTT detector + DETECTOR_KAZE, //!< KAZE detector + DETECTOR_MSER, //!< MSER detector + DETECTOR_ORB, //!< ORB detector + DETECTOR_SimpleBlob, //!< SimpleBlob detector +# endif +# if defined(HAVE_OPENCV_XFEATURES2D) DETECTOR_MSD, //!< MSD detector + DETECTOR_SIFT, //!< SIFT detector + DETECTOR_STAR, //!< STAR detector +# endif +# if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D) + DETECTOR_SURF, //!< SURF detector +# endif #endif -#endif + DETECTOR_TYPE_SIZE //!< Number of detectors available }; /*! Predefined constant for descriptor extraction type. */ enum vpFeatureDescriptorType { -#if (VISP_HAVE_OPENCV_VERSION >= 0x020403) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) +# if defined(HAVE_OPENCV_FEATURES) DESCRIPTOR_ORB, //!< ORB descriptor + DESCRIPTOR_SIFT, //!< SIFT descriptor +# endif +# if defined(HAVE_OPENCV_XFEATURES2D) + DESCRIPTOR_AKAZE, //!< AKAZE descriptor DESCRIPTOR_BRISK, //!< BRISK descriptor -#if (VISP_HAVE_OPENCV_VERSION < 0x030000) || (defined(VISP_HAVE_OPENCV_XFEATURES2D)) - DESCRIPTOR_FREAK, //!< FREAK descriptor + DESCRIPTOR_BoostDesc, //!< BoostDesc descriptor DESCRIPTOR_BRIEF, //!< BRIEF descriptor -#endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) - DESCRIPTOR_SIFT, //!< SIFT descriptor -#endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) - DESCRIPTOR_SURF, //!< SUFT descriptor -#endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030000) + DESCRIPTOR_DAISY, //!< DAISY descriptor + DESCRIPTOR_FREAK, //!< FREAK descriptor DESCRIPTOR_KAZE, //!< KAZE descriptor + DESCRIPTOR_LATCH, //!< LATCH descriptor + DESCRIPTOR_VGG, //!< VGG descriptor +# endif +# if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D) + DESCRIPTOR_SURF, //!< SURF descriptor +# endif +#else // opencv < 5.0.0 +# if defined(HAVE_OPENCV_FEATURES2D) DESCRIPTOR_AKAZE, //!< AKAZE descriptor -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) + DESCRIPTOR_BRISK, //!< BRISK descriptor + DESCRIPTOR_KAZE, //!< KAZE descriptor + DESCRIPTOR_ORB, //!< ORB descriptor +# endif +# if defined(HAVE_OPENCV_XFEATURES2D) + DESCRIPTOR_BRIEF, //!< BRIEF descriptor DESCRIPTOR_DAISY, //!< DAISY descriptor + DESCRIPTOR_FREAK, //!< FREAK descriptor DESCRIPTOR_LATCH, //!< LATCH descriptor + DESCRIPTOR_SIFT, //!< SIFT descriptor +# endif +# if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D) + DESCRIPTOR_SURF, //!< SURF descriptor +# endif +# if defined(HAVE_OPENCV_XFEATURES2D) && (VISP_HAVE_OPENCV_VERSION >= 0x030200) + DESCRIPTOR_BoostDesc, //!< BoostDesc descriptor, only with OpenCV >= 3.2.0 + DESCRIPTOR_VGG, //!< VGG descriptor, only with OpenCV >= 3.2.0 +# endif #endif -#endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(VISP_HAVE_OPENCV_XFEATURES2D) - DESCRIPTOR_VGG, //!< VGG descriptor - DESCRIPTOR_BoostDesc, //!< BoostDesc descriptor -#endif -#endif + DESCRIPTOR_TYPE_SIZE //!< Number of descriptors available }; @@ -971,19 +1048,16 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint { if (!m_computeCovariance) { std::cout << "Warning : The covariance matrix has not been computed. " - "See setCovarianceComputation() to do it." + << "See setCovarianceComputation() to do it." << std::endl; return vpMatrix(); } if (m_computeCovariance && !m_useRansacVVS) { std::cout << "Warning : The covariance matrix can only be computed " - "with a Virtual Visual Servoing approach." - << std::endl + << "with a Virtual Visual Servoing approach." << std::endl << "Use setUseRansacVVS(true) to choose to use a pose " - "estimation method based on a Virtual Visual Servoing " - "approach." - << std::endl; + << "estimation method based on a Virtual Visual Servoing approach." << std::endl; return vpMatrix(); } @@ -1008,9 +1082,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint { std::map::const_iterator it_name = m_mapOfDetectorNames.find(type); if (it_name == m_mapOfDetectorNames.end()) { - std::cerr << "Internal problem with the feature type and the " - "corresponding name!" - << std::endl; + std::cerr << "Internal problem with the feature type and the corresponding name!" << std::endl; } std::map >::const_iterator findDetector = @@ -1064,9 +1136,7 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint { std::map::const_iterator it_name = m_mapOfDescriptorNames.find(type); if (it_name == m_mapOfDescriptorNames.end()) { - std::cerr << "Internal problem with the feature type and the " - "corresponding name!" - << std::endl; + std::cerr << "Internal problem with the feature type and the corresponding name!" << std::endl; } std::map >::const_iterator findExtractor = @@ -1551,12 +1621,10 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint m_computeCovariance = flag; if (!m_useRansacVVS) { std::cout << "Warning : The covariance matrix can only be computed " - "with a Virtual Visual Servoing approach." - << std::endl + << "with a Virtual Visual Servoing approach." << std::endl << "Use setUseRansacVVS(true) to choose to use a pose " - "estimation method based on a Virtual " - "Visual Servoing approach." - << std::endl; + << "estimation method based on a Virtual " + << "Visual Servoing approach." << std::endl; } } @@ -1923,8 +1991,8 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint } else if (m_matcher != nullptr && m_useKnn && m_matcherName == "BruteForce") { std::cout << "Warning, you try to set the crossCheck parameter with a " - "BruteForce matcher but knn is enabled"; - std::cout << " (the filtering method uses a ratio constraint)" << std::endl; + << "BruteForce matcher but knn is enabled" + << " (the filtering method uses a ratio constraint)" << std::endl; } } #endif diff --git a/modules/vision/src/key-point/vpKeyPoint.cpp b/modules/vision/src/key-point/vpKeyPoint.cpp index e49545002c..c6b047f45f 100644 --- a/modules/vision/src/key-point/vpKeyPoint.cpp +++ b/modules/vision/src/key-point/vpKeyPoint.cpp @@ -1,6 +1,6 @@ /* * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -31,13 +31,31 @@ * Key point functionalities. */ +#include + +#if (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES) || defined(HAVE_OPENCV_XFEATURES2D) || defined(HAVE_OPENCV_NONFREE)) + #include #include #include #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#if defined(HAVE_OPENCV_3D) +#include +#endif + +#if defined(HAVE_OPENCV_FEATURES) +#include +#endif + +#if defined(HAVE_OPENCV_XFEATURES2D) +#include +#endif + +#if defined(HAVE_OPENCV_3D) +#include +#endif #if defined(VISP_HAVE_PUGIXML) #include @@ -207,7 +225,6 @@ unsigned int vpKeyPoint::buildReference(const vpImage &I_color, const vp return buildReference(I_color, vpRect(iP, width, height)); } - unsigned int vpKeyPoint::buildReference(const vpImage &I, const vpRect &rectangle) { // Reset variables used when dealing with 3D models @@ -553,11 +570,10 @@ void vpKeyPoint::compute3DForPointsInPolygons(const vpHomogeneousMatrix &cMo, co } -void vpKeyPoint::compute3DForPointsOnCylinders( - const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector &candidates, - const std::vector &cylinders, - const std::vector > > &vectorOfCylinderRois, std::vector &points, - cv::Mat *descriptors) +void vpKeyPoint::compute3DForPointsOnCylinders(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, + std::vector &candidates, const std::vector &cylinders, + const std::vector > > &vectorOfCylinderRois, + std::vector &points, cv::Mat *descriptors) { std::vector candidatesToCheck = candidates; candidates.clear(); @@ -613,11 +629,10 @@ void vpKeyPoint::compute3DForPointsOnCylinders( } } -void vpKeyPoint::compute3DForPointsOnCylinders( - const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector &candidates, - const std::vector &cylinders, - const std::vector > > &vectorOfCylinderRois, std::vector &points, - cv::Mat *descriptors) +void vpKeyPoint::compute3DForPointsOnCylinders(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, + std::vector &candidates, const std::vector &cylinders, + const std::vector > > &vectorOfCylinderRois, + std::vector &points, cv::Mat *descriptors) { std::vector candidatesToCheck = candidates; candidates.clear(); @@ -708,24 +723,24 @@ bool vpKeyPoint::computePose(const std::vector &imagePoints, const 0.99, // confidence=0.99 (default) – The probability // that the algorithm produces a useful result. inlierIndex, cv::SOLVEPNP_ITERATIVE); -// SOLVEPNP_ITERATIVE (default): Iterative method is based on -// Levenberg-Marquardt optimization. In this case the function finds such a -// pose that minimizes reprojection error, that is the sum of squared -// distances between the observed projections imagePoints and the projected -// (using projectPoints() ) objectPoints . SOLVEPNP_P3P: Method is based on -// the paper of X.S. Gao, X.-R. Hou, J. Tang, H.-F. Chang “Complete Solution -// Classification for the Perspective-Three-Point Problem”. In this case the -// function requires exactly four object and image points. SOLVEPNP_EPNP: -// Method has been introduced by F.Moreno-Noguer, V.Lepetit and P.Fua in the -// paper “EPnP: Efficient Perspective-n-Point Camera Pose Estimation”. -// SOLVEPNP_DLS: Method is based on the paper of Joel A. Hesch and Stergios I. -// Roumeliotis. “A Direct Least-Squares (DLS) Method for PnP”. SOLVEPNP_UPNP -// Method is based on the paper of A.Penate-Sanchez, J.Andrade-Cetto, -// F.Moreno-Noguer. “Exhaustive Linearization for Robust Camera Pose and Focal -// Length Estimation”. In this case the function also estimates the -// parameters -// f_x and f_y assuming that both have the same value. Then the cameraMatrix -// is updated with the estimated focal length. + // SOLVEPNP_ITERATIVE (default): Iterative method is based on + // Levenberg-Marquardt optimization. In this case the function finds such a + // pose that minimizes reprojection error, that is the sum of squared + // distances between the observed projections imagePoints and the projected + // (using projectPoints() ) objectPoints . SOLVEPNP_P3P: Method is based on + // the paper of X.S. Gao, X.-R. Hou, J. Tang, H.-F. Chang “Complete Solution + // Classification for the Perspective-Three-Point Problem”. In this case the + // function requires exactly four object and image points. SOLVEPNP_EPNP: + // Method has been introduced by F.Moreno-Noguer, V.Lepetit and P.Fua in the + // paper “EPnP: Efficient Perspective-n-Point Camera Pose Estimation”. + // SOLVEPNP_DLS: Method is based on the paper of Joel A. Hesch and Stergios I. + // Roumeliotis. “A Direct Least-Squares (DLS) Method for PnP”. SOLVEPNP_UPNP + // Method is based on the paper of A.Penate-Sanchez, J.Andrade-Cetto, + // F.Moreno-Noguer. “Exhaustive Linearization for Robust Camera Pose and Focal + // Length Estimation”. In this case the function also estimates the + // parameters + // f_x and f_y assuming that both have the same value. Then the cameraMatrix + // is updated with the estimated focal length. #else int nbInlierToReachConsensus = m_nbRansacMinInlierCount; if (m_useConsensusPercentage) { @@ -998,9 +1013,14 @@ void vpKeyPoint::detect(const vpImage &I, std::vector 0 && rectangle.getHeight() > 0) { +#if VISP_HAVE_OPENCV_VERSION >= 0x030000 + int filled = cv::FILLED; +#else + int filled = CV_FILLED; +#endif cv::Point leftTop((int)rectangle.getLeft(), (int)rectangle.getTop()), rightBottom((int)rectangle.getRight(), (int)rectangle.getBottom()); - cv::rectangle(mask, leftTop, rightBottom, cv::Scalar(255), CV_FILLED); + cv::rectangle(mask, leftTop, rightBottom, cv::Scalar(255), filled); } else { mask = cv::Mat::ones(matImg.rows, matImg.cols, CV_8U) * 255; @@ -1017,9 +1037,14 @@ void vpKeyPoint::detect(const vpImage &I_color, std::vector 0 && rectangle.getHeight() > 0) { +#if VISP_HAVE_OPENCV_VERSION >= 0x030000 + int filled = cv::FILLED; +#else + int filled = CV_FILLED; +#endif cv::Point leftTop((int)rectangle.getLeft(), (int)rectangle.getTop()), rightBottom((int)rectangle.getRight(), (int)rectangle.getBottom()); - cv::rectangle(mask, leftTop, rightBottom, cv::Scalar(255), CV_FILLED); + cv::rectangle(mask, leftTop, rightBottom, cv::Scalar(255), filled); } else { mask = cv::Mat::ones(matImg.rows, matImg.cols, CV_8U) * 255; @@ -1192,7 +1217,7 @@ void vpKeyPoint::displayMatching(const vpImage &ICurrent, vpImage displayMatching(m_mapOfImages.begin()->second, IMatching, crossSize); } else { - // Multiple training images, display them as a mosaic image + // Multiple training images, display them as a mosaic image int nbImgSqrt = vpMath::round(std::sqrt((double)nbImg)); //(int) std::floor(std::sqrt((double) nbImg) + 0.5); int nbWidth = nbImgSqrt; int nbHeight = nbImgSqrt; @@ -1229,8 +1254,8 @@ void vpKeyPoint::displayMatching(const vpImage &ICurrent, vpImage current_class_id_index = mapOfImageIdIndex[m_mapOfImageId[it->class_id]]; } else { - // Shift of one unity the index of the training images which are after - // the current image + // Shift of one unity the index of the training images which are after + // the current image current_class_id_index = mapOfImageIdIndex[m_mapOfImageId[it->class_id]] + 1; } @@ -1266,8 +1291,8 @@ void vpKeyPoint::displayMatching(const vpImage &ICurrent, vpImage current_class_id = mapOfImageIdIndex[m_mapOfImageId[m_trainKeyPoints[(size_t)it->trainIdx].class_id]]; } else { - // Shift of one unity the index of the training images which are after - // the current image + // Shift of one unity the index of the training images which are after + // the current image current_class_id = mapOfImageIdIndex[m_mapOfImageId[m_trainKeyPoints[(size_t)it->trainIdx].class_id]] + 1; } @@ -1305,7 +1330,7 @@ void vpKeyPoint::displayMatching(const vpImage &ICurrent, vpImagesecond, IMatching, crossSize); } else { - // Multiple training images, display them as a mosaic image + // Multiple training images, display them as a mosaic image int nbImgSqrt = vpMath::round(std::sqrt((double)nbImg)); //(int) std::floor(std::sqrt((double) nbImg) + 0.5); int nbWidth = nbImgSqrt; int nbHeight = nbImgSqrt; @@ -1342,8 +1367,8 @@ void vpKeyPoint::displayMatching(const vpImage &ICurrent, vpImageclass_id]]; } else { - // Shift of one unity the index of the training images which are after - // the current image + // Shift of one unity the index of the training images which are after + // the current image current_class_id_index = mapOfImageIdIndex[m_mapOfImageId[it->class_id]] + 1; } @@ -1379,8 +1404,8 @@ void vpKeyPoint::displayMatching(const vpImage &ICurrent, vpImagetrainIdx].class_id]]; } else { - // Shift of one unity the index of the training images which are after - // the current image + // Shift of one unity the index of the training images which are after + // the current image current_class_id = mapOfImageIdIndex[m_mapOfImageId[m_trainKeyPoints[(size_t)it->trainIdx].class_id]] + 1; } @@ -1478,13 +1503,13 @@ void vpKeyPoint::extract(const cv::Mat &matImg, std::vector &keyPo } } else { - // Extract descriptors for the given list of keypoints + // Extract descriptors for the given list of keypoints itd->second->compute(matImg, keyPoints, descriptors); } } else { - // Copy the input list of keypoints, keypoints that cannot be computed - // are removed in the function compute + // Copy the input list of keypoints, keypoints that cannot be computed + // are removed in the function compute std::vector keyPoints_tmp = keyPoints; cv::Mat desc; @@ -1717,10 +1742,10 @@ void vpKeyPoint::getTrainPoints(std::vector &points) const { points = m void vpKeyPoint::init() { // Require 2.4.0 <= opencv < 3.0.0 -#if defined(VISP_HAVE_OPENCV_NONFREE) && (VISP_HAVE_OPENCV_VERSION >= 0x020400) && (VISP_HAVE_OPENCV_VERSION < 0x030000) +#if defined(HAVE_OPENCV_NONFREE) && (VISP_HAVE_OPENCV_VERSION >= 0x020400) && (VISP_HAVE_OPENCV_VERSION < 0x030000) // The following line must be called in order to use SIFT or SURF if (!cv::initModule_nonfree()) { - std::cerr << "Cannot init module non free, SIFT or SURF cannot be used." << std::endl; + std::cerr << "Cannot init module non free, SURF cannot be used." << std::endl; } #endif @@ -1757,7 +1782,8 @@ void vpKeyPoint::initDetector(const std::string &detectorName) } if (detectorNameTmp == "SIFT") { -#if (VISP_HAVE_OPENCV_VERSION >= 0x040500) // OpenCV >= 4.5.0 +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) +# if (VISP_HAVE_OPENCV_VERSION >= 0x040500) // OpenCV >= 4.5.0 cv::Ptr siftDetector = cv::SiftFeatureDetector::create(); if (!usePyramid) { m_detectors[detectorNameTmp] = siftDetector; @@ -1765,25 +1791,19 @@ void vpKeyPoint::initDetector(const std::string &detectorName) else { m_detectors[detectorName] = cv::makePtr(siftDetector); } -#else -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) || (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x040400) +# elif (VISP_HAVE_OPENCV_VERSION >= 0x030411) // SIFT is no more patented since 09/03/2020 cv::Ptr siftDetector; if (m_maxFeatures > 0) { -#if (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) siftDetector = cv::SIFT::create(m_maxFeatures); -#else - siftDetector = cv::xfeatures2d::SIFT::create(m_maxFeatures); -#endif } else { -#if (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) siftDetector = cv::SIFT::create(); -#else - siftDetector = cv::xfeatures2d::SIFT::create(); -#endif } +# else + cv::Ptr siftDetector; + siftDetector = cv::xfeatures2d::SIFT::create(); +# endif if (!usePyramid) { m_detectors[detectorNameTmp] = siftDetector; } @@ -1791,16 +1811,14 @@ void vpKeyPoint::initDetector(const std::string &detectorName) std::cerr << "You should not use SIFT with Pyramid feature detection!" << std::endl; m_detectors[detectorName] = cv::makePtr(siftDetector); } -#else +# else std::stringstream ss_msg; - ss_msg << "Fail to initialize the detector: SIFT. OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION - << " was not build with xFeatures2d module."; + ss_msg << "Failed to initialize the SIFT 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); -#endif #endif } else if (detectorNameTmp == "SURF") { -#ifdef VISP_HAVE_OPENCV_XFEATURES2D +#if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D) cv::Ptr surfDetector = cv::xfeatures2d::SURF::create(); if (!usePyramid) { m_detectors[detectorNameTmp] = surfDetector; @@ -1811,12 +1829,12 @@ void vpKeyPoint::initDetector(const std::string &detectorName) } #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the detector: SURF. OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION - << " was not build with xFeatures2d module."; + ss_msg << "Failed to initialize the SURF 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } else if (detectorNameTmp == "FAST") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) cv::Ptr fastDetector = cv::FastFeatureDetector::create(); if (!usePyramid) { m_detectors[detectorNameTmp] = fastDetector; @@ -1824,8 +1842,14 @@ void vpKeyPoint::initDetector(const std::string &detectorName) else { m_detectors[detectorName] = cv::makePtr(fastDetector); } +#else + std::stringstream ss_msg; + ss_msg << "Failed to initialize the FAST 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (detectorNameTmp == "MSER") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) cv::Ptr fastDetector = cv::MSER::create(); if (!usePyramid) { m_detectors[detectorNameTmp] = fastDetector; @@ -1833,8 +1857,14 @@ void vpKeyPoint::initDetector(const std::string &detectorName) else { m_detectors[detectorName] = cv::makePtr(fastDetector); } +#else + std::stringstream ss_msg; + ss_msg << "Failed to initialize the MSER 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (detectorNameTmp == "ORB") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) cv::Ptr orbDetector; if (m_maxFeatures > 0) { orbDetector = cv::ORB::create(m_maxFeatures); @@ -1849,9 +1879,19 @@ void vpKeyPoint::initDetector(const std::string &detectorName) std::cerr << "You should not use ORB with Pyramid feature detection!" << std::endl; m_detectors[detectorName] = cv::makePtr(orbDetector); } +#else + std::stringstream ss_msg; + ss_msg << "Failed to initialize the ORB 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (detectorNameTmp == "BRISK") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) + cv::Ptr briskDetector = cv::xfeatures2d::BRISK::create(); +#else cv::Ptr briskDetector = cv::BRISK::create(); +#endif if (!usePyramid) { m_detectors[detectorNameTmp] = briskDetector; } @@ -1859,9 +1899,20 @@ void vpKeyPoint::initDetector(const std::string &detectorName) std::cerr << "You should not use BRISK with Pyramid feature detection!" << std::endl; m_detectors[detectorName] = cv::makePtr(briskDetector); } +#else + std::stringstream ss_msg; + + ss_msg << "Failed to initialize the BRISK 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (detectorNameTmp == "KAZE") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) + cv::Ptr kazeDetector = cv::xfeatures2d::KAZE::create(); +#else cv::Ptr kazeDetector = cv::KAZE::create(); +#endif if (!usePyramid) { m_detectors[detectorNameTmp] = kazeDetector; } @@ -1869,9 +1920,19 @@ void vpKeyPoint::initDetector(const std::string &detectorName) std::cerr << "You should not use KAZE with Pyramid feature detection!" << std::endl; m_detectors[detectorName] = cv::makePtr(kazeDetector); } +#else + std::stringstream ss_msg; + ss_msg << "Failed to initialize the KAZE 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (detectorNameTmp == "AKAZE") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) + cv::Ptr akazeDetector = cv::xfeatures2d::AKAZE::create(); +#else cv::Ptr akazeDetector = cv::AKAZE::create(); +#endif if (!usePyramid) { m_detectors[detectorNameTmp] = akazeDetector; } @@ -1879,8 +1940,14 @@ void vpKeyPoint::initDetector(const std::string &detectorName) std::cerr << "You should not use AKAZE with Pyramid feature detection!" << std::endl; m_detectors[detectorName] = cv::makePtr(akazeDetector); } +#else + std::stringstream ss_msg; + ss_msg << "Failed to initialize the AKAZE 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (detectorNameTmp == "GFTT") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) cv::Ptr gfttDetector = cv::GFTTDetector::create(); if (!usePyramid) { m_detectors[detectorNameTmp] = gfttDetector; @@ -1888,8 +1955,14 @@ void vpKeyPoint::initDetector(const std::string &detectorName) else { m_detectors[detectorName] = cv::makePtr(gfttDetector); } +#else + std::stringstream ss_msg; + ss_msg << "Failed to initialize the GFTT 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (detectorNameTmp == "SimpleBlob") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) cv::Ptr simpleBlobDetector = cv::SimpleBlobDetector::create(); if (!usePyramid) { m_detectors[detectorNameTmp] = simpleBlobDetector; @@ -1897,9 +1970,14 @@ void vpKeyPoint::initDetector(const std::string &detectorName) else { m_detectors[detectorName] = cv::makePtr(simpleBlobDetector); } +#else + std::stringstream ss_msg; + ss_msg << "Failed to initialize the SimpleBlob 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (detectorNameTmp == "STAR") { -#ifdef VISP_HAVE_OPENCV_XFEATURES2D +#if defined(HAVE_OPENCV_XFEATURES2D) cv::Ptr starDetector = cv::xfeatures2d::StarDetector::create(); if (!usePyramid) { m_detectors[detectorNameTmp] = starDetector; @@ -1909,23 +1987,31 @@ void vpKeyPoint::initDetector(const std::string &detectorName) } #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the detector: STAR. OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION - << " was not build with xFeatures2d module."; + ss_msg << "Failed to initialize the STAR 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } else if (detectorNameTmp == "AGAST") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) + cv::Ptr agastDetector = cv::xfeatures2d::AgastFeatureDetector::create(); +#else cv::Ptr agastDetector = cv::AgastFeatureDetector::create(); +#endif if (!usePyramid) { m_detectors[detectorNameTmp] = agastDetector; } else { m_detectors[detectorName] = cv::makePtr(agastDetector); } +#else + std::stringstream ss_msg; + ss_msg << "Failed to initialize the STAR 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (detectorNameTmp == "MSD") { -#if (VISP_HAVE_OPENCV_VERSION >= 0x030100) -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if defined(HAVE_OPENCV_XFEATURES2D) cv::Ptr msdDetector = cv::xfeatures2d::MSDDetector::create(); if (!usePyramid) { m_detectors[detectorNameTmp] = msdDetector; @@ -1936,14 +2022,8 @@ void vpKeyPoint::initDetector(const std::string &detectorName) } #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the detector: MSD. OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION - << " was not build with xFeatures2d module."; + ss_msg << "Failed to initialize the MSD 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); -#endif -#else - std::stringstream ss_msg; - ss_msg << "Feature " << detectorName << " is not available in OpenCV version: " << std::hex - << VISP_HAVE_OPENCV_VERSION << " (require >= OpenCV 3.1)."; #endif } else { @@ -1956,7 +2036,7 @@ void vpKeyPoint::initDetector(const std::string &detectorName) detectorInitialized = !m_detectors[detectorNameTmp].empty(); } else { - // if not null and to avoid warning C4800: forcing value to bool 'true' or 'false' (performance warning) + // if not null and to avoid warning C4800: forcing value to bool 'true' or 'false' (performance warning) detectorInitialized = !m_detectors[detectorName].empty(); } @@ -1982,131 +2062,128 @@ void vpKeyPoint::initExtractor(const std::string &extractorName) m_extractors[extractorName] = cv::DescriptorExtractor::create(extractorName); #else if (extractorName == "SIFT") { -#if (VISP_HAVE_OPENCV_VERSION >= 0x040500) // OpenCV >= 4.5.0 - m_extractors[extractorName] = cv::SIFT::create(); -#else -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) || (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x040400) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) // SIFT is no more patented since 09/03/2020 -#if (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) +# if (VISP_HAVE_OPENCV_VERSION >= 0x030411) m_extractors[extractorName] = cv::SIFT::create(); -#else +# else m_extractors[extractorName] = cv::xfeatures2d::SIFT::create(); -#endif +# endif #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: SIFT. OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION - << " was not build with xFeatures2d module."; + ss_msg << "Fail to initialize the SIFT 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); -#endif #endif } else if (extractorName == "SURF") { -#ifdef VISP_HAVE_OPENCV_XFEATURES2D +#if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D) // Use extended set of SURF descriptors (128 instead of 64) m_extractors[extractorName] = cv::xfeatures2d::SURF::create(100, 4, 3, true); #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: SURF. OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION - << " was not build with xFeatures2d module."; + ss_msg << "Fail to initialize the SURF 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } else if (extractorName == "ORB") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) m_extractors[extractorName] = cv::ORB::create(); +#else + std::stringstream ss_msg; + ss_msg << "Fail to initialize the ORB 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (extractorName == "BRISK") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) + m_extractors[extractorName] = cv::xfeatures2d::BRISK::create(); +#else m_extractors[extractorName] = cv::BRISK::create(); +#endif +#else + std::stringstream ss_msg; + ss_msg << "Fail to initialize the BRISK 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (extractorName == "FREAK") { -#ifdef VISP_HAVE_OPENCV_XFEATURES2D +#if defined(HAVE_OPENCV_XFEATURES2D) m_extractors[extractorName] = cv::xfeatures2d::FREAK::create(); #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: " << extractorName << ". OpenCV version " << std::hex - << VISP_HAVE_OPENCV_VERSION << " was not build with xFeatures2d module."; + ss_msg << "Fail to initialize the FREAK 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } else if (extractorName == "BRIEF") { -#ifdef VISP_HAVE_OPENCV_XFEATURES2D +#if defined(HAVE_OPENCV_XFEATURES2D) m_extractors[extractorName] = cv::xfeatures2d::BriefDescriptorExtractor::create(); #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: " << extractorName << ". OpenCV version " << std::hex - << VISP_HAVE_OPENCV_VERSION << " was not build with xFeatures2d module."; + ss_msg << "Fail to initialize the BRIEF 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } else if (extractorName == "KAZE") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) + m_extractors[extractorName] = cv::xfeatures2d::KAZE::create(); +#else m_extractors[extractorName] = cv::KAZE::create(); +#endif +#else + std::stringstream ss_msg; + ss_msg << "Fail to initialize the KAZE 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; + throw vpException(vpException::fatalError, ss_msg.str()); +#endif } else if (extractorName == "AKAZE") { +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) + m_extractors[extractorName] = cv::xfeatures2d::AKAZE::create(); +#else m_extractors[extractorName] = cv::AKAZE::create(); - } - else if (extractorName == "DAISY") { -#ifdef VISP_HAVE_OPENCV_XFEATURES2D - m_extractors[extractorName] = cv::xfeatures2d::DAISY::create(); +#endif #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: " << extractorName << ". OpenCV version " << std::hex - << VISP_HAVE_OPENCV_VERSION << " was not build with xFeatures2d module."; + ss_msg << "Fail to initialize the AKAZE 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } - else if (extractorName == "LATCH") { -#ifdef VISP_HAVE_OPENCV_XFEATURES2D - m_extractors[extractorName] = cv::xfeatures2d::LATCH::create(); + else if (extractorName == "DAISY") { +#if defined(HAVE_OPENCV_XFEATURES2D) + m_extractors[extractorName] = cv::xfeatures2d::DAISY::create(); #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: " << extractorName << ". OpenCV version " << std::hex - << VISP_HAVE_OPENCV_VERSION << " was not build with xFeatures2d module."; + ss_msg << "Fail to initialize the DAISY 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } - else if (extractorName == "LUCID") { -#ifdef VISP_HAVE_OPENCV_XFEATURES2D - // m_extractors[extractorName] = cv::xfeatures2d::LUCID::create(1, 2); - // Not possible currently, need a color image - throw vpException(vpException::badValue, "Not possible currently as it needs a color image."); + else if (extractorName == "LATCH") { +#if defined(HAVE_OPENCV_XFEATURES2D) + m_extractors[extractorName] = cv::xfeatures2d::LATCH::create(); #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: " << extractorName << ". OpenCV version " << std::hex - << VISP_HAVE_OPENCV_VERSION << " was not build with xFeatures2d module."; + ss_msg << "Fail to initialize the LATCH 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } else if (extractorName == "VGG") { -#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(HAVE_OPENCV_XFEATURES2D) m_extractors[extractorName] = cv::xfeatures2d::VGG::create(); #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: " << extractorName << ". OpenCV version " << std::hex - << VISP_HAVE_OPENCV_VERSION << " was not build with xFeatures2d module."; - throw vpException(vpException::fatalError, ss_msg.str()); -#endif -#else - std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: " << extractorName << ". OpenCV version " << std::hex - << VISP_HAVE_OPENCV_VERSION << " but requires at least OpenCV 3.2."; + ss_msg << "Fail to initialize the VGG 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } else if (extractorName == "BoostDesc") { -#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(HAVE_OPENCV_XFEATURES2D) m_extractors[extractorName] = cv::xfeatures2d::BoostDesc::create(); #else std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: " << extractorName << ". OpenCV version " << std::hex - << VISP_HAVE_OPENCV_VERSION << " was not build with xFeatures2d module."; - throw vpException(vpException::fatalError, ss_msg.str()); -#endif -#else - std::stringstream ss_msg; - ss_msg << "Fail to initialize the extractor: " << extractorName << ". OpenCV version " << std::hex - << VISP_HAVE_OPENCV_VERSION << " but requires at least OpenCV 3.2."; + ss_msg << "Fail to initialize the BoostDesc 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION; throw vpException(vpException::fatalError, ss_msg.str()); #endif } @@ -2155,60 +2232,61 @@ void vpKeyPoint::initExtractors(const std::vector &extractorNames) void vpKeyPoint::initFeatureNames() { // Create map enum to string -#if (VISP_HAVE_OPENCV_VERSION >= 0x020403) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) m_mapOfDetectorNames[DETECTOR_FAST] = "FAST"; m_mapOfDetectorNames[DETECTOR_MSER] = "MSER"; m_mapOfDetectorNames[DETECTOR_ORB] = "ORB"; - m_mapOfDetectorNames[DETECTOR_BRISK] = "BRISK"; m_mapOfDetectorNames[DETECTOR_GFTT] = "GFTT"; m_mapOfDetectorNames[DETECTOR_SimpleBlob] = "SimpleBlob"; -#if (VISP_HAVE_OPENCV_VERSION < 0x030000) || (defined(VISP_HAVE_OPENCV_XFEATURES2D)) - m_mapOfDetectorNames[DETECTOR_STAR] = "STAR"; -#endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) - m_mapOfDetectorNames[DETECTOR_SIFT] = "SIFT"; #endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) - m_mapOfDetectorNames[DETECTOR_SURF] = "SURF"; -#endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030000) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) + m_mapOfDetectorNames[DETECTOR_BRISK] = "BRISK"; m_mapOfDetectorNames[DETECTOR_KAZE] = "KAZE"; m_mapOfDetectorNames[DETECTOR_AKAZE] = "AKAZE"; m_mapOfDetectorNames[DETECTOR_AGAST] = "AGAST"; #endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030100) && defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if defined(HAVE_OPENCV_XFEATURES2D) + m_mapOfDetectorNames[DETECTOR_STAR] = "STAR"; m_mapOfDetectorNames[DETECTOR_MSD] = "MSD"; #endif +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) + m_mapOfDetectorNames[DETECTOR_SIFT] = "SIFT"; +#endif +#if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D) + m_mapOfDetectorNames[DETECTOR_SURF] = "SURF"; +#endif +#if defined(HAVE_OPENCV_XFEATURES2D) + m_mapOfDetectorNames[DETECTOR_MSD] = "MSD"; #endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x020403) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) m_mapOfDescriptorNames[DESCRIPTOR_ORB] = "ORB"; +#endif +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) m_mapOfDescriptorNames[DESCRIPTOR_BRISK] = "BRISK"; -#if (VISP_HAVE_OPENCV_VERSION < 0x030000) || (defined(VISP_HAVE_OPENCV_XFEATURES2D)) +#endif +#if defined(HAVE_OPENCV_XFEATURES2D) m_mapOfDescriptorNames[DESCRIPTOR_FREAK] = "FREAK"; m_mapOfDescriptorNames[DESCRIPTOR_BRIEF] = "BRIEF"; #endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) m_mapOfDescriptorNames[DESCRIPTOR_SIFT] = "SIFT"; #endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D) m_mapOfDescriptorNames[DESCRIPTOR_SURF] = "SURF"; #endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030000) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) m_mapOfDescriptorNames[DESCRIPTOR_KAZE] = "KAZE"; m_mapOfDescriptorNames[DESCRIPTOR_AKAZE] = "AKAZE"; -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) +#endif +#if defined(HAVE_OPENCV_XFEATURES2D) m_mapOfDescriptorNames[DESCRIPTOR_DAISY] = "DAISY"; m_mapOfDescriptorNames[DESCRIPTOR_LATCH] = "LATCH"; #endif -#endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(HAVE_OPENCV_XFEATURES2D) m_mapOfDescriptorNames[DESCRIPTOR_VGG] = "VGG"; m_mapOfDescriptorNames[DESCRIPTOR_BoostDesc] = "BoostDesc"; #endif -#endif } void vpKeyPoint::initMatcher(const std::string &matcherName) @@ -4211,7 +4289,11 @@ void vpKeyPoint::PyramidAdaptedFeatureDetector::detectImpl(const cv::Mat &image, src = dst; if (!mask.empty()) +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) + resize(dilated_mask, src_mask, src.size(), 0, 0, cv::INTER_AREA); +#else resize(dilated_mask, src_mask, src.size(), 0, 0, CV_INTER_AREA); +#endif } } diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index eefbe8cb92..670474ce82 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -480,7 +480,6 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, FuncCheckValidityPose func) best_consensus = sequentialRansac.getBestConsensus(); } } - if (foundSolution) { const unsigned int nbMinRandom = 4; diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp index 778e60eef0..d3f811766e 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp @@ -41,14 +41,11 @@ #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) && defined(HAVE_OPENCV_VIDEO) +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES) || defined(HAVE_OPENCV_XFEATURES2D) || defined(HAVE_OPENCV_NONFREE)) #include #include -#include -#include -#include -#include +#include #include #include #include @@ -169,19 +166,15 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis vpImageIo::read(I, filenameRef); std::string filenameCur = vpIoTools::createFilePath(dirname, "image%04d." + ext); -#if defined(VISP_HAVE_X11) - vpDisplayX display; -#elif defined(VISP_HAVE_GTK) - vpDisplayGTK display; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI display; -#elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV display; -#endif + vpDisplay *display = nullptr; if (opt_display) { - display.setDownScalingFactor(vpDisplay::SCALE_AUTO); - display.init(I, 0, 0, "ORB keypoints matching and pose estimation"); +#ifdef VISP_HAVE_DISPLAY + display = vpDisplayFactory::allocateDisplay(I, 0, 0, "ORB keypoints matching and pose estimation"); + display->setDownScalingFactor(vpDisplay::SCALE_AUTO); +#else + std::cout << "No image viewer is available..." << std::endl; +#endif } vpCameraParameters cam; @@ -321,21 +314,15 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis g.open(I); g.acquire(I); -#if defined(VISP_HAVE_X11) - vpDisplayX display2; -#elif defined(VISP_HAVE_GTK) - vpDisplayGTK display2; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI display2; -#elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV display2; -#endif + vpDisplay *display2 = nullptr; keypoints.createImageMatching(I, IMatching); if (opt_display) { - display2.setDownScalingFactor(vpDisplay::SCALE_AUTO); - display2.init(IMatching, 0, (int)I.getHeight() / vpDisplay::getDownScalingFactor(I) + 80, "IMatching"); +#ifdef VISP_HAVE_DISPLAY + display2 = vpDisplayFactory::allocateDisplay(IMatching, 0, (int)I.getHeight() / vpDisplay::getDownScalingFactor(I) + 30, "IMatching"); + display2->setDownScalingFactor(vpDisplay::SCALE_AUTO); +#endif } bool opt_click = false; @@ -424,6 +411,13 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis } } + if (display) { + delete display; + } + if (display2) { + delete display2; + } + if (!times_vec.empty()) { std::cout << "Computation time, Mean: " << vpMath::getMean(times_vec) << " ms ; Median: " << vpMath::getMedian(times_vec) << " ms ; Std: " << vpMath::getStdev(times_vec) diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp index f4c4d67076..8a480a4aee 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp @@ -43,16 +43,19 @@ #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES)) -#include +#if defined(HAVE_OPENCV_FEATURES) +#include +#endif + +#if defined(HAVE_OPENCV_FEATURES2D) +#include +#endif #include #include -#include -#include -#include -#include +#include #include #include #include @@ -192,19 +195,15 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis Imatch.resize(Icur.getHeight(), 2 * Icur.getWidth()); Imatch.insert(Iref, vpImagePoint(0, 0)); -#if defined(VISP_HAVE_X11) - vpDisplayX display; -#elif defined(VISP_HAVE_GTK) - vpDisplayGTK display; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI display; -#elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV display; -#endif + vpDisplay *display = nullptr; if (opt_display) { - display.setDownScalingFactor(vpDisplay::SCALE_AUTO); - display.init(Imatch, 0, 0, "ORB keypoints matching"); +#ifdef VISP_HAVE_DISPLAY + display = vpDisplayFactory::allocateDisplay(Imatch, 0, 0, "ORB keypoints matching"); + display->setDownScalingFactor(vpDisplay::SCALE_AUTO); +#else + std::cout << "No image viewer is available..." << std::endl; +#endif } bool opt_click = false; @@ -269,6 +268,10 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis } } } + + if (display) { + delete display; + } } int main(int argc, const char **argv) diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp index 94d69d74d6..e73901fe6b 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp @@ -43,15 +43,12 @@ #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES)) #include #include #include -#include -#include -#include -#include +#include #include #include #include @@ -151,7 +148,7 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) template void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_display, vpImage &I, - vpImage &Imatch, vpImage &Iref) + vpImage &Imatch, vpImage &Iref) { #if VISP_HAVE_DATASET_VERSION >= 0x030600 std::string ext("png"); @@ -167,23 +164,20 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis Iref = I; std::string filenameCur = vpIoTools::createFilePath(dirname, "image%04d." + ext); -#if defined(VISP_HAVE_X11) - vpDisplayX display, display2; -#elif defined(VISP_HAVE_GTK) - vpDisplayGTK display, display2; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI display, display2; -#elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV display, display2; -#endif + vpDisplay *display = nullptr, *display2 = nullptr; if (opt_display) { - display.setDownScalingFactor(vpDisplay::SCALE_AUTO); - display.init(I, 0, 0, "ORB keypoints matching"); Imatch.resize(I.getHeight(), 2 * I.getWidth()); Imatch.insert(I, vpImagePoint(0, 0)); - display2.setDownScalingFactor(vpDisplay::SCALE_AUTO); - display2.init(Imatch, 0, (int)I.getHeight() / vpDisplay::getDownScalingFactor(I) + 70, "ORB keypoints matching"); + +#ifdef VISP_HAVE_DISPLAY + display = vpDisplayFactory::allocateDisplay(I, 0, 0, "ORB keypoints matching"); + display->setDownScalingFactor(vpDisplay::SCALE_AUTO); + display2 = vpDisplayFactory::allocateDisplay(Imatch, 0, (int)I.getHeight() / vpDisplay::getDownScalingFactor(I) + 40, "ORB keypoints matching"); + display2->setDownScalingFactor(vpDisplay::SCALE_AUTO); +#else + std::cout << "No image viewer is available..." << std::endl; +#endif } vpCameraParameters cam; @@ -240,19 +234,12 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis cv::Ptr extractor; cv::Ptr matcher; -#if (VISP_HAVE_OPENCV_VERSION >= 0x030000) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) detector = cv::ORB::create(500, 1.2f, 1); extractor = cv::ORB::create(500, 1.2f, 1); -#elif (VISP_HAVE_OPENCV_VERSION >= 0x020301) - detector = cv::FeatureDetector::create("ORB"); - extractor = cv::DescriptorExtractor::create("ORB"); #endif matcher = cv::DescriptorMatcher::create("BruteForce-Hamming"); -#if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000) - detector->set("nLevels", 1); -#endif - // Detect keypoints on the current image std::vector trainKeyPoints; cv::Mat matImg; @@ -286,7 +273,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis bool opt_click = false; vpMouseButton::vpMouseButtonType button; - while ((opt_display && !g.end()) || (!opt_display && g.getFrameIndex() < 30)) { + while (g.getFrameIndex() < 30) { g.acquire(I); vpImageConvert::convert(I, matImg); @@ -326,12 +313,16 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis bool is_pose_estimated = false; if (estimated_pose.npt >= 4) { try { - unsigned int nb_inliers = (unsigned int)(0.6 * estimated_pose.npt); + unsigned int nb_inliers = static_cast(0.7 * estimated_pose.npt); estimated_pose.setRansacNbInliersToReachConsensus(nb_inliers); - estimated_pose.setRansacThreshold(0.01); + estimated_pose.setRansacThreshold(0.001); estimated_pose.setRansacMaxTrials(500); - estimated_pose.computePose(vpPose::RANSAC, cMo); - is_pose_estimated = true; + if (estimated_pose.computePose(vpPose::RANSAC, cMo)) { + is_pose_estimated = true; // success + } + else { + is_pose_estimated = false; + } } catch (...) { is_pose_estimated = false; @@ -381,6 +372,13 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis } } } + + if (display) { + delete display; + } + if (display2) { + delete display2; + } } int main(int argc, const char **argv) diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp index 8321466188..9aae6b73ab 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp @@ -43,14 +43,11 @@ #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) && defined(HAVE_OPENCV_VIDEO) +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES)) #include #include -#include -#include -#include -#include +#include #include #include #include @@ -158,64 +155,60 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis vpImageIo::read(Iinput, filename); Iinput.halfSizeImage(I); -#if defined(VISP_HAVE_X11) - vpDisplayX display; -#elif defined(VISP_HAVE_GTK) - vpDisplayGTK display; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI display; -#elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV display; -#endif + vpDisplay *display = nullptr; if (opt_display) { - display.init(I, 0, 0, "KeyPoints detection."); +#ifdef VISP_HAVE_DISPLAY + display = vpDisplayFactory::allocateDisplay(I, 0, 0, "KeyPoints detection."); +#else + std::cout << "No image viewer is available..." << std::endl; +#endif } // Here, we want to test feature detection on a pyramid of images even for // features that are scale invariant to detect potential problem in ViSP. std::cout << "INFORMATION: " << std::endl; std::cout << "Here, we want to test feature detection on a pyramid of images even for features " - "that are scale invariant to detect potential problem in ViSP." - << std::endl + << "that are scale invariant to detect potential problem in ViSP." << std::endl << std::endl; vpKeyPoint keyPoints; // Will test the different types of keypoints detection to see if there is // a problem between OpenCV versions, modules or constructors std::vector detectorNames; +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) detectorNames.push_back("PyramidFAST"); detectorNames.push_back("FAST"); +#endif +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) detectorNames.push_back("PyramidMSER"); detectorNames.push_back("MSER"); detectorNames.push_back("PyramidGFTT"); detectorNames.push_back("GFTT"); detectorNames.push_back("PyramidSimpleBlob"); detectorNames.push_back("SimpleBlob"); -// In contrib modules -#if (VISP_HAVE_OPENCV_VERSION < 0x030000) || defined(VISP_HAVE_OPENCV_XFEATURES2D) +#endif + + // In contrib modules +#if defined(HAVE_OPENCV_XFEATURES2D) detectorNames.push_back("PyramidSTAR"); detectorNames.push_back("STAR"); #endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030000) - detectorNames.push_back("PyramidAGAST"); - detectorNames.push_back("AGAST"); -#endif +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) detectorNames.push_back("PyramidORB"); detectorNames.push_back("ORB"); -#if (VISP_HAVE_OPENCV_VERSION >= 0x020403) - detectorNames.push_back("PyramidBRISK"); - detectorNames.push_back("BRISK"); #endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030000) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) + detectorNames.push_back("PyramidAGAST"); + detectorNames.push_back("AGAST"); detectorNames.push_back("PyramidBRISK"); + detectorNames.push_back("BRISK"); detectorNames.push_back("PyramidKAZE"); detectorNames.push_back("KAZE"); detectorNames.push_back("PyramidAKAZE"); detectorNames.push_back("AKAZE"); #endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) #if (VISP_HAVE_OPENCV_VERSION != 0x040504) && (VISP_HAVE_OPENCV_VERSION != 0x040505) && \ (VISP_HAVE_OPENCV_VERSION != 0x040600) && (VISP_HAVE_OPENCV_VERSION != 0x040700) && \ (VISP_HAVE_OPENCV_VERSION != 0x040900) && (VISP_HAVE_OPENCV_VERSION != 0x040A00) && \ @@ -228,7 +221,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis detectorNames.push_back("SIFT"); #endif #endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D) detectorNames.push_back("PyramidSURF"); detectorNames.push_back("SURF"); #endif @@ -268,8 +261,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis std::map mapOfDetectorNames = keyPoints.getDetectorNames(); for (int i = 0; i < vpKeyPoint::DETECTOR_TYPE_SIZE; i++) { -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) #if ((VISP_HAVE_OPENCV_VERSION == 0x040504) || (VISP_HAVE_OPENCV_VERSION == 0x040505) || \ (VISP_HAVE_OPENCV_VERSION == 0x040600) || (VISP_HAVE_OPENCV_VERSION == 0x040700) || \ (VISP_HAVE_OPENCV_VERSION == 0x040900) || (VISP_HAVE_OPENCV_VERSION == 0x040A00)) && \ @@ -314,6 +306,10 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis } } } + + if (display) { + delete display; + } } int main(int argc, const char **argv) diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp index 2b5471617a..9678347eca 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp @@ -41,14 +41,11 @@ #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) && defined(HAVE_OPENCV_VIDEO) +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES)) #include #include -#include -#include -#include -#include +#include #include #include #include @@ -203,54 +200,48 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis vpImageIo::read(Iinput, filename); Iinput.quarterSizeImage(I); -#if defined(VISP_HAVE_X11) - vpDisplayX display; -#elif defined(VISP_HAVE_GTK) - vpDisplayGTK display; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI display; -#elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV display; -#endif + vpDisplay *display = nullptr; if (opt_display) { - display.init(I, 0, 0, "KeyPoints detection."); +#ifdef VISP_HAVE_DISPLAY + display = vpDisplayFactory::allocateDisplay(I, 0, 0, "KeyPoints detection."); +#else + std::cout << "No image viewer is available..." << std::endl; +#endif } vpKeyPoint keyPoints; std::vector descriptorNames; -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) descriptorNames.push_back("SIFT"); #endif -#if defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if defined(HAVE_OPENCV_NONFREE) || defined(HAVE_OPENCV_XFEATURES2D) descriptorNames.push_back("SURF"); #endif +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) descriptorNames.push_back("ORB"); -#if (VISP_HAVE_OPENCV_VERSION >= 0x020403) +#endif +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) descriptorNames.push_back("BRISK"); #endif -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) || (VISP_HAVE_OPENCV_VERSION < 0x030000) +#if defined(HAVE_OPENCV_XFEATURES2D) descriptorNames.push_back("BRIEF"); -#if (VISP_HAVE_OPENCV_VERSION >= 0x020402) descriptorNames.push_back("FREAK"); -#endif -#endif -#if defined(VISP_HAVE_OPENCV_XFEATURES2D) descriptorNames.push_back("DAISY"); descriptorNames.push_back("LATCH"); #endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(HAVE_OPENCV_XFEATURES2D) descriptorNames.push_back("VGG"); descriptorNames.push_back("BoostDesc"); #endif -#if (VISP_HAVE_OPENCV_VERSION >= 0x030000) +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) descriptorNames.push_back("KAZE"); descriptorNames.push_back("AKAZE"); #endif - +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) std::string detectorName = "FAST"; +#endif keyPoints.setDetector(detectorName); std::vector kpts; @@ -288,7 +279,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis } } else if (*itd == "BoostDesc") { -#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(HAVE_OPENCV_XFEATURES2D) cv::Ptr boostDesc = keyPoints.getExtractor("BoostDesc"); // Init BIN BOOST descriptor for FAST keypoints boostDesc = cv::xfeatures2d::BoostDesc::create(cv::xfeatures2d::BoostDesc::BINBOOST_256, true, 5.0f); @@ -357,7 +348,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis } } else if (mapOfDescriptorNames[(vpKeyPoint::vpFeatureDescriptorType)i] == "BoostDesc") { -#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(VISP_HAVE_OPENCV_XFEATURES2D) +#if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(HAVE_OPENCV_XFEATURES2D) detectorName = "FAST"; keyPoints.setDetector(detectorName); keyPoints.detect(I, kpts); @@ -407,6 +398,9 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis } } } + if (display) { + delete display; + } } int main(int argc, const char **argv) diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp index eba90a7573..22c0e663f1 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp @@ -42,7 +42,7 @@ #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) && defined(HAVE_OPENCV_VIDEO) +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES)) #include #include @@ -466,10 +466,8 @@ template void run_test(const std::string &env_ipath, const std:: std::cout << "Saving / loading learning files with binary descriptor are ok !" << std::endl; } -// Test with floating point descriptor -#if defined(VISP_HAVE_OPENCV_NONFREE) || \ - ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400)) + // Test with floating point descriptor +#if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) { #if (VISP_HAVE_OPENCV_VERSION != 0x040504) && (VISP_HAVE_OPENCV_VERSION != 0x040505) && \ (VISP_HAVE_OPENCV_VERSION != 0x040600) && (VISP_HAVE_OPENCV_VERSION != 0x040700) && \ diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp index 5278fe739e..4232361cbf 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp @@ -41,14 +41,11 @@ #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) && defined(HAVE_OPENCV_VIDEO) +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES) || defined(HAVE_OPENCV_XFEATURES2D) || defined(HAVE_OPENCV_NONFREE)) #include #include -#include -#include -#include -#include +#include #include #include #include @@ -75,24 +72,23 @@ bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display) void usage(const char *name, const char *badparam) { fprintf(stdout, "\n\ - Test keypoints matching.\n\ - \n\ - SYNOPSIS\n\ - %s [-c] [-d] [-h]\n", - name); + Test keypoints matching.\n\ + \n\ + SYNOPSIS\n\ + %s [-c] [-d] [-h]\n", name); fprintf(stdout, "\n\ - OPTIONS: \n\ - \n\ - -c\n\ - Disable the mouse click. Useful to automate the \n\ - execution of this program without human intervention.\n\ - \n\ - -d \n\ - Turn off the display.\n\ - \n\ - -h\n\ - Print the help.\n"); + OPTIONS: \n\ + \n\ + -c\n\ + Disable the mouse click. Useful to automate the \n\ + execution of this program without human intervention.\n\ + \n\ + -d \n\ + Turn off the display.\n\ + \n\ + -h\n\ + Print the help.\n"); if (badparam) fprintf(stdout, "\nERROR: Bad parameter [%s]\n", badparam); @@ -174,19 +170,15 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis Imatch.resize(Icur.getHeight(), 2 * Icur.getWidth()); Imatch.insert(Iref, vpImagePoint(0, 0)); -#if defined(VISP_HAVE_X11) - vpDisplayX display; -#elif defined(VISP_HAVE_GTK) - vpDisplayGTK display; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI display; -#elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV display; -#endif + vpDisplay *display = nullptr; if (opt_display) { - display.setDownScalingFactor(vpDisplay::SCALE_AUTO); - display.init(Imatch, 0, 0, "ORB keypoints matching"); +#ifdef VISP_HAVE_DISPLAY + display = vpDisplayFactory::allocateDisplay(Imatch, 0, 0, "ORB keypoints matching"); + display->setDownScalingFactor(vpDisplay::SCALE_AUTO); +#else + std::cout << "No image viewer is available..." << std::endl; +#endif } bool opt_click = false; @@ -217,7 +209,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis } } else { - // Use right click to enable/disable step by step tracking + // Use right click to enable/disable step by step tracking if (vpDisplay::getClick(Imatch, button, false)) { if (button == vpMouseButton::button3) { opt_click = true; @@ -229,6 +221,10 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis } } } + + if (display) { + delete display; + } } int main(int argc, const char **argv) diff --git a/tutorial/bridge/opencv/CMakeLists.txt b/tutorial/bridge/opencv/CMakeLists.txt index 1c2130b14c..333e32dcdf 100644 --- a/tutorial/bridge/opencv/CMakeLists.txt +++ b/tutorial/bridge/opencv/CMakeLists.txt @@ -9,7 +9,7 @@ set(tutorial_cpp tutorial-bridge-opencv-image.cpp tutorial-bridge-opencv-matrix.cpp) -list(APPEND tutorial_data "${CMAKE_CURRENT_SOURCE_DIR}/chessboard.pgm" ) +list(APPEND tutorial_data "${CMAKE_CURRENT_SOURCE_DIR}/chessboard.jpeg" ) list(APPEND tutorial_data "${CMAKE_CURRENT_SOURCE_DIR}/monkey.jpeg" ) foreach(cpp ${tutorial_cpp}) diff --git a/tutorial/bridge/opencv/tutorial-bridge-opencv-camera-param.cpp b/tutorial/bridge/opencv/tutorial-bridge-opencv-camera-param.cpp index c5fb8621e7..2bc7c8a295 100644 --- a/tutorial/bridge/opencv/tutorial-bridge-opencv-camera-param.cpp +++ b/tutorial/bridge/opencv/tutorial-bridge-opencv-camera-param.cpp @@ -1,12 +1,20 @@ //! \example tutorial-bridge-opencv-camera-param.cpp #include -#include + #include + +#if defined(HAVE_OPENCV_IMGPROC) \ + && (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_3D))) + +#include #include #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) && defined(HAVE_OPENCV_IMGPROC) +#if defined(HAVE_OPENCV_CALIB3D) #include +#elif defined(HAVE_OPENCV_3D) +#include +#endif #include #include @@ -32,7 +40,9 @@ int main() //! [Load ViSP image] vpImage I; - vpImageIo::read(I, "chessboard.pgm"); + std::string image_name = "chessboard.jpeg"; + std::cout << "Read image: " << image_name << std::endl; + vpImageIo::read(I, image_name); //! [Load ViSP image] //! [Convert ViSP 2 OpenCV image] @@ -51,14 +61,24 @@ int main() //! [Convert OpenCV 2 ViSP image] //! [Save image] - vpImageIo::write(IUndistorted, "chessboard-undistorted.pgm"); + image_name = "chessboard-undistorted.jpeg"; + std::cout << "Save undistorted image: " << image_name << std::endl; + vpImageIo::write(IUndistorted, image_name); //! [Save image] } #else int main() { - std::cout << "This tutorial required OpenCV imgproc module" << std::endl; +#if !defined(HAVE_OPENCV_IMGPROC) + std::cout << "This tutorial requires OpenCV imgproc module." << std::endl; +#endif +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) && !defined(HAVE_OPENCV_CALIB3D) + std::cout << "This tutorial requires OpenCV calib3d module." << std::endl; +#endif +#if (VISP_HAVE_OPENCV_VERSION >= 0x050000) && !defined(HAVE_OPENCV_3D) + std::cout << "This tutorial requires OpenCV 3d module." << std::endl; +#endif return EXIT_SUCCESS; } #endif diff --git a/tutorial/bridge/opencv/tutorial-bridge-opencv-image.cpp b/tutorial/bridge/opencv/tutorial-bridge-opencv-image.cpp index aebd60ca44..79f3ef3c70 100644 --- a/tutorial/bridge/opencv/tutorial-bridge-opencv-image.cpp +++ b/tutorial/bridge/opencv/tutorial-bridge-opencv-image.cpp @@ -2,10 +2,12 @@ #include #include + +#if defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_IMGCODECS) + #include #include -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_IMGCODECS) #include #include #include @@ -19,38 +21,43 @@ int main() { //! [Load ViSP color image] vpImage Irgba; - vpImageIo::read(Irgba, "monkey.jpeg"); + std::string image_name = "monkey.jpeg"; + std::cout << "Read color image: " << image_name << std::endl; + vpImageIo::read(Irgba, image_name); //! [Load ViSP color image] - //! [Load ViSP grey image] - vpImage Igrey; - vpImageIo::read(Igrey, "monkey.jpeg"); - //! [Load ViSP grey image] + //! [Load ViSP gray image] + vpImage Igray; + std::cout << "Read gray image: " << image_name << std::endl; + vpImageIo::read(Igray, image_name); + //! [Load ViSP gray image] //! [Convert to OpenCV color image] cv::Mat cv_img_color; vpImageConvert::convert(Irgba, cv_img_color); //! [Convert to OpenCV color image] - //! [Convert to OpenCV grey image] - cv::Mat cv_img_grey; - vpImageConvert::convert(Igrey, cv_img_grey); - //! [Convert to OpenCV grey image] + //! [Convert to OpenCV gray image] + cv::Mat cv_img_gray; + vpImageConvert::convert(Igray, cv_img_gray); + //! [Convert to OpenCV gray image] std::cout << "Save converted images from vpImage to cv::Mat" << std::endl; std::cout << "- monkey-cv-color.jpeg" << std::endl; - std::cout << "- monkey-cv-grey.jpeg" << std::endl; + std::cout << "- monkey-cv-gray.jpeg" << std::endl; //! [Save OpenCV color image] cv::imwrite("monkey-cv-color.jpeg", cv_img_color); //! [Save OpenCV color image] - //! [Save OpenCV grey image] - cv::imwrite("monkey-cv-grey.jpeg", cv_img_grey); - //! [Save OpenCV grey image] + //! [Save OpenCV gray image] + cv::imwrite("monkey-cv-gray.jpeg", cv_img_gray); + //! [Save OpenCV gray image] } // From OpenCV to ViSP conversion { //! [Load OpenCV color image] + std::string image_name = "monkey.jpeg"; + std::cout << "Read color image: " << image_name << std::endl; #if VISP_HAVE_OPENCV_VERSION >= 0x030000 cv::Mat cv_img_color = cv::imread("monkey.jpeg", cv::IMREAD_COLOR); #else @@ -63,34 +70,40 @@ int main() vpImageConvert::convert(cv_img_color, Irgba); //! [Convert to ViSP color image] - //! [Load OpenCV grey image] + //! [Load OpenCV gray image] + std::cout << "Read gray image: " << image_name << std::endl; #if VISP_HAVE_OPENCV_VERSION >= 0x030000 - cv::Mat cv_img_grey = cv::imread("monkey.jpeg", cv::IMREAD_GRAYSCALE); + cv::Mat cv_img_gray = cv::imread("monkey.jpeg", cv::IMREAD_GRAYSCALE); #else - cv::Mat cv_img_grey = cv::imread("monkey.jpeg", CV_LOAD_IMAGE_GRAYSCALE); + cv::Mat cv_img_gray = cv::imread("monkey.jpeg", CV_LOAD_IMAGE_GRAYSCALE); #endif - //! [Load OpenCV grey image] + //! [Load OpenCV gray image] - //! [Convert to ViSP grey image] - vpImage Igrey; - vpImageConvert::convert(cv_img_grey, Igrey); - //! [Convert to ViSP grey image] + //! [Convert to ViSP gray image] + vpImage Igray; + vpImageConvert::convert(cv_img_gray, Igray); + //! [Convert to ViSP gray image] std::cout << "Save converted images from cv::Mat to vpImage" << std::endl; std::cout << "- monkey-vp-color.jpeg" << std::endl; - std::cout << "- monkey-vp-grey.jpeg" << std::endl; + std::cout << "- monkey-vp-gray.jpeg" << std::endl; //! [Save ViSP color image] vpImageIo::write(Irgba, "monkey-vp-color.jpeg"); //! [Save ViSP color image] - //! [Save ViSP grey image] - vpImageIo::write(Igrey, "monkey-vp-grey.jpeg"); - //! [Save ViSP grey image] + //! [Save ViSP gray image] + vpImageIo::write(Igray, "monkey-vp-gray.jpeg"); + //! [Save ViSP gray image] } } #else int main() { - std::cout << "This tutorial required OpenCV imgproc and imgcodecs modules." << std::endl; +#if !defined(HAVE_OPENCV_IMGPROC) + std::cout << "This tutorial requires OpenCV imgproc module." << std::endl; +#endif +#if !defined(HAVE_OPENCV_IMGPROC) + std::cout << "This tutorial requires OpenCV imgcodecs module." << std::endl; +#endif return EXIT_SUCCESS; } #endif diff --git a/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp b/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp index 698bf5f237..7ad9c3e71d 100644 --- a/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp +++ b/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp @@ -1,16 +1,15 @@ //! \example tutorial-bridge-opencv-matrix.cpp #include + +#if defined(HAVE_OPENCV_CORE) + #include #include -#if defined(HAVE_OPENCV_IMGPROC) #include -#include -#endif int main() { -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; #endif @@ -52,6 +51,14 @@ int main() std::cout << "M: \n" << M << std::endl; std::cout << "M_cv: \n" << M_cv << std::endl; //! [Modify ViSP matrix] + } } +#else +int main() +{ +#if !defined(HAVE_OPENCV_CORE) + std::cout << "This tutorial requires OpenCV core module." << std::endl; #endif + return EXIT_SUCCESS; } +#endif diff --git a/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp b/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp index 146f625986..5f3eb452f6 100644 --- a/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp @@ -135,7 +135,7 @@ inline Model::Model(const std::string &model_filename) data_curr_line++; } catch (...) { - // Line is empty or incomplete. We skeep it + // Line is empty or incomplete. We skeep it } } @@ -167,7 +167,7 @@ std::ostream &operator<<(std::ostream &os, const Model &model) << std::setw(6) << std::setfill(' ') << bound.get_X() << ", " << std::setw(6) << std::setfill(' ') << bound.get_Y() << ", " << std::setw(6) << std::setfill(' ') << bound.get_Z() << std::endl; - // clang-format on + // clang-format on } os << "-Keypoints:" << std::endl; @@ -177,7 +177,7 @@ std::ostream &operator<<(std::ostream &os, const Model &model) << std::setw(6) << std::setfill(' ') << keypoint.get_X() << ", " << std::setw(6) << std::setfill(' ') << keypoint.get_Y() << ", " << std::setw(6) << std::setfill(' ') << keypoint.get_Z() << std::endl; - // clang-format on + // clang-format on } return os; diff --git a/tutorial/computer-vision/tutorial-pose-from-points-live.cpp b/tutorial/computer-vision/tutorial-pose-from-points-live.cpp index 8710c9d118..bf7171107b 100644 --- a/tutorial/computer-vision/tutorial-pose-from-points-live.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-points-live.cpp @@ -42,25 +42,32 @@ int main(int argc, char **argv) double opt_square_width = 0.12; int opt_device = 0; // For OpenCV and V4l2 grabber to set the camera device - for (int i = 0; i < argc; i++) { + for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--intrinsic" && i + 1 < argc) { - opt_intrinsic_file = std::string(argv[i + 1]); + opt_intrinsic_file = std::string(argv[++i]); } - else if (std::string(argv[i]) == "--camera_name" && i + 1 < argc) { - opt_camera_name = std::string(argv[i + 1]); + else if (std::string(argv[i]) == "--camera-name" && i + 1 < argc) { + opt_camera_name = std::string(argv[++i]); } - else if (std::string(argv[i]) == "--camera_device" && i + 1 < argc) { - opt_device = atoi(argv[i + 1]); + else if (std::string(argv[i]) == "--camera-device" && i + 1 < argc) { + opt_device = atoi(argv[++i]); + } + else if (std::string(argv[i]) == "--square-width" && i + 1 < argc) { + opt_device = atoi(argv[++i]); } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { - std::cout << "\nUsage: " << argv[0] << " [--camera_device (default: 0)]" + std::cout << "\nUsage: " << argv[0] + << " [--camera-device (default: 0)]" << " [--intrinsic (default: empty)]" - " [--camera_name (default: empty)]" - " [--square_width (default: empty)]" + << " [--square-width I; - // Parameters of our camera - vpCameraParameters cam(840, 840, I.getWidth() / 2, I.getHeight() / 2); // Default parameters - vpXmlParserCamera parser; - if (!opt_intrinsic_file.empty() && !opt_camera_name.empty()) { - std::cout << "Intrinsic file: " << opt_intrinsic_file << std::endl; - std::cout << "Camera name : " << opt_camera_name << std::endl; - if (parser.parse(cam, opt_intrinsic_file, opt_camera_name, vpCameraParameters::perspectiveProjWithDistortion) == - vpXmlParserCamera::SEQUENCE_OK) { - std::cout << "Succeed to read camera parameters from xml file" << std::endl; - } - else { - std::cout << "Unable to read camera parameters from xml file" << std::endl; - } - } - //! [Grabber] #if defined(VISP_HAVE_V4L2) vpV4l2Grabber g; @@ -133,6 +125,21 @@ int main(int argc, char **argv) #endif //! [Grabber] + // Parameters of our camera + vpCameraParameters cam(840, 840, I.getWidth() / 2, I.getHeight() / 2); // Default parameters + vpXmlParserCamera parser; + if (!opt_intrinsic_file.empty() && !opt_camera_name.empty()) { + std::cout << "Intrinsic file: " << opt_intrinsic_file << std::endl; + std::cout << "Camera name : " << opt_camera_name << std::endl; + if (parser.parse(cam, opt_intrinsic_file, opt_camera_name, vpCameraParameters::perspectiveProjWithDistortion) == + vpXmlParserCamera::SEQUENCE_OK) { + std::cout << "Succeed to read camera parameters from xml file" << std::endl; + } + else { + std::cout << "Unable to read camera parameters from xml file" << std::endl; + } + } + std::cout << "Square width : " << opt_square_width << std::endl; std::cout << cam << std::endl; @@ -236,4 +243,4 @@ int main(int argc, char **argv) "use this example" << std::endl; #endif - } +} diff --git a/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp b/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp index ca624086c4..d6d5f008f0 100644 --- a/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp @@ -20,16 +20,19 @@ int main(int argc, char **argv) double opt_square_width = 0.12; int opt_camera_index = 1; // camera index: 1. Left, 2.Right - for (int i = 0; i < argc; i++) { + for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--camera_index" && i + 1 < argc) { - opt_camera_index = atoi(argv[i + 1]); + opt_camera_index = atoi(argv[++i]); } else if (std::string(argv[i]) == "--square_width" && i + 1 < argc) { - opt_square_width = atoi(argv[i + 1]); + opt_square_width = atoi(argv[++i]); } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { - std::cout << "\nUsage: " << argv[0] << " [--camera_index <1.Left | 2.Right> (default: 1)]" - << " [--square_width (default: 1)]" + << " [--square_width ] [--code-type <0 for QR code | " - "1 for DataMatrix code>] [--help] [-h]" + << " [--device ]" + << " [--code-type <0 for QR code | 1 for DataMatrix code>]" + << " [--help] [-h]" << std::endl; return EXIT_SUCCESS; } diff --git a/tutorial/detection/barcode/tutorial-barcode-detector.cpp b/tutorial/detection/barcode/tutorial-barcode-detector.cpp index 00bfb1dba3..d3905469b8 100644 --- a/tutorial/detection/barcode/tutorial-barcode-detector.cpp +++ b/tutorial/detection/barcode/tutorial-barcode-detector.cpp @@ -11,7 +11,7 @@ int main(int argc, const char **argv) { //! [Macro defined] -#if (defined(VISP_HAVE_ZBAR) || defined(VISP_HAVE_DMTX)) && \ +#if (defined(VISP_HAVE_ZBAR) || defined(VISP_HAVE_DMTX)) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) //! [Macro defined] #ifdef ENABLE_VISP_NAMESPACE @@ -36,9 +36,10 @@ int main(int argc, const char **argv) #if (defined(VISP_HAVE_ZBAR) && defined(VISP_HAVE_DMTX)) int opt_barcode = 0; // 0=QRCode, 1=DataMatrix - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--code-type") - opt_barcode = atoi(argv[i + 1]); + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--code-type" && i + 1 < argc) { + opt_barcode = atoi(argv[++i]); + } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Usage: " << argv[0] << " [--code-type <0 for QR code | 1 for DataMatrix code>] [--help] [-h]" << std::endl; @@ -96,7 +97,7 @@ int main(int argc, const char **argv) vpDisplay::getClick(I); } delete detector; -} + } catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } diff --git a/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp b/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp index 63bf19e8d6..8474d631ff 100644 --- a/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp +++ b/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp @@ -2,6 +2,14 @@ #include #include + +#if defined(VISP_HAVE_THREADS) && defined(HAVE_OPENCV_HIGHGUI) \ + && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEOIO) \ + && (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_OBJDETECT)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XOBJDETECT))) + +#include +#include + #include #include #include @@ -9,12 +17,6 @@ #include #include -#if defined(HAVE_OPENCV_OBJDETECT) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) \ - && defined(HAVE_OPENCV_VIDEOIO) && defined(VISP_HAVE_THREADS) - -#include -#include - #include #ifdef ENABLE_VISP_NAMESPACE @@ -200,17 +202,22 @@ int main(int argc, const char *argv[]) unsigned int opt_scale = 2; // Default value is 2 in the constructor. Turn // it to 1 to avoid subsampling - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--haar") - opt_face_cascade_name = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--device") - opt_device = (unsigned int)atoi(argv[i + 1]); - else if (std::string(argv[i]) == "--scale") - opt_scale = (unsigned int)atoi(argv[i + 1]); - else if (std::string(argv[i]) == "--help") { + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--haar" && i + 1 < argc) { + opt_face_cascade_name = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--device" && i + 1 < argc) { + opt_device = (unsigned int)atoi(argv[++i]); + } + else if (std::string(argv[i]) == "--scale" && i + 1 < argc) { + opt_scale = (unsigned int)atoi(argv[++i]); + } + else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) { std::cout << "Usage: " << argv[0] - << " [--haar ] [--device ] [--scale ] [--help]" + << " [--haar ]" + << " [--device ]" + << " [--scale ]" + << " [--help] [-h]" << std::endl; return EXIT_SUCCESS; } @@ -266,13 +273,25 @@ int main(int argc, const char *argv[]) #else int main() { -#ifndef VISP_HAVE_OPENCV - std::cout << "You should install OpenCV to make this example working..." << std::endl; -#elif !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX - std::cout << "You should enable pthread usage and rebuild ViSP..." << std::endl; -#else - std::cout << "Multi-threading seems not supported on this platform" << std::endl; +#if !defined(VISP_HAVE_THREADS) + std::cout << "This tutorial needs std::threads that is missing." << std::endl; +#endif +#if !defined(HAVE_OPENCV_HIGHGUI) + std::cout << "This tutorial needs OpenCV highgui module that is missing." << std::endl; +#endif +#if !defined(HAVE_OPENCV_VIDEOIO) + std::cout << "This tutorial needs OpenCV videoio module that is missing." << std::endl; #endif +#if !defined(HAVE_OPENCV_IMGPROC) + std::cout << "This tutorial needs OpenCV imgproc module that is missing." << std::endl; +#endif +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) && !defined(HAVE_OPENCV_OBJDETECT) + std::cout << "This tutorial needs OpenCV objdetect module that is missing." << std::endl; +#endif +#if ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && !defined(HAVE_OPENCV_XOBJDETECT)) + std::cout << "This tutorial needs OpenCV xobjdetect module that is missing." << std::endl; +#endif + return EXIT_SUCCESS; } diff --git a/tutorial/detection/face/tutorial-face-detector-live.cpp b/tutorial/detection/face/tutorial-face-detector-live.cpp index 7c6c3df58f..ad899f7314 100644 --- a/tutorial/detection/face/tutorial-face-detector-live.cpp +++ b/tutorial/detection/face/tutorial-face-detector-live.cpp @@ -14,7 +14,8 @@ int main(int argc, const char *argv[]) { -#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_OBJDETECT) +#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) \ + && (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_OBJDETECT)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XOBJDETECT))) #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; #endif @@ -24,17 +25,22 @@ int main(int argc, const char *argv[]) unsigned int opt_scale = 2; // Default value is 2 in the constructor. Turn // it to 1 to avoid subsampling - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--haar") - opt_face_cascade_name = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--device") - opt_device = (unsigned int)atoi(argv[i + 1]); - else if (std::string(argv[i]) == "--scale") - opt_scale = (unsigned int)atoi(argv[i + 1]); - else if (std::string(argv[i]) == "--help") { + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--haar" && i + 1 < argc) { + opt_face_cascade_name = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--device" && i + 1 < argc) { + opt_device = (unsigned int)atoi(argv[++i]); + } + else if (std::string(argv[i]) == "--scale" && i + 1 < argc) { + opt_scale = (unsigned int)atoi(argv[++i]); + } + else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) { std::cout << "Usage: " << argv[0] - << " [--haar ] [--device ] [--scale ] [--help]" + << " [--haar ]" + << " [--device ]" + << " [--scale ]" + << " [--help] [-h]" << std::endl; return EXIT_SUCCESS; } @@ -124,6 +130,21 @@ int main(int argc, const char *argv[]) std::cout << e.getMessage() << std::endl; } #else + + +#if !defined(HAVE_OPENCV_HIGHGUI) + std::cout << "This tutorial needs OpenCV highgui module that is missing." << std::endl; +#endif +#if !defined(HAVE_OPENCV_IMGPROC) + std::cout << "This tutorial needs OpenCV imgproc module that is missing." << std::endl; +#endif +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) && !defined(HAVE_OPENCV_OBJDETECT) + std::cout << "This tutorial needs OpenCV objdetect module that is missing." << std::endl; +#endif +#if ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && !defined(HAVE_OPENCV_XOBJDETECT)) + std::cout << "This tutorial needs OpenCV xobjdetect module that is missing." << std::endl; +#endif + (void)argc; (void)argv; #endif diff --git a/tutorial/detection/face/tutorial-face-detector.cpp b/tutorial/detection/face/tutorial-face-detector.cpp index bb02af1130..c48ccf5ebf 100644 --- a/tutorial/detection/face/tutorial-face-detector.cpp +++ b/tutorial/detection/face/tutorial-face-detector.cpp @@ -11,7 +11,8 @@ int main(int argc, const char *argv[]) { //! [Macro defined] -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_OBJDETECT) +#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && \ + (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_OBJDETECT)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XOBJDETECT))) #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; #endif @@ -22,13 +23,17 @@ int main(int argc, const char *argv[]) std::string opt_video = "video.mp4"; //! [Default settings] - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--haar") - opt_face_cascade_name = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--video") - opt_video = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { - std::cout << "Usage: " << argv[0] << " [--haar ] [--video ]" + for (int i = 1; i < argc; i++) { + if (std::string(argv[i]) == "--haar" && i + 1 < argc) { + opt_face_cascade_name = std::string(argv[++i]); + } + else if (std::string(argv[i]) == "--video" && i + 1 < argc) { + opt_video = std::string(argv[++i]); + } + else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) { + std::cout << "Usage: " << argv[0] + << " [--haar ]" + << " [--video ]" << " [--help] [-h]" << std::endl; return EXIT_SUCCESS; } @@ -90,8 +95,22 @@ int main(int argc, const char *argv[]) } catch (const vpException &e) { std::cout << e.getMessage() << std::endl; -} + } #else + +#if !defined(HAVE_OPENCV_HIGHGUI) + std::cout << "This tutorial needs OpenCV highgui module that is missing." << std::endl; +#endif +#if !defined(HAVE_OPENCV_IMGPROC) + std::cout << "This tutorial needs OpenCV imgproc module that is missing." << std::endl; +#endif +#if (VISP_HAVE_OPENCV_VERSION < 0x050000) && !defined(HAVE_OPENCV_OBJDETECT) + std::cout << "This tutorial needs OpenCV objdetect module that is missing." << std::endl; +#endif +#if ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && !defined(HAVE_OPENCV_XOBJDETECT)) + std::cout << "This tutorial needs OpenCV xobjdetect module that is missing." << std::endl; +#endif + (void)argc; (void)argv; #endif diff --git a/tutorial/detection/matching/tutorial-matching-keypoint-SIFT.cpp b/tutorial/detection/matching/tutorial-matching-keypoint-SIFT.cpp index c0ecfae1da..dd0200b8f5 100644 --- a/tutorial/detection/matching/tutorial-matching-keypoint-SIFT.cpp +++ b/tutorial/detection/matching/tutorial-matching-keypoint-SIFT.cpp @@ -10,9 +10,9 @@ int main() { //! [Define] -#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) && \ - (defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ - (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400)) +#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && \ + ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_XFEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES)) + //! [Define] #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; diff --git a/tutorial/detection/matching/tutorial-matching-keypoint-homography.cpp b/tutorial/detection/matching/tutorial-matching-keypoint-homography.cpp index 6d6841f033..1fef7a0ff1 100644 --- a/tutorial/detection/matching/tutorial-matching-keypoint-homography.cpp +++ b/tutorial/detection/matching/tutorial-matching-keypoint-homography.cpp @@ -8,7 +8,7 @@ int main(int argc, const char **argv) { -#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES) || defined(HAVE_OPENCV_XFEATURES2D) || defined(HAVE_OPENCV_NONFREE)) #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; #endif @@ -79,9 +79,8 @@ int main(int argc, const char **argv) std::cout << "Nb matches: " << nbMatch << std::endl; //! [Matching] - std::vector iPref(nbMatch), - iPcur(nbMatch); // Coordinates in pixels (for display only) - //! [Allocation] + std::vector iPref(nbMatch), iPcur(nbMatch); // Coordinates in pixels (for display only) + //! [Allocation] std::vector mPref_x(nbMatch), mPref_y(nbMatch); std::vector mPcur_x(nbMatch), mPcur_y(nbMatch); std::vector inliers(nbMatch); @@ -137,7 +136,7 @@ int main(int argc, const char **argv) if (vpDisplay::getClick(Idisp, false)) break; -} + } vpDisplay::getClick(Idisp); #else diff --git a/tutorial/detection/matching/tutorial-matching-keypoint.cpp b/tutorial/detection/matching/tutorial-matching-keypoint.cpp index 35ba74a970..db6fc010b3 100644 --- a/tutorial/detection/matching/tutorial-matching-keypoint.cpp +++ b/tutorial/detection/matching/tutorial-matching-keypoint.cpp @@ -10,7 +10,7 @@ int main() { //! [Define] -#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_FEATURES) || defined(HAVE_OPENCV_XFEATURES2D) || defined(HAVE_OPENCV_NONFREE)) //! [Define] #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; diff --git a/tutorial/detection/object/cube.cao b/tutorial/detection/object/cube.cao index 4408839f0f..eaf4f98964 100644 --- a/tutorial/detection/object/cube.cao +++ b/tutorial/detection/object/cube.cao @@ -1,19 +1,27 @@ -V1 +V1 +# 3D Points 8 - 0.000 0.000 0.000 --0.084 0.000 0.000 --0.084 0.084 0.000 - 0.000 0.084 0.000 - 0.000 0.000 0.084 + 0.000 0.000 0.000 +-0.084 0.000 0.000 +-0.084 0.084 0.000 + 0.000 0.084 0.000 + 0.000 0.000 0.084 -0.084 0.000 0.084 --0.084 0.084 0.084 - 0.000 0.084 0.084 -0 -0 -6 +-0.084 0.084 0.084 + 0.000 0.084 0.084 +# 3D Lines +0 # Number of lines +# Faces from 3D lines +0 # Number of faces +# Faces from 3D points +6 # Number of faces 4 0 4 5 1 4 1 5 6 2 4 6 7 3 2 4 3 7 4 0 4 0 1 2 3 -4 7 6 5 4 +4 7 6 5 4 +# 3D cylinders +0 # Number of cylinders +# 3D circles +0 # Number of circles diff --git a/tutorial/detection/object/tutorial-detection-object-mbt-deprecated.cpp b/tutorial/detection/object/tutorial-detection-object-mbt-deprecated.cpp index 08c453db35..5651702bd6 100644 --- a/tutorial/detection/object/tutorial-detection-object-mbt-deprecated.cpp +++ b/tutorial/detection/object/tutorial-detection-object-mbt-deprecated.cpp @@ -10,7 +10,9 @@ int main(int argc, char **argv) { -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#if defined(HAVE_OPENCV_IMGPROC) && \ + (((VISP_HAVE_OPENCV_VERSION < 0x050000) && (defined(HAVE_OPENCV_FEATURES2D) || defined(HAVE_OPENCV_XFEATURES2D))) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))) + #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; #endif @@ -18,11 +20,14 @@ int main(int argc, char **argv) try { std::string videoname = "teabox.mp4"; - for (int i = 0; i < argc; i++) { - if (std::string(argv[i]) == "--name") - videoname = std::string(argv[i + 1]); - else if (std::string(argv[i]) == "--help") { - std::cout << "\nUsage: " << argv[0] << " [--name