diff --git a/.github/workflows/ubuntu-dep-apt.yml b/.github/workflows/ubuntu-dep-apt.yml index 48f47dfcf2..bb77160c2c 100644 --- a/.github/workflows/ubuntu-dep-apt.yml +++ b/.github/workflows/ubuntu-dep-apt.yml @@ -15,7 +15,7 @@ jobs: matrix: os: [ubuntu-20.04, ubuntu-22.04] compiler: [ {CC: /usr/bin/gcc-9, CXX: /usr/bin/g++-9}, {CC: /usr/bin/gcc-10, CXX: /usr/bin/g++-10}, {CC: /usr/bin/clang, CXX: /usr/bin/clang++} ] - standard: [ 98, 11, 14, 17 ] + standard: [ 11, 14, 17 ] steps: # https://github.com/marketplace/actions/cancel-workflow-action @@ -36,7 +36,7 @@ jobs: - name: Print compiler information run: dpkg --list | grep compiler - - name: Install dependencies for ubuntu 18.04 and 20.04 + - name: Install dependencies for ubuntu 20.04 if: matrix.os != 'ubuntu-22.04' run: sudo apt-get update && sudo apt-get install -y libx11-dev libdc1394-22-dev libv4l-dev liblapack-dev libopenblas-dev libeigen3-dev libopencv-dev nlohmann-json3-dev diff --git a/.github/workflows/ubuntu-dep-src.yml b/.github/workflows/ubuntu-dep-src.yml index dff5233a84..c481c39a38 100644 --- a/.github/workflows/ubuntu-dep-src.yml +++ b/.github/workflows/ubuntu-dep-src.yml @@ -31,7 +31,7 @@ jobs: - name: Print OS information run: lsb_release -a - - name: Install dependencies for ubuntu 18.04 and 20.04 + - name: Install dependencies for ubuntu 20.04 if: matrix.os != 'ubuntu-22.04' run: | sudo apt-get update && sudo apt-get install -y libdc1394-22-dev diff --git a/.github/workflows/ubuntu-ustk.yml b/.github/workflows/ubuntu-ustk.yml index 23eea4f098..fab02f8d6b 100644 --- a/.github/workflows/ubuntu-ustk.yml +++ b/.github/workflows/ubuntu-ustk.yml @@ -34,7 +34,7 @@ jobs: - name: Print compiler information run: dpkg --list | grep compiler - - name: Install dependencies for ubuntu 18.04 and 20.04 + - name: Install dependencies for ubuntu 20.04 if: matrix.os != 'ubuntu-22.04' run: sudo apt-get update && sudo apt-get install -y libx11-dev libdc1394-22-dev libv4l-dev liblapack-dev libopenblas-dev libeigen3-dev libopencv-dev nlohmann-json3-dev diff --git a/CMakeLists.txt b/CMakeLists.txt index d8110b8b79..b15c567720 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -551,8 +551,8 @@ VP_OPTION(USE_SOXT SOXT "" "Include Coin/SoXt support" "" OF set(THREADS_PREFER_PTHREAD_FLAG ON) VP_OPTION(USE_THREADS Threads "" "Include std::thread support" "" ON IF NOT (WIN32 OR MINGW)) -# We need threads with c++11 -if((VISP_CXX_STANDARD GREATER VISP_CXX_STANDARD_98) AND NOT USE_THREADS) +# We need threads. To be changed to make threads optional +if(NOT USE_THREADS) if(Threads_FOUND) message(WARNING "We need std::thread. We turn USE_THREADS=ON.") unset(USE_THREADS) @@ -589,38 +589,7 @@ VP_OPTION(USE_NLOHMANN_JSON nlohmann_json QUIET "Include nlohmann json support" # ---------------------------------------------------------------------------- # Handle cxx standard depending on specific 3rd parties. Should be before module parsing and VISP3rdParty.cmake include # ---------------------------------------------------------------------------- -# if c++ standard is not at leat c++11, force 3rd parties that require at least c++11 to OFF -if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_11) - if(USE_REALSENSE) - message(WARNING "librealsense 3rd party was detected and needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable librealsense usage turning USE_REALSENSE=OFF.") - unset(USE_REALSENSE) - set(USE_REALSENSE OFF CACHE BOOL "Include RealSense SDK support" FORCE) - endif() - if(USE_REALSENSE2) - message(WARNING "librealsense2 3rd party was detected and needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable librealsense2 usage turning USE_REALSENSE2=OFF.") - unset(USE_REALSENSE2) - set(USE_REALSENSE2 OFF CACHE BOOL "Include RealSense2 SDK support" FORCE) - endif() - if(USE_FRANKA) - message(WARNING "libfranka 3rd party was detected and needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable libfranka usage turning USE_FRANKA=OFF.") - unset(USE_FRANKA) - set(USE_FRANKA OFF CACHE BOOL "Include libfranka SDK support for Franka Emika robots" FORCE) - endif() - if(USE_UR_RTDE) - message(WARNING "ur_rtde 3rd party was detected and needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable ur_rtde usage turning USE_UR_RTDE=OFF.") - unset(USE_UR_RTDE) - set(USE_UR_RTDE OFF CACHE BOOL "Include ur_rtde SDK support for Universal Robots robots" FORCE) - endif() - if((OpenCV_VERSION VERSION_GREATER 4.0.0) OR (OpenCV_VERSION VERSION_EQUAL 4.0.0)) - # if c++ standard is not at least 11: disable opencv 4.x usage - message(WARNING "OpenCV ${OpenCV_VERSION} 3rd party was detected and needs c++11 or higher compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable OpenCV usage turning USE_OPENCV=OFF") - unset(USE_OPENCV) - set(USE_OPENCV OFF CACHE BOOL "Include OpenCV support" FORCE) - endif() - # Downgrade to cxx98 to completely disable cxx11 - unset(CMAKE_CXX_STANDARD) -endif() - +# if c++ standard is not at leat c++17, force 3rd parties that require at least c++17 to OFF if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_17) if(USE_MAVSDK) message(WARNING "mavsdk 3rd party was detected and needs at least c++17 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable MAVSDK usage turning USE_MAVSDK=OFF.") @@ -665,9 +634,9 @@ VP_OPTION(WITH_APRILTAG_BIG_FAMILY "" "" "Build AprilTag big family (41h12, VP_OPTION(WITH_ATIDAQ "" "" "Build atidaq-c as built-in library" "" ON IF USE_COMEDI AND NOT WINRT) VP_OPTION(WITH_CLIPPER "" "" "Build clipper as built-in library" "" ON IF USE_OPENCV) VP_OPTION(WITH_LAPACK "" "" "Build lapack as built-in library" "" ON IF NOT USE_LAPACK) -VP_OPTION(WITH_QBDEVICE "" "" "Build qbdevice-api as built-in library" "" ON IF (VISP_CXX_STANDARD GREATER VISP_CXX_STANDARD_98) AND (NOT WINRT) AND (NOT IOS)) -VP_OPTION(WITH_TAKKTILE2 "" "" "Build Right Hand takktile2 driver as built-in library" "" ON IF (VISP_CXX_STANDARD GREATER VISP_CXX_STANDARD_98) AND (NOT WIN32) AND (NOT WINRT) AND (NOT IOS) AND (NOT ANDROID)) -VP_OPTION(WITH_CATCH2 "" "" "Use catch2" "" ON IF (VISP_CXX_STANDARD GREATER VISP_CXX_STANDARD_98)) +VP_OPTION(WITH_QBDEVICE "" "" "Build qbdevice-api as built-in library" "" ON IF (NOT WINRT) AND (NOT IOS)) +VP_OPTION(WITH_TAKKTILE2 "" "" "Build Right Hand takktile2 driver as built-in library" "" ON IF (NOT WIN32) AND (NOT WINRT) AND (NOT IOS) AND (NOT ANDROID)) +VP_OPTION(WITH_CATCH2 "" "" "Use catch2 for testing" "" ON) # ---------------------------------------------------------------------------- # Check for specific functions. Should be after cxx standard detection in VISPDetectCXXStandard.cmake and potential modification depending on pcl, realsense2, libfranka diff --git a/ChangeLog.txt b/ChangeLog.txt index d19f2e9c7c..55ca45d97c 100644 --- a/ChangeLog.txt +++ b/ChangeLog.txt @@ -12,9 +12,11 @@ ViSP 3.x.x (Version in development) . - Deprecated removed . vpPlanarObjectDetector, vpFernClassifier classes are removed + . End of supporting c++98 standard. As a consequence, ViSP is no more compatible with Ubuntu 12.04 - New features and improvements . Introduce applications in apps folder, a collection of useful tools that have a dependency to the install target + . Bump minimal c++ standard to c++11 - Applications . Migrate eye-to-hand tutorials in apps - Tutorials diff --git a/apps/calibration/visp-acquire-franka-calib-data.cpp b/apps/calibration/visp-acquire-franka-calib-data.cpp index f1bfcdfaca..3498622c4b 100644 --- a/apps/calibration/visp-acquire-franka-calib-data.cpp +++ b/apps/calibration/visp-acquire-franka-calib-data.cpp @@ -42,7 +42,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA) && \ defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_MODULE_ROBOT) && defined(VISP_HAVE_MODULE_SENSOR) // optional @@ -169,9 +169,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense-2.x." << std::endl; #endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif #if !defined(VISP_HAVE_FRANKA) std::cout << "Install libfranka." << std::endl; #endif diff --git a/apps/calibration/visp-acquire-universal-robots-calib-data.cpp b/apps/calibration/visp-acquire-universal-robots-calib-data.cpp index 6bb11a27e3..7ecadd446d 100644 --- a/apps/calibration/visp-acquire-universal-robots-calib-data.cpp +++ b/apps/calibration/visp-acquire-universal-robots-calib-data.cpp @@ -42,7 +42,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE) && \ defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_MODULE_ROBOT) && defined(VISP_HAVE_MODULE_SENSOR) // optional @@ -171,9 +171,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense-2.x." << std::endl; #endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif #if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." << std::endl; diff --git a/apps/calibration/visp-compute-hand-eye-calibration.cpp b/apps/calibration/visp-compute-hand-eye-calibration.cpp index e72024e146..1ed28ed68c 100644 --- a/apps/calibration/visp-compute-hand-eye-calibration.cpp +++ b/apps/calibration/visp-compute-hand-eye-calibration.cpp @@ -187,11 +187,9 @@ int main(int argc, const char *argv[]) // save eMc std::string name_we = vpIoTools::createFilePath(vpIoTools::getParent(opt_eMc_file), vpIoTools::getNameWE(opt_eMc_file)) + ".txt"; std::cout << std::endl << "Save transformation matrix eMc as an homogeneous matrix in: " << name_we << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + std::ofstream file_eMc(name_we); -#else - std::ofstream file_eMc(name_we.c_str()); -#endif + eMc.save(file_eMc); vpPoseVector pose_vec(eMc); diff --git a/cmake/VISPDetectCXXStandard.cmake b/cmake/VISPDetectCXXStandard.cmake index 53c1d0f1e1..ab040d821c 100644 --- a/cmake/VISPDetectCXXStandard.cmake +++ b/cmake/VISPDetectCXXStandard.cmake @@ -1,22 +1,19 @@ -set(VISP_CXX_STANDARD_98 199711L) +set(VISP_CXX_STANDARD_98 199711L) # Keep for compat with previous releases set(VISP_CXX_STANDARD_11 201103L) set(VISP_CXX_STANDARD_14 201402L) set(VISP_CXX_STANDARD_17 201703L) if(DEFINED USE_CXX_STANDARD) - if(USE_CXX_STANDARD STREQUAL "98") - set(CMAKE_CXX_STANDARD 98) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_98}) - elseif(USE_CXX_STANDARD STREQUAL "11") - set(CMAKE_CXX_STANDARD 11) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_11}) + if(USE_CXX_STANDARD STREQUAL "11") + set(CMAKE_CXX_STANDARD 11) + set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_11}) elseif(USE_CXX_STANDARD STREQUAL "14") - set(CMAKE_CXX_STANDARD 14) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_14}) + set(CMAKE_CXX_STANDARD 14) + set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_14}) elseif(USE_CXX_STANDARD STREQUAL "17") - set(CMAKE_CXX_STANDARD 17) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_17}) + set(CMAKE_CXX_STANDARD 17) + set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_17}) endif() set(CMAKE_CXX_EXTENSIONS OFF) # use -std=c++11 instead of -std=gnu++11 @@ -24,15 +21,10 @@ if(DEFINED USE_CXX_STANDARD) else() set(AVAILABLE_CXX_STANDARD TRUE) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_98}) + set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_11}) set(CMAKE_CXX_STANDARD_REQUIRED FALSE) - if(CMAKE_CXX98_COMPILE_FEATURES) - set(CXX98_STANDARD_FOUND ON CACHE STRING "cxx98 standard") - mark_as_advanced(CXX98_STANDARD_FOUND) - endif() - if(CMAKE_CXX11_COMPILE_FEATURES) # cxx11 implementation maybe incomplete especially with g++ 4.6.x. # That's why we check more in depth for cxx_override that is not available with g++ 4.6.3 @@ -60,8 +52,6 @@ else() set(USE_CXX_STANDARD "14" CACHE STRING "Selected cxx standard") elseif(CXX11_STANDARD_FOUND) set(USE_CXX_STANDARD "11" CACHE STRING "Selected cxx standard") - elseif(CXX98_STANDARD_FOUND) - set(USE_CXX_STANDARD "98" CACHE STRING "Selected cxx standard") else() set(AVAILABLE_CXX_STANDARD FALSE) endif() @@ -72,9 +62,6 @@ else() endif() if(AVAILABLE_CXX_STANDARD) - if(CXX98_STANDARD_FOUND) - set_property(CACHE USE_CXX_STANDARD APPEND_STRING PROPERTY STRINGS "98") - endif() if(CXX11_STANDARD_FOUND) set_property(CACHE USE_CXX_STANDARD APPEND_STRING PROPERTY STRINGS ";11") endif() @@ -85,10 +72,7 @@ else() set_property(CACHE USE_CXX_STANDARD APPEND_STRING PROPERTY STRINGS ";17") endif() - if(USE_CXX_STANDARD STREQUAL "98") - set(CMAKE_CXX_STANDARD 98) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_98}) - elseif(USE_CXX_STANDARD STREQUAL "11") + if(USE_CXX_STANDARD STREQUAL "11") set(CMAKE_CXX_STANDARD 11) set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_11}) elseif(USE_CXX_STANDARD STREQUAL "14") diff --git a/cmake/templates/VISPConfig.cmake.in b/cmake/templates/VISPConfig.cmake.in index 0ed3aaaf2e..fd4b9b6bdb 100644 --- a/cmake/templates/VISPConfig.cmake.in +++ b/cmake/templates/VISPConfig.cmake.in @@ -201,9 +201,6 @@ set(VISP_HAVE_CMU1394 "@VISP_HAVE_CMU1394@") set(VISP_HAVE_COIN3D "@VISP_HAVE_COIN3D@") set(VISP_HAVE_COIN3D_AND_GUI "@VISP_HAVE_COIN3D_AND_GUI@") set(VISP_HAVE_COMEDI "@VISP_HAVE_COMEDI@") -set(VISP_HAVE_CPP11_COMPATIBILITY "@VISP_HAVE_CXX11@") # to keep compat with previous releases -set(VISP_HAVE_CXX11 "@VISP_HAVE_CXX11@") -set(VISP_CXX_STANDARD_98 "@VISP_CXX_STANDARD_98@") set(VISP_CXX_STANDARD_11 "@VISP_CXX_STANDARD_11@") set(VISP_CXX_STANDARD_14 "@VISP_CXX_STANDARD_14@") set(VISP_CXX_STANDARD_17 "@VISP_CXX_STANDARD_17@") diff --git a/cmake/templates/vpConfig.h.in b/cmake/templates/vpConfig.h.in index 26c9ef50d4..ebdd634d43 100644 --- a/cmake/templates/vpConfig.h.in +++ b/cmake/templates/vpConfig.h.in @@ -485,19 +485,13 @@ #cmakedefine VISP_HAVE_NLOHMANN_JSON // Define c++ standard values also available in __cplusplus when gcc is used -#define VISP_CXX_STANDARD_98 ${VISP_CXX_STANDARD_98} +#define VISP_CXX_STANDARD_98 ${VISP_CXX_STANDARD_98} # Keep for compat with previous releases #define VISP_CXX_STANDARD_11 ${VISP_CXX_STANDARD_11} #define VISP_CXX_STANDARD_14 ${VISP_CXX_STANDARD_14} #define VISP_CXX_STANDARD_17 ${VISP_CXX_STANDARD_17} #define VISP_CXX_STANDARD ${VISP_CXX_STANDARD} -// Defined to keep compat with previous releases when c++ 11 available -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) -# define VISP_HAVE_CXX11 -# define VISP_HAVE_CPP11_COMPATIBILITY -#endif - // Defined if isnan macro is available #cmakedefine VISP_HAVE_FUNC_ISNAN diff --git a/doc/config-doxygen.in b/doc/config-doxygen.in index 144e0aac01..fc2f3cc9fa 100644 --- a/doc/config-doxygen.in +++ b/doc/config-doxygen.in @@ -2153,9 +2153,6 @@ PREDEFINED = @DOXYGEN_SHOULD_SKIP_THIS@ \ VISP_HAVE_COIN3D \ VISP_HAVE_COIN3D_AND_GUI \ VISP_HAVE_COMEDI \ - VISP_HAVE_CPP11_COMPATIBILITY \ - VISP_HAVE_CXX11 \ - VISP_CXX_STANDARD_98=@VISP_CXX_STANDARD_98@ \ VISP_CXX_STANDARD_11=@VISP_CXX_STANDARD_11@ \ VISP_CXX_STANDARD_14=@VISP_CXX_STANDARD_14@ \ VISP_CXX_STANDARD_17=@VISP_CXX_STANDARD_17@ \ diff --git a/doc/tutorial/detection/tutorial-detection-object-deprecated.dox b/doc/tutorial/detection/tutorial-detection-object-deprecated.dox index 46e7a39bec..4611967283 100644 --- a/doc/tutorial/detection/tutorial-detection-object-deprecated.dox +++ b/doc/tutorial/detection/tutorial-detection-object-deprecated.dox @@ -77,7 +77,7 @@ Otherwise, the configuration must be made in the code. \snippet tutorial-detection-object-mbt-deprecated.cpp Keypoint code config -We then detect keypoints in the reference image with the object we want to learn : +We then detect keypoints in the reference image with the object we want to learn : \snippet tutorial-detection-object-mbt-deprecated.cpp Keypoints reference detection @@ -173,7 +173,7 @@ And finally, we build the reference keypoints and we set the flag append to true \subsection dep_detection_object_display_multiple_images How to display the matching when the learning is done on multiple images -In this section we will explain how to display the matching between keypoints detected in the current image and their correspondances in the reference images that are used during the learning stage, as given in the next video: +In this section we will explain how to display the matching between keypoints detected in the current image and their correspondences in the reference images that are used during the learning stage, as given in the next video: \htmlonly diff --git a/doc/tutorial/detection/tutorial-detection-object.dox b/doc/tutorial/detection/tutorial-detection-object.dox index c48b094d39..74bd74e6fd 100644 --- a/doc/tutorial/detection/tutorial-detection-object.dox +++ b/doc/tutorial/detection/tutorial-detection-object.dox @@ -75,7 +75,7 @@ Otherwise, the configuration must be made in the code. \snippet tutorial-detection-object-mbt.cpp Keypoint code config -We then detect keypoints in the reference image with the object we want to learn : +We then detect keypoints in the reference image with the object we want to learn : \snippet tutorial-detection-object-mbt.cpp Keypoints reference detection @@ -171,7 +171,7 @@ And finally, we build the reference keypoints and we set the flag append to true \subsection detection_object_display_multiple_images How to display the matching when the learning is done on multiple images -In this section we will explain how to display the matching between keypoints detected in the current image and their correspondances in the reference images that are used during the learning stage, as given in the next video: +In this section we will explain how to display the matching between keypoints detected in the current image and their correspondences in the reference images that are used during the learning stage, as given in the next video: \htmlonly diff --git a/example/device/framegrabber/getRealSense2Info.cpp b/example/device/framegrabber/getRealSense2Info.cpp index f56b0cc209..3346e2ef2e 100644 --- a/example/device/framegrabber/getRealSense2Info.cpp +++ b/example/device/framegrabber/getRealSense2Info.cpp @@ -42,7 +42,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE2) int main() { @@ -57,11 +57,13 @@ int main() if (rs.getDepthScale() != 0) // If it has depth sensor std::cout << "Depth scale: " << std::setprecision(std::numeric_limits::max_digits10) << rs.getDepthScale() - << std::endl; + << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -75,11 +77,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #endif return EXIT_SUCCESS; } diff --git a/example/device/framegrabber/grabRealSense.cpp b/example/device/framegrabber/grabRealSense.cpp index 0aff9af270..517d2b3379 100644 --- a/example/device/framegrabber/grabRealSense.cpp +++ b/example/device/framegrabber/grabRealSense.cpp @@ -48,7 +48,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE) // Using a thread to display the pointcloud with PCL produces a segfault on // OSX @@ -113,7 +113,7 @@ vpThread::Return displayPointcloudFunction(vpThread::Args args) int main() { -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE) try { vpRealSense rs; rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30)); @@ -254,11 +254,6 @@ int main() #elif !defined(VISP_HAVE_REALSENSE) std::cout << "This deprecated example is only working with librealsense 1.x" << std::endl; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; - << std::endl; #endif return EXIT_SUCCESS; } diff --git a/example/device/framegrabber/grabRealSense2.cpp b/example/device/framegrabber/grabRealSense2.cpp index b6f16da5a9..18f5bcd345 100644 --- a/example/device/framegrabber/grabRealSense2.cpp +++ b/example/device/framegrabber/grabRealSense2.cpp @@ -44,8 +44,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #ifdef VISP_HAVE_PCL #include @@ -64,7 +63,7 @@ bool cancelled = false, update_pointcloud = false; class ViewerWorker { public: - explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {} + explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { } void run() { @@ -94,7 +93,8 @@ class ViewerWorker if (local_update) { if (m_colorMode) { local_pointcloud_color = pointcloud_color->makeShared(); - } else { + } + else { local_pointcloud = pointcloud->makeShared(); } } @@ -109,15 +109,18 @@ class ViewerWorker viewer->addPointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "RGB sample cloud"); - } else { + } + else { viewer->addPointCloud(local_pointcloud, "sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); } init = false; - } else { + } + else { if (m_colorMode) { viewer->updatePointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - } else { + } + else { viewer->updatePointCloud(local_pointcloud, "sample cloud"); } } @@ -160,9 +163,9 @@ int main() rs.open(config); std::cout << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithoutDistortion) - << std::endl; + << std::endl; std::cout << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) - << std::endl; + << std::endl; std::cout << "Extrinsics cMd: \n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl; std::cout << "Extrinsics dMc: \n" << rs.getTransformation(RS2_STREAM_DEPTH, RS2_STREAM_COLOR) << std::endl; std::cout << "Extrinsics cMi: \n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_INFRARED) << std::endl; @@ -235,9 +238,11 @@ int main() viewer_thread.join(); #endif - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -251,11 +256,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #endif return EXIT_SUCCESS; } diff --git a/example/device/framegrabber/grabRealSense2_T265.cpp b/example/device/framegrabber/grabRealSense2_T265.cpp index 4f8a22ec3b..959fe60067 100644 --- a/example/device/framegrabber/grabRealSense2_T265.cpp +++ b/example/device/framegrabber/grabRealSense2_T265.cpp @@ -50,7 +50,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() @@ -62,7 +62,7 @@ int main() double ts; vpImagePoint frame_origin; std::list > - frame_origins; // Frame origin's history for trajectory visualization + frame_origins; // Frame origin's history for trajectory visualization unsigned int display_scale = 2; try { @@ -160,15 +160,17 @@ int main() std::cout << "Loop time: " << std::setw(8) << vpTime::measureTimeMs() - t << "ms. Confidence = " << confidence; std::cout << " Gyro vel: x = " << std::setw(10) << std::setprecision(3) << imu_vel[0] << " y = " << std::setw(10) - << std::setprecision(3) << imu_vel[1] << " z = " << std::setw(8) << imu_vel[2]; + << std::setprecision(3) << imu_vel[1] << " z = " << std::setw(8) << imu_vel[2]; std::cout << " Accel: x = " << std::setw(10) << std::setprecision(3) << imu_acc[0] << " y = " << std::setw(10) - << std::setprecision(3) << imu_acc[1] << " z = " << std::setw(8) << imu_acc[2]; + << std::setprecision(3) << imu_acc[1] << " z = " << std::setw(8) << imu_acc[2]; std::cout << std::endl; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -182,10 +184,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #elif !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) std::cout << "You don't have X11 or GDI display capabilities" << std::endl; #elif !(RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) diff --git a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp index 898de9e557..ea1a2dc508 100644 --- a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp +++ b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp @@ -45,8 +45,7 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_V4L2) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) +#if defined(VISP_HAVE_V4L2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) #include #include diff --git a/example/device/framegrabber/readRealSenseData.cpp b/example/device/framegrabber/readRealSenseData.cpp index f63a4989a4..43b160a9da 100644 --- a/example/device/framegrabber/readRealSenseData.cpp +++ b/example/device/framegrabber/readRealSenseData.cpp @@ -40,7 +40,7 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include #include @@ -51,9 +51,7 @@ #include #include #include -#endif -#if defined(VISP_HAVE_PCL) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #define USE_PCL_VIEWER #endif diff --git a/example/device/framegrabber/saveRealSenseData.cpp b/example/device/framegrabber/saveRealSenseData.cpp index 4b8155b29f..7548872130 100644 --- a/example/device/framegrabber/saveRealSenseData.cpp +++ b/example/device/framegrabber/saveRealSenseData.cpp @@ -39,7 +39,7 @@ #include #include -#if (defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2)) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if (defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2)) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include diff --git a/example/math/quadprog.cpp b/example/math/quadprog.cpp index 19609c80df..116b570804 100644 --- a/example/math/quadprog.cpp +++ b/example/math/quadprog.cpp @@ -47,7 +47,7 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_LAPACK) +#if defined(VISP_HAVE_LAPACK) #include #include @@ -177,14 +177,6 @@ int main(int argc, char **argv) #endif return EXIT_SUCCESS; } -#elif !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) -int main() -{ - std::cout << "You did not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; - return EXIT_SUCCESS; -} #else int main() { diff --git a/example/math/quadprog_eq.cpp b/example/math/quadprog_eq.cpp index cd4ba09fa2..49c20b23de 100644 --- a/example/math/quadprog_eq.cpp +++ b/example/math/quadprog_eq.cpp @@ -47,7 +47,7 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_LAPACK) +#if defined(VISP_HAVE_LAPACK) #include "qp_plot.h" #include @@ -204,14 +204,6 @@ int main(int argc, char **argv) } #endif } -#elif !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) -int main() -{ - std::cout << "You did not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; - return EXIT_SUCCESS; -} #else int main() { diff --git a/example/servo-afma6/servoAfma6AprilTagIBVS.cpp b/example/servo-afma6/servoAfma6AprilTagIBVS.cpp index c600d48cd2..f20cfed7b3 100644 --- a/example/servo-afma6/servoAfma6AprilTagIBVS.cpp +++ b/example/servo-afma6/servoAfma6AprilTagIBVS.cpp @@ -66,8 +66,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6) void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) @@ -78,7 +77,8 @@ void display_point_trajectory(const vpImage &I, const std::vector if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) { traj_vip[i].push_back(vip[i]); } - } else { + } + else { traj_vip[i].push_back(vip[i]); } } @@ -103,24 +103,31 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { opt_tagSize = std::stod(argv[i + 1]); - } else if (std::string(argv[i]) == "--verbose") { + } + else if (std::string(argv[i]) == "--verbose") { opt_verbose = true; - } else if (std::string(argv[i]) == "--plot") { + } + else if (std::string(argv[i]) == "--plot") { opt_plot = true; - } else if (std::string(argv[i]) == "--adaptive_gain") { + } + else if (std::string(argv[i]) == "--adaptive_gain") { opt_adaptive_gain = true; - } else if (std::string(argv[i]) == "--task_sequencing") { + } + 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") { + } + else if (std::string(argv[i]) == "--no-convergence-threshold") { convergence_threshold = 0.; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout - << argv[0] << " --tag_size ] " - << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" - << "\n"; + << argv[0] << " --tag_size ] " + << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" + << "\n"; return EXIT_SUCCESS; } } @@ -129,8 +136,8 @@ int main(int argc, char **argv) try { std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -158,7 +165,7 @@ int main(int argc, char **argv) // Get camera intrinsics vpCameraParameters cam = - rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); + rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); std::cout << "cam:\n" << cam << "\n"; vpImage I(height, width); @@ -182,7 +189,7 @@ int main(int argc, char **argv) // Desired pose used to compute the desired features vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis - vpRotationMatrix({1, 0, 0, 0, -1, 0, 0, 0, -1})); + vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 })); // Create visual features std::vector p(4), pd(4); // We use 4 points @@ -205,7 +212,8 @@ int main(int argc, char **argv) if (opt_adaptive_gain) { vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30 task.setLambda(lambda); - } else { + } + else { task.setLambda(0.5); } @@ -277,7 +285,8 @@ int main(int argc, char **argv) } if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) { oMo = v_oMo[0]; - } else { + } + else { std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl; oMo = v_oMo[1]; // Introduce PI rotation } @@ -316,7 +325,8 @@ int main(int argc, char **argv) t_init_servo = vpTime::measureTimeMs(); } v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.); - } else { + } + else { v_c = task.computeControlLaw(); } @@ -359,7 +369,7 @@ int main(int argc, char **argv) if (error < convergence_threshold) { has_converged = true; std::cout << "Servo task has converged" - << "\n"; + << "\n"; vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red); } if (first_time) { @@ -427,12 +437,14 @@ int main(int argc, char **argv) if (traj_corners) { delete[] traj_corners; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -445,9 +457,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense-2.x" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif #if !defined(VISP_HAVE_AFMA6) std::cout << "ViSP is not build with Afma6 robot support..." << std::endl; #endif diff --git a/example/servo-afma6/servoAfma6AprilTagPBVS.cpp b/example/servo-afma6/servoAfma6AprilTagPBVS.cpp index 992798bc1d..cb847dcb01 100644 --- a/example/servo-afma6/servoAfma6AprilTagPBVS.cpp +++ b/example/servo-afma6/servoAfma6AprilTagPBVS.cpp @@ -63,8 +63,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6) void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) @@ -75,7 +74,8 @@ void display_point_trajectory(const vpImage &I, const std::vector if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) { traj_vip[i].push_back(vip[i]); } - } else { + } + else { traj_vip[i].push_back(vip[i]); } } @@ -101,25 +101,32 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { opt_tagSize = std::stod(argv[i + 1]); - } else if (std::string(argv[i]) == "--verbose") { + } + else if (std::string(argv[i]) == "--verbose") { opt_verbose = true; - } else if (std::string(argv[i]) == "--plot") { + } + else if (std::string(argv[i]) == "--plot") { opt_plot = true; - } else if (std::string(argv[i]) == "--adaptive_gain") { + } + else if (std::string(argv[i]) == "--adaptive_gain") { opt_adaptive_gain = true; - } else if (std::string(argv[i]) == "--task_sequencing") { + } + 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") { + } + else if (std::string(argv[i]) == "--no-convergence-threshold") { convergence_threshold_t = 0.; convergence_threshold_tu = 0.; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout - << argv[0] << " [--tag_size ] " - << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" - << "\n"; + << argv[0] << " [--tag_size ] " + << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" + << "\n"; return EXIT_SUCCESS; } } @@ -128,8 +135,8 @@ int main(int argc, char **argv) try { std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -156,7 +163,7 @@ int main(int argc, char **argv) // Get camera intrinsics vpCameraParameters cam = - rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); + rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); std::cout << "cam:\n" << cam << "\n"; vpImage I(height, width); @@ -180,7 +187,7 @@ int main(int argc, char **argv) // Desired pose to reach vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis - vpRotationMatrix({1, 0, 0, 0, -1, 0, 0, 0, -1})); + vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 })); cdMc = cdMo * cMo.inverse(); vpFeatureTranslation t(vpFeatureTranslation::cdMc); @@ -200,7 +207,8 @@ int main(int argc, char **argv) if (opt_adaptive_gain) { vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30 task.setLambda(lambda); - } else { + } + else { task.setLambda(0.5); } @@ -268,7 +276,8 @@ int main(int argc, char **argv) } if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) { oMo = v_oMo[0]; - } else { + } + else { std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl; oMo = v_oMo[1]; // Introduce PI rotation } @@ -287,7 +296,8 @@ int main(int argc, char **argv) t_init_servo = vpTime::measureTimeMs(); } v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.); - } else { + } + else { v_c = task.computeControlLaw(); } @@ -400,12 +410,14 @@ int main(int argc, char **argv) if (traj_vip) { delete[] traj_vip; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -418,9 +430,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense-2.x" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif #if !defined(VISP_HAVE_AFMA6) std::cout << "ViSP is not build with Afma-6 robot support..." << std::endl; #endif diff --git a/example/servo-bebop2/servoBebop2.cpp b/example/servo-bebop2/servoBebop2.cpp index f95f8d053e..98bd516911 100644 --- a/example/servo-bebop2/servoBebop2.cpp +++ b/example/servo-bebop2/servoBebop2.cpp @@ -73,13 +73,7 @@ int main() std::cout << "\nThis example requires ffmpeg library. You should install it.\n" << std::endl; return EXIT_SUCCESS; } -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) -int main() -{ - std::cout << "\nThis example requires cxx11 standard or higher. Turn it on using cmake -DUSE_CXX_STANDARD=11.\n" - << std::endl; - return EXIT_SUCCESS; -} + #else bool compareImagePoint(std::pair p1, std::pair p2) @@ -125,7 +119,8 @@ int main(int argc, char **argv) if (std::string(argv[i]) == "--ip" && i + 1 < argc) { ip_address = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--distance_to_tag" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--distance_to_tag" && i + 1 < argc) { opt_distance_to_tag = std::atof(argv[i + 1]); if (opt_distance_to_tag <= 0) { std::cout << "Error : invalid distance to tag." << std::endl << "See " << argv[0] << " --help" << std::endl; @@ -133,65 +128,71 @@ int main(int argc, char **argv) } opt_has_distance_to_tag = true; i++; - } else if (std::string(argv[i]) == "--intrinsic") { + } + else if (std::string(argv[i]) == "--intrinsic") { opt_cam_parameters = std::string(argv[i + 1]); opt_has_cam_parameters = true; i++; - } else if (std::string(argv[i]) == "--hd_stream") { + } + else if (std::string(argv[i]) == "--hd_stream") { stream_res = 1; - } else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { + } + else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { verbose = true; - } else { + } + else { std::cout << "Error : unknown parameter " << argv[i] << std::endl - << "See " << argv[0] << " --help" << std::endl; + << "See " << argv[0] << " --help" << std::endl; return EXIT_FAILURE; } } - } else if (argc >= 2 && (std::string(argv[1]) == "--help" || std::string(argv[1]) == "-h")) { + } + 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 ] " - << "[--hd_stream] [--verbose] [-v] [--help] [-h]\n" - << std::endl - << "Description:\n" - << " --tag_size \n" - << " The size of the tag to detect in meters, required.\n\n" - << " --ip \n" - << " Ip address of the drone to which you want to connect (default : 192.168.42.1).\n\n" - << " --distance_to_tag \n" - << " The desired distance to the tag in meters (default: 1 meter).\n\n" - << " --intrinsic \n" - << " XML file containing computed intrinsic camera parameters (default: empty).\n\n" - << " --hd_stream\n" - << " Enables HD 720p streaming instead of default 480p.\n" - << " Allows to increase range and accuracy of the tag detection,\n" - << " but increases latency and computation time.\n" - << " Caution: camera calibration settings are different for the two resolutions.\n" - << " Make sure that if you pass custom intrinsic camera parameters,\n" - << " they were obtained with the correct resolution.\n\n" - << " --verbose, -v\n" - << " Enables verbose (drone information messages and velocity commands\n" - << " are then displayed).\n\n" - << " --help, -h\n" - << " Print help message.\n" - << std::endl; + << " " << argv[0] + << " [--tag_size ] [--ip ] [--distance_to_tag ] [--intrinsic ] " + << "[--hd_stream] [--verbose] [-v] [--help] [-h]\n" + << std::endl + << "Description:\n" + << " --tag_size \n" + << " The size of the tag to detect in meters, required.\n\n" + << " --ip \n" + << " Ip address of the drone to which you want to connect (default : 192.168.42.1).\n\n" + << " --distance_to_tag \n" + << " The desired distance to the tag in meters (default: 1 meter).\n\n" + << " --intrinsic \n" + << " XML file containing computed intrinsic camera parameters (default: empty).\n\n" + << " --hd_stream\n" + << " Enables HD 720p streaming instead of default 480p.\n" + << " Allows to increase range and accuracy of the tag detection,\n" + << " but increases latency and computation time.\n" + << " Caution: camera calibration settings are different for the two resolutions.\n" + << " Make sure that if you pass custom intrinsic camera parameters,\n" + << " they were obtained with the correct resolution.\n\n" + << " --verbose, -v\n" + << " Enables verbose (drone information messages and velocity commands\n" + << " are then displayed).\n\n" + << " --help, -h\n" + << " Print help message.\n" + << std::endl; return EXIT_SUCCESS; - } else { + } + else { std::cout << "Error : tag size parameter required." << std::endl << "See " << argv[0] << " --help" << std::endl; return EXIT_FAILURE; } std::cout - << "\nWARNING: \n - This program does no sensing or avoiding of " - "obstacles, \n" - "the drone WILL collide with any objects in the way! Make sure " - "the \n" - "drone has approximately 3 meters of free space on all sides.\n" - " - The drone uses a downward-facing camera for horizontal speed estimation,\n make sure the drone flies " - "above a non-uniform flooring,\n or its movement will be inacurate and dangerous !\n" + << "\nWARNING: \n - This program does no sensing or avoiding of " + "obstacles, \n" + "the drone WILL collide with any objects in the way! Make sure " + "the \n" + "drone has approximately 3 meters of free space on all sides.\n" + " - The drone uses a downward-facing camera for horizontal speed estimation,\n make sure the drone flies " + "above a non-uniform flooring,\n or its movement will be inacurate and dangerous !\n" - << std::endl; + << std::endl; vpRobotBebop2 drone( verbose, true, ip_address); // Create the drone with desired verbose level, settings reset, and corresponding IP @@ -254,15 +255,18 @@ int main(int argc, char **argv) std::cout << "Cannot find parameters in XML file " << opt_cam_parameters << std::endl; if (drone.getVideoHeight() == 720) { // 720p streaming cam.initPersProjWithoutDistortion(785.6412585, 785.3322447, 637.9049857, 359.7524531); - } else { // 480p streaming + } + else { // 480p streaming cam.initPersProjWithoutDistortion(531.9213063, 520.8495788, 429.133986, 240.9464457); } } - } else { + } + else { std::cout << "Setting default camera parameters ... " << std::endl; if (drone.getVideoHeight() == 720) { // 720p streaming cam.initPersProjWithoutDistortion(785.6412585, 785.3322447, 637.9049857, 359.7524531); - } else { // 480p streaming + } + else { // 480p streaming cam.initPersProjWithoutDistortion(531.9213063, 520.8495788, 429.133986, 240.9464457); } } @@ -291,7 +295,7 @@ int main(int argc, char **argv) vpRotationMatrix c1Rc2(c1_rxyz_c2); // Rotation between camera 1 and 2 vpHomogeneousMatrix c1Mc2(vpTranslationVector(), c1Rc2); // Homogeneous matrix between c1 and c2 - vpRotationMatrix c1Re{0, 1, 0, 0, 0, 1, 1, 0, 0}; // Rotation between camera 1 and E + vpRotationMatrix c1Re { 0, 1, 0, 0, 0, 1, 1, 0, 0 }; // Rotation between camera 1 and E vpTranslationVector c1te(0, 0, -0.09); // Translation between camera 1 and E vpHomogeneousMatrix c1Me(c1te, c1Re); // Homogeneous matrix between c1 and E @@ -311,8 +315,8 @@ int main(int argc, char **argv) double Z_d = (opt_has_distance_to_tag ? opt_distance_to_tag : 1.); // Define the desired polygon corresponding the the AprilTag CLOCKWISE - double X[4] = {tagSize / 2., tagSize / 2., -tagSize / 2., -tagSize / 2.}; - double Y[4] = {tagSize / 2., -tagSize / 2., -tagSize / 2., tagSize / 2.}; + double X[4] = { tagSize / 2., tagSize / 2., -tagSize / 2., -tagSize / 2. }; + double Y[4] = { tagSize / 2., -tagSize / 2., -tagSize / 2., tagSize / 2. }; std::vector vec_P, vec_P_d; for (int i = 0; i < 4; i++) { @@ -499,7 +503,8 @@ int main(int argc, char **argv) vpDisplay::displayLine(I, vec_ip[vec_ip_sorted[2].first], vec_ip[vec_ip_sorted[3].first], vpColor::red, 1, false); - } else { + } + else { std::stringstream sserr; sserr << "Failed to detect an Apriltag, or detected multiple ones"; vpDisplay::displayText(I, 120, 20, sserr.str(), vpColor::red); @@ -528,11 +533,13 @@ int main(int argc, char **argv) return EXIT_SUCCESS; - } else { + } + else { std::cout << "ERROR : failed to setup drone control." << std::endl; return EXIT_FAILURE; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Caught an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/example/servo-franka/servoFrankaIBVS.cpp b/example/servo-franka/servoFrankaIBVS.cpp index 6e78536aaa..d2cee5acd0 100644 --- a/example/servo-franka/servoFrankaIBVS.cpp +++ b/example/servo-franka/servoFrankaIBVS.cpp @@ -74,8 +74,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA) void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) @@ -86,7 +85,8 @@ void display_point_trajectory(const vpImage &I, const std::vector if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) { traj_vip[i].push_back(vip[i]); } - } else { + } + else { traj_vip[i].push_back(vip[i]); } } @@ -113,29 +113,38 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { opt_tagSize = std::stod(argv[i + 1]); - } else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { opt_robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) { opt_eMc_filename = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--verbose") { + } + else if (std::string(argv[i]) == "--verbose") { opt_verbose = true; - } else if (std::string(argv[i]) == "--plot") { + } + else if (std::string(argv[i]) == "--plot") { opt_plot = true; - } else if (std::string(argv[i]) == "--adaptive_gain") { + } + else if (std::string(argv[i]) == "--adaptive_gain") { opt_adaptive_gain = true; - } else if (std::string(argv[i]) == "--task_sequencing") { + } + 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") { + } + else if (std::string(argv[i]) == "--no-convergence-threshold") { convergence_threshold = 0.; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout - << argv[0] << " [--ip ] [--tag_size ] [--eMc ] " - << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" - << "\n"; + << argv[0] << " [--ip ] [--tag_size ] [--eMc ] " + << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" + << "\n"; return EXIT_SUCCESS; } } @@ -166,16 +175,17 @@ int main(int argc, char **argv) // If provided, read camera extrinsics from --eMc if (!opt_eMc_filename.empty()) { ePc.loadYAML(opt_eMc_filename, ePc); - } else { + } + else { std::cout << "Warning, opt_eMc_filename is empty! Use hard coded values." - << "\n"; + << "\n"; } vpHomogeneousMatrix eMc(ePc); std::cout << "eMc:\n" << eMc << "\n"; // Get camera intrinsics vpCameraParameters cam = - rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); + rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); std::cout << "cam:\n" << cam << "\n"; vpImage I(height, width); @@ -199,7 +209,7 @@ int main(int argc, char **argv) // Desired pose used to compute the desired features vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis - vpRotationMatrix({1, 0, 0, 0, -1, 0, 0, 0, -1})); + vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 })); // Create visual features std::vector p(4), pd(4); // We use 4 points @@ -222,7 +232,8 @@ int main(int argc, char **argv) if (opt_adaptive_gain) { vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30 task.setLambda(lambda); - } else { + } + else { task.setLambda(0.5); } @@ -295,7 +306,8 @@ int main(int argc, char **argv) } if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) { oMo = v_oMo[0]; - } else { + } + else { std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl; oMo = v_oMo[1]; // Introduce PI rotation } @@ -334,7 +346,8 @@ int main(int argc, char **argv) t_init_servo = vpTime::measureTimeMs(); } v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.); - } else { + } + else { v_c = task.computeControlLaw(); } @@ -377,7 +390,7 @@ int main(int argc, char **argv) if (error < convergence_threshold) { has_converged = true; std::cout << "Servo task has converged" - << "\n"; + << "\n"; vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red); } if (first_time) { @@ -445,18 +458,21 @@ int main(int argc, char **argv) if (traj_corners) { delete[] traj_corners; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " - << std::endl; + << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " + << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -469,9 +485,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense-2.x" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif #if !defined(VISP_HAVE_FRANKA) std::cout << "Install libfranka." << std::endl; #endif diff --git a/example/servo-franka/servoFrankaPBVS.cpp b/example/servo-franka/servoFrankaPBVS.cpp index 3925f45c82..df6caa27a0 100644 --- a/example/servo-franka/servoFrankaPBVS.cpp +++ b/example/servo-franka/servoFrankaPBVS.cpp @@ -71,8 +71,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA) void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) @@ -83,7 +82,8 @@ void display_point_trajectory(const vpImage &I, const std::vector if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) { traj_vip[i].push_back(vip[i]); } - } else { + } + else { traj_vip[i].push_back(vip[i]); } } @@ -111,30 +111,39 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { opt_tagSize = std::stod(argv[i + 1]); - } else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { opt_robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) { opt_eMc_filename = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--verbose") { + } + else if (std::string(argv[i]) == "--verbose") { opt_verbose = true; - } else if (std::string(argv[i]) == "--plot") { + } + else if (std::string(argv[i]) == "--plot") { opt_plot = true; - } else if (std::string(argv[i]) == "--adaptive_gain") { + } + else if (std::string(argv[i]) == "--adaptive_gain") { opt_adaptive_gain = true; - } else if (std::string(argv[i]) == "--task_sequencing") { + } + 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") { + } + else if (std::string(argv[i]) == "--no-convergence-threshold") { convergence_threshold_t = 0.; convergence_threshold_tu = 0.; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout - << argv[0] << " [--ip ] [--tag_size ] [--eMc ] " - << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" - << "\n"; + << argv[0] << " [--ip ] [--tag_size ] [--eMc ] " + << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" + << "\n"; return EXIT_SUCCESS; } } @@ -165,16 +174,17 @@ int main(int argc, char **argv) // If provided, read camera extrinsics from --eMc if (!opt_eMc_filename.empty()) { ePc.loadYAML(opt_eMc_filename, ePc); - } else { + } + else { std::cout << "Warning, opt_eMc_filename is empty! Use hard coded values." - << "\n"; + << "\n"; } vpHomogeneousMatrix eMc(ePc); std::cout << "eMc:\n" << eMc << "\n"; // Get camera intrinsics vpCameraParameters cam = - rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); + rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); std::cout << "cam:\n" << cam << "\n"; vpImage I(height, width); @@ -198,7 +208,7 @@ int main(int argc, char **argv) // Desired pose to reach vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis - vpRotationMatrix({1, 0, 0, 0, -1, 0, 0, 0, -1})); + vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 })); cdMc = cdMo * cMo.inverse(); vpFeatureTranslation t(vpFeatureTranslation::cdMc); @@ -218,7 +228,8 @@ int main(int argc, char **argv) if (opt_adaptive_gain) { vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30 task.setLambda(lambda); - } else { + } + else { task.setLambda(0.5); } @@ -287,7 +298,8 @@ int main(int argc, char **argv) } if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) { oMo = v_oMo[0]; - } else { + } + else { std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl; oMo = v_oMo[1]; // Introduce PI rotation } @@ -306,7 +318,8 @@ int main(int argc, char **argv) t_init_servo = vpTime::measureTimeMs(); } v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.); - } else { + } + else { v_c = task.computeControlLaw(); } @@ -419,18 +432,21 @@ int main(int argc, char **argv) if (traj_vip) { delete[] traj_vip; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " - << std::endl; + << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " + << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -443,9 +459,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense-2.x" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif #if !defined(VISP_HAVE_FRANKA) std::cout << "Install libfranka." << std::endl; #endif diff --git a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp index 7b5011991f..8fa7735c17 100644 --- a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp +++ b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp @@ -59,7 +59,7 @@ #endif #include -#if (defined(VISP_HAVE_PTU46) & defined(VISP_HAVE_DC1394) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)) +#if defined(VISP_HAVE_PTU46) && defined(VISP_HAVE_DC1394) #include diff --git a/example/servo-universal-robots/UniversalRobotsMoveToPosition.cpp b/example/servo-universal-robots/UniversalRobotsMoveToPosition.cpp index f6038c801f..4cb3808e1f 100644 --- a/example/servo-universal-robots/UniversalRobotsMoveToPosition.cpp +++ b/example/servo-universal-robots/UniversalRobotsMoveToPosition.cpp @@ -55,12 +55,14 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { opt_robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--read" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--read" && i + 1 < argc) { opt_position_filename = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Move UR robot to a position specified from a file." << std::endl; std::cout << argv[0] << " [--ip ] [--read ] [--help] [-h]\n" - << std::endl; + << std::endl; std::cout << "Example:\n" << argv[0] << " --ip 192.168.0.100 --read position.pos\n" << std::endl; return EXIT_SUCCESS; @@ -74,7 +76,7 @@ int main(int argc, char **argv) } if (!vpIoTools::checkFilename(opt_position_filename)) { std::cout << "\nError: position filename \"" << opt_position_filename << "\" given as input doesn't exist. " - << std::endl; + << std::endl; std::cout << "Call \"" << argv[0] << " --help\" to get usage" << std::endl; return EXIT_FAILURE; } @@ -85,12 +87,14 @@ int main(int argc, char **argv) robot.connect(opt_robot_ip); robot.move(opt_position_filename); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -102,10 +106,7 @@ int main() { #if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." - << std::endl; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; + << std::endl; #endif return EXIT_SUCCESS; } diff --git a/example/servo-universal-robots/UniversalRobotsSavePosition.cpp b/example/servo-universal-robots/UniversalRobotsSavePosition.cpp index e8a7413d16..851e82f532 100644 --- a/example/servo-universal-robots/UniversalRobotsSavePosition.cpp +++ b/example/servo-universal-robots/UniversalRobotsSavePosition.cpp @@ -54,13 +54,15 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { opt_robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--save" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--save" && i + 1 < argc) { opt_position_filename = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Save UR robot position in a file." << std::endl; std::cout << "Usage:\n" << std::endl; std::cout << argv[0] << " [--ip ] [--save ] [--help] [-h]\n" - << std::endl; + << std::endl; std::cout << "Example:\n" << argv[0] << " --ip 192.168.0.100 --save position.pos\n" << std::endl; return EXIT_SUCCESS; @@ -77,12 +79,14 @@ int main(int argc, char **argv) robot.savePosFile(opt_position_filename, q); std::cout << "Robot position saved in \"" << opt_position_filename << "\"" << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -94,10 +98,7 @@ int main() { #if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." - << std::endl; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; + << std::endl; #endif return EXIT_SUCCESS; } diff --git a/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp b/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp index 65cfca7f2a..6d049fb8db 100644 --- a/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp +++ b/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp @@ -71,8 +71,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE) void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) @@ -83,7 +82,8 @@ void display_point_trajectory(const vpImage &I, const std::vector if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) { traj_vip[i].push_back(vip[i]); } - } else { + } + else { traj_vip[i].push_back(vip[i]); } } @@ -110,29 +110,38 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { opt_tagSize = std::stod(argv[i + 1]); - } else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { opt_robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) { opt_eMc_filename = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--verbose") { + } + else if (std::string(argv[i]) == "--verbose") { opt_verbose = true; - } else if (std::string(argv[i]) == "--plot") { + } + else if (std::string(argv[i]) == "--plot") { opt_plot = true; - } else if (std::string(argv[i]) == "--adaptive_gain") { + } + else if (std::string(argv[i]) == "--adaptive_gain") { opt_adaptive_gain = true; - } else if (std::string(argv[i]) == "--task_sequencing") { + } + 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") { + } + else if (std::string(argv[i]) == "--no-convergence-threshold") { convergence_threshold = 0.; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout - << argv[0] << " [--ip ] [--tag_size ] [--eMc ] " - << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" - << "\n"; + << argv[0] << " [--ip ] [--tag_size ] [--eMc ] " + << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" + << "\n"; return EXIT_SUCCESS; } } @@ -143,8 +152,8 @@ int main(int argc, char **argv) robot.connect(opt_robot_ip); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -182,16 +191,17 @@ int main(int argc, char **argv) // If provided, read camera extrinsics from --eMc if (!opt_eMc_filename.empty()) { ePc.loadYAML(opt_eMc_filename, ePc); - } else { + } + else { std::cout << "Warning, opt_eMc_filename is empty! Use hard coded values." - << "\n"; + << "\n"; } vpHomogeneousMatrix eMc(ePc); std::cout << "eMc:\n" << eMc << "\n"; // Get camera intrinsics vpCameraParameters cam = - rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); + rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); std::cout << "cam:\n" << cam << "\n"; vpImage I(height, width); @@ -215,7 +225,7 @@ int main(int argc, char **argv) // Desired pose used to compute the desired features vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis - vpRotationMatrix({1, 0, 0, 0, -1, 0, 0, 0, -1})); + vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 })); // Create visual features std::vector p(4), pd(4); // We use 4 points @@ -238,7 +248,8 @@ int main(int argc, char **argv) if (opt_adaptive_gain) { vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30 task.setLambda(lambda); - } else { + } + else { task.setLambda(0.5); } @@ -311,7 +322,8 @@ int main(int argc, char **argv) } if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) { oMo = v_oMo[0]; - } else { + } + else { std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl; oMo = v_oMo[1]; // Introduce PI rotation } @@ -350,7 +362,8 @@ int main(int argc, char **argv) t_init_servo = vpTime::measureTimeMs(); } v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.); - } else { + } + else { v_c = task.computeControlLaw(); } @@ -393,7 +406,7 @@ int main(int argc, char **argv) if (error < convergence_threshold) { has_converged = true; std::cout << "Servo task has converged" - << "\n"; + << "\n"; vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red); } if (first_time) { @@ -461,12 +474,14 @@ int main(int argc, char **argv) if (traj_corners) { delete[] traj_corners; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -479,12 +494,9 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense-2.x" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif #if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." - << std::endl; + << std::endl; #endif return EXIT_SUCCESS; } diff --git a/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp b/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp index db3a9aef03..af7861ef76 100644 --- a/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp +++ b/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp @@ -68,8 +68,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE) void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) @@ -80,7 +79,8 @@ void display_point_trajectory(const vpImage &I, const std::vector if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) { traj_vip[i].push_back(vip[i]); } - } else { + } + else { traj_vip[i].push_back(vip[i]); } } @@ -108,30 +108,39 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { opt_tagSize = std::stod(argv[i + 1]); - } else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { opt_robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) { opt_eMc_filename = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--verbose") { + } + else if (std::string(argv[i]) == "--verbose") { opt_verbose = true; - } else if (std::string(argv[i]) == "--plot") { + } + else if (std::string(argv[i]) == "--plot") { opt_plot = true; - } else if (std::string(argv[i]) == "--adaptive_gain") { + } + else if (std::string(argv[i]) == "--adaptive_gain") { opt_adaptive_gain = true; - } else if (std::string(argv[i]) == "--task_sequencing") { + } + 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") { + } + else if (std::string(argv[i]) == "--no-convergence-threshold") { convergence_threshold_t = 0.; convergence_threshold_tu = 0.; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout - << argv[0] << " [--ip ] [--tag_size ] [--eMc ] " - << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" - << "\n"; + << argv[0] << " [--ip ] [--tag_size ] [--eMc ] " + << "[--quad_decimate ] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" + << "\n"; return EXIT_SUCCESS; } } @@ -142,8 +151,8 @@ int main(int argc, char **argv) robot.connect(opt_robot_ip); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -181,16 +190,17 @@ int main(int argc, char **argv) // If provided, read camera extrinsics from --eMc if (!opt_eMc_filename.empty()) { ePc.loadYAML(opt_eMc_filename, ePc); - } else { + } + else { std::cout << "Warning, opt_eMc_filename is empty! Use hard coded values." - << "\n"; + << "\n"; } vpHomogeneousMatrix eMc(ePc); std::cout << "eMc:\n" << eMc << "\n"; // Get camera intrinsics vpCameraParameters cam = - rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); + rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion); std::cout << "cam:\n" << cam << "\n"; vpImage I(height, width); @@ -214,7 +224,7 @@ int main(int argc, char **argv) // Desired pose to reach vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis - vpRotationMatrix({1, 0, 0, 0, -1, 0, 0, 0, -1})); + vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 })); cdMc = cdMo * cMo.inverse(); vpFeatureTranslation t(vpFeatureTranslation::cdMc); @@ -234,7 +244,8 @@ int main(int argc, char **argv) if (opt_adaptive_gain) { vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30 task.setLambda(lambda); - } else { + } + else { task.setLambda(0.5); } @@ -303,7 +314,8 @@ int main(int argc, char **argv) } if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) { oMo = v_oMo[0]; - } else { + } + else { std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl; oMo = v_oMo[1]; // Introduce PI rotation } @@ -322,7 +334,8 @@ int main(int argc, char **argv) t_init_servo = vpTime::measureTimeMs(); } v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.); - } else { + } + else { v_c = task.computeControlLaw(); } @@ -435,12 +448,14 @@ int main(int argc, char **argv) if (traj_vip) { delete[] traj_vip; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -453,12 +468,9 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense-2.x" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif #if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." - << std::endl; + << std::endl; #endif return EXIT_SUCCESS; } diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index b3248c656f..595ade35ca 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -97,20 +97,16 @@ int main() int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpArray2D a{ {-1, -2, -3}, {4, 5.5, 6.0f} }; std::cout << "a:\n" << a << std::endl; -#endif } \endcode The array could also be initialized using operator=(const std::initializer_list< std::initializer_list< Type > > &) \code int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpArray2D a; a = { {-1, -2, -3}, {4, 5.5, 6.0f} }; -#endif } \endcode @@ -120,10 +116,8 @@ int main() int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpArray2D a{ -1, -2, -3, 4, 5.5, 6.0f }; a.reshape(2, 3); -#endif } \endcode */ @@ -154,12 +148,7 @@ template class vpArray2D Copy constructor of a 2D array. */ vpArray2D(const vpArray2D &A) - : -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - vpArray2D() -#else - rowNum(0), colNum(0), rowPtrs(NULL), dsize(0), data(NULL) -#endif + : vpArray2D() { resize(A.rowNum, A.colNum, false, false); memcpy(data, A.data, (size_t)rowNum * (size_t)colNum * sizeof(Type)); @@ -172,12 +161,7 @@ template class vpArray2D \param c : Array number of columns. */ vpArray2D(unsigned int r, unsigned int c) - : -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - vpArray2D() -#else - rowNum(0), colNum(0), rowPtrs(NULL), dsize(0), data(NULL) -#endif + : vpArray2D() { resize(r, c); } @@ -190,18 +174,12 @@ template class vpArray2D \param val : Each element of the array is set to \e val. */ vpArray2D(unsigned int r, unsigned int c, Type val) - : -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - vpArray2D() -#else - rowNum(0), colNum(0), rowPtrs(NULL), dsize(0), data(NULL) -#endif + : vpArray2D() { resize(r, c, false, false); *this = val; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpArray2D(vpArray2D &&A) noexcept { rowNum = A.rowNum; @@ -251,7 +229,6 @@ template class vpArray2D std::copy(it->begin(), it->end(), rowPtrs[i]); } } -#endif /*! Destructor that deallocate memory. @@ -460,7 +437,6 @@ template class vpArray2D return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpArray2D &operator=(vpArray2D &&other) noexcept { if (this != &other) { @@ -513,7 +489,6 @@ template class vpArray2D #ifdef VISP_HAVE_NLOHMANN_JSON vpArray2D &operator=(const nlohmann::json &j) = delete; -#endif #endif //! Set element \f$A_{ij} = x\f$ using A[i][j] = x diff --git a/modules/core/include/visp3/core/vpCameraParameters.h b/modules/core/include/visp3/core/vpCameraParameters.h index ada6c7074d..1a9f2b283d 100644 --- a/modules/core/include/visp3/core/vpCameraParameters.h +++ b/modules/core/include/visp3/core/vpCameraParameters.h @@ -159,7 +159,7 @@ to estimate the parameters corresponding to the model implemented in this class. - \note Note also that \ref tutorial-bridge-opencv gives the correspondance + \note Note also that \ref tutorial-bridge-opencv gives the correspondence between ViSP and OpenCV camera modelization. \note The conversion from pixel coordinates \f$(u,v)\f$ in the normalized diff --git a/modules/core/include/visp3/core/vpColVector.h b/modules/core/include/visp3/core/vpColVector.h index 0236d46bc1..6f0bc5ef96 100644 --- a/modules/core/include/visp3/core/vpColVector.h +++ b/modules/core/include/visp3/core/vpColVector.h @@ -104,20 +104,16 @@ class vpPoseVector; * * int main() * { - * #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) * vpColVector v({-1, -2.1, -3}); * std::cout << "v:\n" << v << std::endl; - * #endif * } * \endcode * The vector could also be initialized using operator=(const std::initializer_list< double > &) * \code * int main() * { - * #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) * vpColVector v; * v = {-1, -2.1, -3}; - * #endif * } * \endcode * @@ -244,7 +240,7 @@ class VISP_EXPORT vpColVector : public vpArray2D * Constructor that creates a column vector from a std vector of float. */ vpColVector(const std::vector &v); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + /*! * Move constructor that take rvalue. */ @@ -253,7 +249,6 @@ class VISP_EXPORT vpColVector : public vpArray2D { std::copy(list.begin(), list.end(), data); } -#endif /*! * Removes all elements from the vector (which are destroyed), @@ -632,7 +627,6 @@ class VISP_EXPORT vpColVector : public vpArray2D */ vpColVector &operator=(double x); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! * Overloaded move assignment operator taking rvalue. */ @@ -662,7 +656,6 @@ class VISP_EXPORT vpColVector : public vpArray2D * \sa operator<<() */ vpColVector &operator=(const std::initializer_list &list); -#endif /*! * Compare two column vectors. diff --git a/modules/core/include/visp3/core/vpColormap.h b/modules/core/include/visp3/core/vpColormap.h index e30ddd189c..2609e6f3a0 100644 --- a/modules/core/include/visp3/core/vpColormap.h +++ b/modules/core/include/visp3/core/vpColormap.h @@ -36,25 +36,24 @@ #define _vpColormap_h_ /*! - \file vpColormap.h - - \brief Colormap tool to have a mapping between 256 values and RGB values. -*/ + * \file vpColormap.h + * + * \brief Colormap tool to have a mapping between 256 values and RGB values. + */ #include #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! - \class vpColormap - - \ingroup group_core_image - - \brief Creates a colormap class to be able to recolor an image with different grayscale - values into some corresponding color values, for better visualization for example. -*/ + * \class vpColormap + * + * \ingroup group_core_image + * + * \brief Creates a colormap class to be able to recolor an image with different grayscale + * values into some corresponding color values, for better visualization for example. + */ class VISP_EXPORT vpColormap { public: @@ -98,4 +97,3 @@ class VISP_EXPORT vpColormap }; #endif -#endif diff --git a/modules/core/include/visp3/core/vpHomogeneousMatrix.h b/modules/core/include/visp3/core/vpHomogeneousMatrix.h index 6e4291f992..4c7f498ad1 100644 --- a/modules/core/include/visp3/core/vpHomogeneousMatrix.h +++ b/modules/core/include/visp3/core/vpHomogeneousMatrix.h @@ -137,7 +137,6 @@ class vpPoint; int main() { - #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { vpHomogeneousMatrix M( vpTranslationVector(0.1, 0.2, 0.3), vpRotationMatrix( {0, 0, -1, 0, -1, 0, -1, 0, 0} ) ); std::cout << "M:\n" << M << std::endl; @@ -148,7 +147,6 @@ class vpPoint; -1, 0, 0, 0.3 }; std::cout << "M:\n" << M << std::endl; } - #endif } \endcode @@ -209,9 +207,7 @@ class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D explicit vpHomogeneousMatrix(const std::vector &v); explicit vpHomogeneousMatrix(const std::vector &v); vpHomogeneousMatrix(double tx, double ty, double tz, double tux, double tuy, double tuz); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpHomogeneousMatrix(const std::initializer_list &list); -#endif void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R); void buildFrom(const vpTranslationVector &t, const vpThetaUVector &tu); @@ -352,10 +348,10 @@ class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D void print() const; /*! - This function is not applicable to an homogeneous matrix that is always a - 4-by-4 matrix. - \exception vpException::fatalError When this function is called. - */ + * This function is not applicable to an homogeneous matrix that is always a + * 4-by-4 matrix. + * \exception vpException::fatalError When this function is called. + */ void resize(unsigned int nrows, unsigned int ncols, bool flagNullify = true) { (void)nrows; @@ -383,16 +379,16 @@ class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) /*! - @name Deprecated functions - */ + * @name Deprecated functions + */ //@{ /*! - \deprecated Provided only for compat with previous releases. - This function does nothing. + * \deprecated Provided only for compat with previous releases. + * This function does nothing. */ vp_deprecated void init() { } /*! - \deprecated You should rather use eye(). + * \deprecated You should rather use eye(). */ vp_deprecated void setIdentity(); //@} diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 0f56a92b36..76dc22b44c 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -143,10 +143,8 @@ template class vpImage vpImage(); //! copy constructor vpImage(const vpImage &); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) //! move constructor vpImage(vpImage &&); -#endif //! constructor set the size of the image vpImage(unsigned int height, unsigned int width); //! constructor set the size of the image and init all the pixel @@ -861,7 +859,6 @@ vpImage::vpImage(const vpImage &I) memcpy(static_cast(bitmap), static_cast(I.bitmap), I.npixels * sizeof(Type)); } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! \relates vpImage */ @@ -878,7 +875,6 @@ vpImage::vpImage(vpImage &&I) I.row = NULL; I.hasOwnership = false; } -#endif /*! * \brief Return the maximum value within the bitmap diff --git a/modules/core/include/visp3/core/vpImageFilter.h b/modules/core/include/visp3/core/vpImageFilter.h index a977d73509..eb671845d6 100644 --- a/modules/core/include/visp3/core/vpImageFilter.h +++ b/modules/core/include/visp3/core/vpImageFilter.h @@ -35,10 +35,9 @@ #define _vpImageFilter_h_ /*! - \file vpImageFilter.h - \brief Various image filter, convolution, etc... - -*/ + * \file vpImageFilter.h + * \brief Various image filter, convolution, etc... + */ #include #include @@ -60,13 +59,12 @@ #endif /*! - \class vpImageFilter - - \ingroup group_core_image - - \brief Various image filter, convolution, etc... - -*/ + * \class vpImageFilter + * + * \ingroup group_core_image + * + * \brief Various image filter, convolution, etc... + */ class VISP_EXPORT vpImageFilter { public: @@ -113,13 +111,241 @@ class VISP_EXPORT vpImageFilter const float &upperThresholdRatio, const bool &normalizeGradients, const vpCannyBackendType &cannyBackend, const vpCannyFilteringAndGradientType &cannyFilteringSteps); - /*! - Apply a 1x3 derivative filter to an image pixel. +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) + static float computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *p_cv_dIx, const cv::Mat *p_cv_dIy, + float &lowerThresh, const unsigned int &gaussianKernelSize = 5, + const float &gaussianStdev = 2.f, const unsigned int &apertureGradient = 3, + const float &lowerThresholdRatio = 0.6, const float &upperThresholdRatio = 0.8, + const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING); - \param I : Image to filter - \param r : coordinates (row) of the pixel - \param c : coordinates (column) of the pixel - */ + static void computePartialDerivatives(const cv::Mat &cv_I, + cv::Mat &cv_dIx, cv::Mat &cv_dIy, + const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, + const unsigned int &gaussianKernelSize = 5, const float &gaussianStdev = 2.f, + const unsigned int &apertureGradient = 3, + const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING); +#endif + + /** + * \brief Compute the partial derivatives (i.e. horizontal and vertical gradients) of the input image. + * + * \tparam ImageType Either unsigned char, float or double + * \tparam FilterType Either float or double. + * \param[in] I The input image we want the partial derivatives. + * \param[out] dIx The horizontal partial derivative, i.e. horizontal gradient. + * \param[out] dIy The vertical partial derivative, i.e. vertical gradient. + * \param[in] computeDx Indicate if we must compute the horizontal gradient. + * \param[in] computeDy Indicate if we must compute the vertical gradient. + * \param[in] normalize Indicate if we must normalize the gradient filters. + * \param[in] gaussianKernelSize The size of the kernel of the Gaussian filter used to blur the image. + * If it is non-positive, it is computed from kernel size (`gaussianKernelSize` parameter) as + * \f$\sigma = 0.3*((gaussianKernelSize-1)*0.5 - 1) + 0.8\f$. + * \param[in] gaussianStdev The standard deviation of the Gaussian filter used to blur the image. + * \param[in] apertureGradient The size of the kernel of the gradient filter. + * \param[in] filteringType The type of filters to apply to compute the gradients. + * \param[in] backend The type of backend to use to compute the gradients. + */ + template + inline static void computePartialDerivatives(const vpImage &I, + vpImage &dIx, vpImage &dIy, + const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, + const unsigned int &gaussianKernelSize = 5, const FilterType &gaussianStdev = 2.f, + const unsigned int &apertureGradient = 3, + const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING, + const vpCannyBackendType &backend = CANNY_VISP_BACKEND) + { + if (backend == CANNY_OPENCV_BACKEND) { +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) + cv::Mat cv_I, cv_dIx, cv_dIy; + vpImageConvert::convert(I, cv_I); + computePartialDerivatives(cv_I, cv_dIx, cv_dIy, computeDx, computeDy, normalize, gaussianKernelSize, + gaussianStdev, apertureGradient, filteringType); + if (computeDx) { + vpImageConvert::convert(cv_dIx, dIx); + } + if (computeDy) { + vpImageConvert::convert(cv_dIy, dIy); + } +#else + throw(vpException(vpException::badValue, "You need to compile ViSP with OpenCV to use CANNY_OPENCV_BACKEND")); +#endif + } + else { + if (filteringType == CANNY_GBLUR_SCHARR_FILTERING || filteringType == CANNY_GBLUR_SOBEL_FILTERING) { + dIx.resize(I.getHeight(), I.getWidth()); + dIy.resize(I.getHeight(), I.getWidth()); + + // Computing the Gaussian blur + gradients of the image + vpImage Iblur; + vpImageFilter::gaussianBlur(I, Iblur, gaussianKernelSize, gaussianStdev); + + vpArray2D gradientFilterX(apertureGradient, apertureGradient); // Gradient filter along the X-axis + vpArray2D gradientFilterY(apertureGradient, apertureGradient); // Gradient filter along the Y-axis + + // Helper to apply the scale to the raw values of the filters + auto scaleFilter = [](vpArray2D &filter, const float &scale) { + for (unsigned int r = 0; r < filter.getRows(); r++) { + for (unsigned int c = 0; c < filter.getCols(); c++) { + filter[r][c] = filter[r][c] * scale; + } + }}; + + // Scales to apply to the filters to get a normalized gradient filter that gives a gradient + // between 0 and 255 for an vpImage + float scaleX = 1.f; + float scaleY = 1.f; + + if (filteringType == CANNY_GBLUR_SOBEL_FILTERING) { + if (computeDx) { + scaleX = vpImageFilter::getSobelKernelX(gradientFilterX.data, (apertureGradient - 1)/2); + } + if (computeDy) { + scaleY = vpImageFilter::getSobelKernelY(gradientFilterY.data, (apertureGradient - 1)/2); + } + } + else if (filteringType == CANNY_GBLUR_SCHARR_FILTERING) { + if (computeDx) { + scaleX = vpImageFilter::getScharrKernelX(gradientFilterX.data, (apertureGradient - 1)/2); + } + if (computeDy) { + scaleY = vpImageFilter::getScharrKernelY(gradientFilterY.data, (apertureGradient - 1)/2); + } + } + + // Scale the gradient filters to have a normalized gradient filter + if (normalize) { + if (computeDx) { + scaleFilter(gradientFilterX, scaleX); + } + if (computeDy) { + scaleFilter(gradientFilterY, scaleY); + } + } + + // Apply the gradient filters to get the gradients + if (computeDx) { + vpImageFilter::filter(Iblur, dIx, gradientFilterX); + } + + if (computeDy) { + vpImageFilter::filter(Iblur, dIy, gradientFilterY); + } + } + else { + std::string errMsg = "[vpImageFilter::computePartialDerivatives] Filtering + gradient method \""; + errMsg += vpCannyFilteringAndGradientTypeToString(filteringType); + errMsg += "\" is not implemented yet\n"; + throw(vpException(vpException::notImplementedError, errMsg)); + } + } + } + + template + inline static void computePartialDerivatives(const vpImage &I, + vpImage &dIx, vpImage &dIy, + const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, + const unsigned int &gaussianKernelSize = 5, const FilterType &gaussianStdev = 2.f, + const unsigned int &apertureGradient = 3, + const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING, + const vpCannyBackendType &backend = CANNY_VISP_BACKEND) = delete; + + template + inline static void computePartialDerivatives(const vpImage &I, + vpImage &dIx, vpImage &dIy, + const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, + const unsigned int &gaussianKernelSize = 5, const unsigned char &gaussianStdev = 2.f, + const unsigned int &apertureGradient = 3, + const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING, + const vpCannyBackendType &backend = CANNY_VISP_BACKEND) = delete; + + template + inline static void computePartialDerivatives(const vpImage &I, + vpImage &dIx, vpImage &dIy, + const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, + const unsigned int gaussianKernelSize = 5, const vpRGBa gaussianStdev = vpRGBa(), + const unsigned int apertureGradient = 3, + const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING, + const vpCannyBackendType &backend = CANNY_VISP_BACKEND) = delete; + + /** + * \brief Compute the upper Canny edge filter threshold, using Gaussian blur + Sobel or + Scharr operators to compute + * the gradient of the image. + * + * \tparam OutType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param[in] I : The gray-scale image, in ViSP format. + * \param[in] p_dIx : If different from nullptr, must contain the gradient of the image with regard to the horizontal axis. + * \param[in] p_dIy : If different from nullptr, must contain the gradient of the image with regard to the vertical axis. + * \param[in] lowerThresh : Canny lower threshold. + * \param[in] gaussianKernelSize : The size of the mask of the Gaussian filter to apply (an odd number). + * \param[in] gaussianStdev : The standard deviation of the Gaussian filter to apply. + * \param[in] apertureGradient : Size of the mask for the Sobel operator (odd number). + * \param[in] lowerThresholdRatio : The ratio of the upper threshold the lower threshold must be equal to. + * \param[in] upperThresholdRatio : The ratio of pixels whose absolute gradient Gabs is lower or equal to define + * the upper threshold. + * \param[in] filteringType : The gradient filter to apply to compute the gradient, if \b p_dIx and \b p_dIy are + * nullptr. + * \return The upper Canny edge filter threshold. + */ + template + inline static float computeCannyThreshold(const vpImage &I, float &lowerThresh, + const vpImage *p_dIx = nullptr, const vpImage *p_dIy = nullptr, + const unsigned int &gaussianKernelSize = 5, + const OutType &gaussianStdev = 2.f, const unsigned int &apertureGradient = 3, + const float &lowerThresholdRatio = 0.6, const float &upperThresholdRatio = 0.8, + const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING) + { + double w = I.getWidth(); + double h = I.getHeight(); + + vpImage dI(h, w); + vpImage dIx(h, w), dIy(h, w); + if (p_dIx != nullptr && p_dIy != nullptr) { + dIx = *p_dIx; + dIy = *p_dIy; + } + else { + computePartialDerivatives(I, dIx, dIy, true, true, true, gaussianKernelSize, gaussianStdev, + apertureGradient, filteringType); + } + + // Computing the absolute gradient of the image G = |dIx| + |dIy| + for (unsigned int r = 0; r < h; r++) { + for (unsigned int c = 0; c < w; c++) { + float dx = (float)dIx[r][c]; + float dy = (float)dIy[r][c]; + float gradient = std::abs(dx) + std::abs(dy); + float gradientClamped = std::min(gradient, (float)std::numeric_limits::max()); + dI[r][c] = gradientClamped; + } + } + + // Compute the histogram + vpHistogram hist; + const unsigned int nbBins = 256; + hist.calculate(dI, nbBins); + float accu = 0; + float t = (float)(upperThresholdRatio * w * h); + float bon = 0; + for (unsigned int i = 0; i < nbBins; i++) { + float tf = hist[i]; + accu = accu + tf; + if (accu > t) { + bon = (float)i; + break; + } + } + float upperThresh = std::max(bon, 1.f); + lowerThresh = lowerThresholdRatio * bon; + return upperThresh; + } + + /*! + * Apply a 1x3 derivative filter to an image pixel. + * + * \param I : Image to filter + * \param r : coordinates (row) of the pixel + * \param c : coordinates (column) of the pixel + */ template static double derivativeFilterX(const vpImage &I, unsigned int r, unsigned int c) { return (2047.0 * (I[r][c + 1] - I[r][c - 1]) + 913.0 * (I[r][c + 2] - I[r][c - 2]) + @@ -127,12 +353,12 @@ class VISP_EXPORT vpImageFilter } /*! - Apply a 3x1 derivative filter to an image pixel. - - \param I : Image to filter - \param r : coordinates (row) of the pixel - \param c : coordinates (column) of the pixel - */ + * Apply a 3x1 derivative filter to an image pixel. + * + * \param I : Image to filter + * \param r : coordinates (row) of the pixel + * \param c : coordinates (column) of the pixel + */ template static double derivativeFilterY(const vpImage &I, unsigned int r, unsigned int c) { return (2047.0 * (I[r + 1][c] - I[r - 1][c]) + 913.0 * (I[r + 2][c] - I[r - 2][c]) + @@ -140,18 +366,18 @@ class VISP_EXPORT vpImageFilter } /*! - Apply a 1 x size Derivative Filter in X to an image pixel. - - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param I : Image to filter - \param r : Coordinates(row) of the pixel - \param c : Coordinates(column) of the pixel - \param filter : Coefficients of the filter to be initialized using - vpImageFilter::getGaussianDerivativeKernel(). - \param size : Size of the filter. - - \sa vpImageFilter::getGaussianDerivativeKernel() - */ + * Apply a 1 x size Derivative Filter in X to an image pixel. + * + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param I : Image to filter + * \param r : Coordinates(row) of the pixel + * \param c : Coordinates(column) of the pixel + * \param filter : Coefficients of the filter to be initialized using + * vpImageFilter::getGaussianDerivativeKernel(). + * \param size : Size of the filter. + * + * \sa vpImageFilter::getGaussianDerivativeKernel() + */ template static FilterType derivativeFilterX(const vpImage &I, unsigned int r, unsigned int c, const FilterType *filter, unsigned int size) { @@ -167,18 +393,18 @@ class VISP_EXPORT vpImageFilter } /*! - Apply a size x 1 Derivative Filter in Y to an image pixel. - - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param I : Image to filter. - \param r : Coordinates (row) of the pixel. - \param c : Coordinates (column) of the pixel. - \param filter : Coefficients of the filter to be initialized using - vpImageFilter::getGaussianDerivativeKernel(). - \param size : Size of the filter. - - \sa vpImageFilter::getGaussianDerivativeKernel() - */ + * Apply a size x 1 Derivative Filter in Y to an image pixel. + * + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param I : Image to filter. + * \param r : Coordinates (row) of the pixel. + * \param c : Coordinates (column) of the pixel. + * \param filter : Coefficients of the filter to be initialized using + * vpImageFilter::getGaussianDerivativeKernel(). + * \param size : Size of the filter. + * + * \sa vpImageFilter::getGaussianDerivativeKernel() + */ template static FilterType derivativeFilterY(const vpImage &I, unsigned int r, unsigned int c, const FilterType *filter, unsigned int size) { @@ -194,33 +420,33 @@ class VISP_EXPORT vpImageFilter } /*! - Apply a filter to an image. - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param I : Image to filter - \param If : Filtered image. - \param M : Filter kernel. - \param convolve : If true, perform a convolution otherwise a correlation. - - \note By default it performs a correlation: - \f[ - \textbf{I\_filtered} \left( u,v \right) = - \sum_{y=0}^{\textbf{kernel\_h}} - \sum_{x=0}^{\textbf{kernel\_w}} - \textbf{M} \left( x,y \right ) \times - \textbf{I} \left( - u-\frac{\textbf{kernel\_w}}{2}+x,v-\frac{\textbf{kernel\_h}}{2}+y \right) - \f] - The convolution is almost the same operation: - \f[ - \textbf{I\_filtered} \left( u,v \right) = - \sum_{y=0}^{\textbf{kernel\_h}} - \sum_{x=0}^{\textbf{kernel\_w}} - \textbf{M} \left( x,y \right ) \times - \textbf{I} \left( - u+\frac{\textbf{kernel\_w}}{2}-x,v+\frac{\textbf{kernel\_h}}{2}-y \right) - \f] - Only pixels in the input image fully covered by the kernel are considered. - */ + * Apply a filter to an image. + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param I : Image to filter + * \param If : Filtered image. + * \param M : Filter kernel. + * \param convolve : If true, perform a convolution otherwise a correlation. + * + * \note By default it performs a correlation: + * \f[ + * \textbf{I\_filtered} \left( u,v \right) = + * \sum_{y=0}^{\textbf{kernel\_h}} + * \sum_{x=0}^{\textbf{kernel\_w}} + * \textbf{M} \left( x,y \right ) \times + * \textbf{I} \left( + * u-\frac{\textbf{kernel\_w}}{2}+x,v-\frac{\textbf{kernel\_h}}{2}+y \right) + * \f] + * The convolution is almost the same operation: + * \f[ + * \textbf{I\_filtered} \left( u,v \right) = + * \sum_{y=0}^{\textbf{kernel\_h}} + * \sum_{x=0}^{\textbf{kernel\_w}} + * \textbf{M} \left( x,y \right ) \times + * \textbf{I} \left( + * u+\frac{\textbf{kernel\_w}}{2}-x,v+\frac{\textbf{kernel\_h}}{2}-y \right) + * \f] + * Only pixels in the input image fully covered by the kernel are considered. + */ template static void filter(const vpImage &I, vpImage &If, const vpArray2D &M, bool convolve = false) { @@ -265,17 +491,17 @@ class VISP_EXPORT vpImageFilter static void filter(const vpImage &I, vpImage &If, const vpArray2D &M, bool convolve = false) = delete; /*! - Apply a filter to an image: - \f[ - \textbf{I}_u = \textbf{M} \ast \textbf{I} \textbf{ and } \textbf{I}_v = - \textbf{M}^t \ast \textbf{I} \f] - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param I : Image to filter - \param Iu : Filtered image along the horizontal axis (u = columns). - \param Iv : Filtered image along the vertical axis (v = rows). - \param M : Filter kernel. - \param convolve : If true, perform a convolution otherwise a correlation. - */ + * Apply a filter to an image: + * \f[ + * \textbf{I}_u = \textbf{M} \ast \textbf{I} \textbf{ and } \textbf{I}_v = + * \textbf{M}^t \ast \textbf{I} \f] + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param I : Image to filter + * \param Iu : Filtered image along the horizontal axis (u = columns). + * \param Iv : Filtered image along the vertical axis (v = rows). + * \param M : Filter kernel. + * \param convolve : If true, perform a convolution otherwise a correlation. + */ template static void filter(const vpImage &I, vpImage &Iu, vpImage &Iv, const vpArray2D &M, bool convolve = false) @@ -333,13 +559,13 @@ class VISP_EXPORT vpImageFilter static void sepFilter(const vpImage &I, vpImage &If, const vpColVector &kernelH, const vpColVector &kernelV); /*! - Apply a separable filter. - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param I: The original image. - \param GI: The filtered image. - \param filter: The separable filter. - \param size: The size of the filter. - */ + * Apply a separable filter. + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param I: The original image. + * \param GI: The filtered image. + * \param filter: The separable filter. + * \param size: The size of the filter. + */ template static void filter(const vpImage &I, vpImage &GI, const FilterType *filter, unsigned int size) { @@ -761,17 +987,17 @@ class VISP_EXPORT vpImageFilter } /*! - Apply a Gaussian blur to an image. - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param I : Input image. - \param GI : Filtered image. - \param size : Filter size. This value should be odd. - \param sigma : Gaussian standard deviation. If it is equal to zero or - negative, it is computed from filter size as sigma = (size-1)/6. - \param normalize : Flag indicating whether to normalize the filter coefficients or not. - - \sa getGaussianKernel() to know which kernel is used. - */ + * Apply a Gaussian blur to an image. + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param I : Input image. + * \param GI : Filtered image. + * \param size : Filter size. This value should be odd. + * \param sigma : Gaussian standard deviation. If it is equal to zero or + * negative, it is computed from filter size as sigma = (size-1)/6. + * \param normalize : Flag indicating whether to normalize the filter coefficients or not. + * + * \sa getGaussianKernel() to know which kernel is used. + */ template static void gaussianBlur(const vpImage &I, vpImage &GI, unsigned int size = 7, FilterType sigma = 0., bool normalize = true) { @@ -787,12 +1013,12 @@ class VISP_EXPORT vpImageFilter static void gaussianBlur(const vpImage &I, vpImage &GI, unsigned int size = 7, double sigma = 0., bool normalize = true); /*! - Apply a 5x5 Gaussian filter to an image pixel. - - \param fr : Image to filter - \param r : coordinates (row) of the pixel - \param c : coordinates (column) of the pixel - */ + * Apply a 5x5 Gaussian filter to an image pixel. + * + * \param fr : Image to filter + * \param r : coordinates (row) of the pixel + * \param c : coordinates (column) of the pixel + */ template static double gaussianFilter(const vpImage &fr, unsigned int r, unsigned int c) { return (15.0 * fr[r][c] + 12.0 * (fr[r - 1][c] + fr[r][c - 1] + fr[r + 1][c] + fr[r][c + 1]) + @@ -808,21 +1034,21 @@ class VISP_EXPORT vpImageFilter static void getGaussYPyramidal(const vpImage &I, vpImage &GI); /*! - Return the coefficients \f$G_i\f$ of a Gaussian filter. - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param[out] filter : Pointer to the half size filter kernel that should refer to a - (size+1)/2 array. The first value refers to the central coefficient, the - next one to the right coefficients. Left coefficients could be deduced by - symmetry. - \param[in] size : Filter size. This value should be odd and positive. - \param[in] sigma : Gaussian standard deviation \f$ \sigma \f$. If it is equal to zero or negative, it is - computed from filter size as sigma = (size-1)/6. - \param[in] normalize : Flag indicating whether to normalize the filter coefficients or not. In that case \f$\Sigma G_i - = 1 \f$. - - The function computes the \e (size+1)/2 values of the Gaussian filter coefficients \f$ G_i \f$ as: - \f[ G_i = \frac{1}{\sigma \sqrt{2 \pi}} \exp{(-i^2 / (2. * \sigma^2))}\f] - */ + * Return the coefficients \f$G_i\f$ of a Gaussian filter. + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param[out] filter : Pointer to the half size filter kernel that should refer to a + * (size+1)/2 array. The first value refers to the central coefficient, the + * next one to the right coefficients. Left coefficients could be deduced by + * symmetry. + * \param[in] size : Filter size. This value should be odd and positive. + * \param[in] sigma : Gaussian standard deviation \f$ \sigma \f$. If it is equal to zero or negative, it is + * computed from filter size as sigma = (size-1)/6. + * \param[in] normalize : Flag indicating whether to normalize the filter coefficients or not. In that case + * \f$\Sigma G_i = 1 \f$. + * + * The function computes the \e (size+1)/2 values of the Gaussian filter coefficients \f$ G_i \f$ as: + * \f[ G_i = \frac{1}{\sigma \sqrt{2 \pi}} \exp{(-i^2 / (2. * \sigma^2))}\f] + */ template static void getGaussianKernel(FilterType *filter, unsigned int size, FilterType sigma = 0., bool normalize = true) { @@ -854,19 +1080,19 @@ class VISP_EXPORT vpImageFilter } /*! - Return the coefficients of a Gaussian derivative filter that may be used to - compute spatial image derivatives after applying a Gaussian blur. - - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param filter : Pointer to the filter kernel that should refer to a - (size+1)/2 array. The first value refers to the central coefficient, the - next one to the right coefficients. Left coefficients could be deduced by - symmetry. - \param size : Filter size. This value should be odd. - \param sigma : Gaussian standard deviation. If it is equal to zero or negative, it is - computed from filter size as sigma = (size-1)/6. - \param normalize : Flag indicating whether to normalize the filter coefficients or not. - */ + * Return the coefficients of a Gaussian derivative filter that may be used to + * compute spatial image derivatives after applying a Gaussian blur. + * + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param filter : Pointer to the filter kernel that should refer to a + * (size+1)/2 array. The first value refers to the central coefficient, the + * next one to the right coefficients. Left coefficients could be deduced by + * symmetry. + * \param size : Filter size. This value should be odd. + * \param sigma : Gaussian standard deviation. If it is equal to zero or negative, it is + * computed from filter size as sigma = (size-1)/6. + * \param normalize : Flag indicating whether to normalize the filter coefficients or not. + */ template static void getGaussianDerivativeKernel(FilterType *filter, unsigned int size, FilterType sigma = 0., bool normalize = true) { @@ -937,15 +1163,15 @@ class VISP_EXPORT vpImageFilter } /*! - Compute the gradient along X after applying a gaussian filter along Y. - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param I : Input image - \param dIx : Gradient along X. - \param gaussianKernel : Gaussian kernel which values should be computed using vpImageFilter::getGaussianKernel(). - \param gaussianDerivativeKernel : Gaussian derivative kernel which values should be computed using - vpImageFilter::getGaussianDerivativeKernel(). - \param size : Size of the Gaussian and Gaussian derivative kernels. - */ + * Compute the gradient along X after applying a gaussian filter along Y. + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param I : Input image + * \param dIx : Gradient along X. + * \param gaussianKernel : Gaussian kernel which values should be computed using vpImageFilter::getGaussianKernel(). + * \param gaussianDerivativeKernel : Gaussian derivative kernel which values should be computed using + * vpImageFilter::getGaussianDerivativeKernel(). + * \param size : Size of the Gaussian and Gaussian derivative kernels. + */ template static void getGradXGauss2D(const vpImage &I, vpImage &dIx, const FilterType *gaussianKernel, const FilterType *gaussianDerivativeKernel, unsigned int size) @@ -999,15 +1225,15 @@ class VISP_EXPORT vpImageFilter } /*! - Compute the gradient along Y after applying a gaussian filter along X. - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param I : Input image - \param dIy : Gradient along Y. - \param gaussianKernel : Gaussian kernel which values should be computed using vpImageFilter::getGaussianKernel(). - \param gaussianDerivativeKernel : Gaussian derivative kernel which values should be computed using - vpImageFilter::getGaussianDerivativeKernel(). - \param size : Size of the Gaussian and Gaussian derivative kernels. - */ + * Compute the gradient along Y after applying a gaussian filter along X. + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param I : Input image + * \param dIy : Gradient along Y. + * \param gaussianKernel : Gaussian kernel which values should be computed using vpImageFilter::getGaussianKernel(). + * \param gaussianDerivativeKernel : Gaussian derivative kernel which values should be computed using + * vpImageFilter::getGaussianDerivativeKernel(). + * \param size : Size of the Gaussian and Gaussian derivative kernels. + */ template static void getGradYGauss2D(const vpImage &I, vpImage &dIy, const FilterType *gaussianKernel, const FilterType *gaussianDerivativeKernel, unsigned int size) @@ -1068,12 +1294,12 @@ class VISP_EXPORT vpImageFilter } /*! - Get Sobel kernel for X-direction. - \tparam FilterType: Either float, to accelerate the computation time, or double, to have greater precision. - \param filter : Pointer to a double array already allocated. - \param size : Kernel size computed as: kernel_size = size*2 + 1 (max size is 20). - \return Scaling factor to normalize the Sobel kernel. - */ + * Get Sobel kernel for X-direction. + * \tparam FilterType: Either float, to accelerate the computation time, or double, to have greater precision. + * \param filter : Pointer to a double array already allocated. + * \param size : Kernel size computed as: kernel_size = size*2 + 1 (max size is 20). + * \return Scaling factor to normalize the Sobel kernel. + */ template inline static FilterType getSobelKernelX(FilterType *filter, unsigned int size) { @@ -1089,12 +1315,12 @@ class VISP_EXPORT vpImageFilter } /*! - Get Sobel kernel for Y-direction. - \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. - \param filter : Pointer to a double array already allocated. - \param size : Kernel size computed as: kernel_size = size*2 + 1 (max size is 20). - \return Scaling factor to normalize the Sobel kernel. - */ + * Get Sobel kernel for Y-direction. + * \tparam FilterType : Either float, to accelerate the computation time, or double, to have greater precision. + * \param filter : Pointer to a double array already allocated. + * \param size : Kernel size computed as: kernel_size = size*2 + 1 (max size is 20). + * \return Scaling factor to normalize the Sobel kernel. + */ template inline static FilterType getSobelKernelY(FilterType *filter, unsigned int size) { @@ -1151,232 +1377,6 @@ class VISP_EXPORT vpImageFilter return scale; } -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) - static float computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *p_cv_dIx, const cv::Mat *p_cv_dIy, - float &lowerThresh, const unsigned int &gaussianKernelSize = 5, - const float &gaussianStdev = 2.f, const unsigned int &apertureGradient = 3, - const float &lowerThresholdRatio = 0.6, const float &upperThresholdRatio = 0.8, - const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING); - - static void computePartialDerivatives(const cv::Mat &cv_I, - cv::Mat &cv_dIx, cv::Mat &cv_dIy, - const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, - const unsigned int &gaussianKernelSize = 5, const float &gaussianStdev = 2.f, - const unsigned int &apertureGradient = 3, - const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING); -#endif - - /** - * \brief Compute the partial derivatives (i.e. horizontal and vertical gradients) of the input image. - * - * \tparam ImageType Either unsigned char, float or double - * \tparam FilterType Either float or double. - * \param[in] I The input image we want the partial derivatives. - * \param[out] dIx The horizontal partial derivative, i.e. horizontal gradient. - * \param[out] dIy The vertical partial derivative, i.e. vertical gradient. - * \param[in] computeDx Idicate if we must compute the horizontal gradient. - * \param[in] computeDy Idicate if we must compute the vertical gradient. - * \param[in] normalize Idicate if we must normalize the gradient filters. - * \param[in] gaussianKernelSize The size of the kernel of the Gaussian filter used to blur the image. - * \param[in] gaussianStdev The standard deviation of the Gaussian filter used to blur the image. - * \param[in] apertureGradient The size of the kernel of the gradient filter. - * \param[in] filteringType The type of filters to apply to compute the gradients. - * \param[in] backend The type of backend to use to compute the gradients. - */ - template - inline static void computePartialDerivatives(const vpImage &I, - vpImage &dIx, vpImage &dIy, - const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, - const unsigned int &gaussianKernelSize = 5, const FilterType &gaussianStdev = 2.f, - const unsigned int &apertureGradient = 3, - const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING, - const vpCannyBackendType &backend = CANNY_VISP_BACKEND) - { - if (backend == CANNY_OPENCV_BACKEND) { -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) - cv::Mat cv_I, cv_dIx, cv_dIy; - vpImageConvert::convert(I, cv_I); - computePartialDerivatives(cv_I, cv_dIx, cv_dIy, computeDx, computeDy, normalize, gaussianKernelSize, - gaussianStdev, apertureGradient, filteringType); - if (computeDx) { - vpImageConvert::convert(cv_dIx, dIx); - } - if (computeDy) { - vpImageConvert::convert(cv_dIy, dIy); - } -#else - throw(vpException(vpException::badValue, "You need to compile ViSP with OpenCV to use CANNY_OPENCV_BACKEND")); -#endif - } - else { - if (filteringType == CANNY_GBLUR_SCHARR_FILTERING || filteringType == CANNY_GBLUR_SOBEL_FILTERING) { - dIx.resize(I.getHeight(), I.getWidth()); - dIy.resize(I.getHeight(), I.getWidth()); - - // Computing the Gaussian blur + gradients of the image - vpImage Iblur; - vpImageFilter::gaussianBlur(I, Iblur, gaussianKernelSize, gaussianStdev); - - vpArray2D gradientFilterX(apertureGradient, apertureGradient); // Gradient filter along the X-axis - vpArray2D gradientFilterY(apertureGradient, apertureGradient); // Gradient filter along the Y-axis - - // Helper to apply the scale to the raw values of the filters - auto scaleFilter = [](vpArray2D &filter, const float &scale) { - for (unsigned int r = 0; r < filter.getRows(); r++) { - for (unsigned int c = 0; c < filter.getCols(); c++) { - filter[r][c] = filter[r][c] * scale; - } - }}; - - // Scales to apply to the filters to get a normalized gradient filter that gives a gradient - // between 0 and 255 for an vpImage - float scaleX = 1.f; - float scaleY = 1.f; - - if (filteringType == CANNY_GBLUR_SOBEL_FILTERING) { - if (computeDx) { - scaleX = vpImageFilter::getSobelKernelX(gradientFilterX.data, (apertureGradient - 1)/2); - } - if (computeDy) { - scaleY = vpImageFilter::getSobelKernelY(gradientFilterY.data, (apertureGradient - 1)/2); - } - } - else if (filteringType == CANNY_GBLUR_SCHARR_FILTERING) { - if (computeDx) { - scaleX = vpImageFilter::getScharrKernelX(gradientFilterX.data, (apertureGradient - 1)/2); - } - if (computeDy) { - scaleY = vpImageFilter::getScharrKernelY(gradientFilterY.data, (apertureGradient - 1)/2); - } - } - - // Scale the gradient filters to have a normalized gradient filter - if (normalize) { - if (computeDx) { - scaleFilter(gradientFilterX, scaleX); - } - if (computeDy) { - scaleFilter(gradientFilterY, scaleY); - } - } - - // Apply the gradient filters to get the gradients - if (computeDx) { - vpImageFilter::filter(Iblur, dIx, gradientFilterX); - } - - if (computeDy) { - vpImageFilter::filter(Iblur, dIy, gradientFilterY); - } - } - else { - std::string errMsg = "[vpImageFilter::computePartialDerivatives] Filtering + gradient method \""; - errMsg += vpCannyFilteringAndGradientTypeToString(filteringType); - errMsg += "\" is not implemented yet\n"; - throw(vpException(vpException::notImplementedError, errMsg)); - } - } - } - - template - inline static void computePartialDerivatives(const vpImage &I, - vpImage &dIx, vpImage &dIy, - const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, - const unsigned int &gaussianKernelSize = 5, const FilterType &gaussianStdev = 2.f, - const unsigned int &apertureGradient = 3, - const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING, - const vpCannyBackendType &backend = CANNY_VISP_BACKEND) = delete; - - template - inline static void computePartialDerivatives(const vpImage &I, - vpImage &dIx, vpImage &dIy, - const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, - const unsigned int &gaussianKernelSize = 5, const unsigned char &gaussianStdev = 2.f, - const unsigned int &apertureGradient = 3, - const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING, - const vpCannyBackendType &backend = CANNY_VISP_BACKEND) = delete; - - template - inline static void computePartialDerivatives(const vpImage &I, - vpImage &dIx, vpImage &dIy, - const bool &computeDx = true, const bool &computeDy = true, const bool &normalize = true, - const unsigned int gaussianKernelSize = 5, const vpRGBa gaussianStdev = vpRGBa(), - const unsigned int apertureGradient = 3, - const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING, - const vpCannyBackendType &backend = CANNY_VISP_BACKEND) = delete; - - /** - * \brief Compute the upper Canny edge filter threshold, using Gaussian blur + Sobel or + Scharr operators to compute - * the gradient of the image. - * - * \tparam OutType : Either float, to accelerate the computation time, or double, to have greater precision. - * \param[in] I : The gray-scale image, in ViSP format. - * \param[in] p_dIx : If different from nullptr, must contain the gradient of the image with regard to the horizontal axis. - * \param[in] p_dIy : If different from nullptr, must contain the gradient of the image with regard to the vertical axis. - * \param[in] lowerThresh : Canny lower threshold. - * \param[in] gaussianFilterSize : The size of the mask of the Gaussian filter to apply (an odd number). - * \param[in] gaussianStdev : The standard deviation of the Gaussian filter to apply. - * \param[in] apertureGradient : Size of the mask for the Sobel operator (odd number). - * \param[in] lowerThresholdRatio : The ratio of the upper threshold the lower threshold must be equal to. - * \param[in] upperThresholdRatio : The ratio of pixels whose absolute gradient Gabs is lower or equal to define - * the upper threshold. - * \param[in] filteringType : The gradient filter to apply to compute the gradient, if \b p_dIx and \b p_dIy are - * nullptr. - * \return The upper Canny edge filter threshold. - */ - template - inline static float computeCannyThreshold(const vpImage &I, float &lowerThresh, - const vpImage *p_dIx = nullptr, const vpImage *p_dIy = nullptr, - const unsigned int &gaussianKernelSize = 5, - const OutType &gaussianStdev = 2.f, const unsigned int &apertureGradient = 3, - const float &lowerThresholdRatio = 0.6, const float &upperThresholdRatio = 0.8, - const vpCannyFilteringAndGradientType &filteringType = CANNY_GBLUR_SOBEL_FILTERING) - { - double w = I.getWidth(); - double h = I.getHeight(); - - vpImage dI(h, w); - vpImage dIx(h, w), dIy(h, w); - if (p_dIx != nullptr && p_dIy != nullptr) { - dIx = *p_dIx; - dIy = *p_dIy; - } - else { - computePartialDerivatives(I, dIx, dIy, true, true, true, gaussianKernelSize, gaussianStdev, - apertureGradient, filteringType); - } - - // Computing the absolute gradient of the image G = |dIx| + |dIy| - for (unsigned int r = 0; r < h; r++) { - for (unsigned int c = 0; c < w; c++) { - float dx = (float)dIx[r][c]; - float dy = (float)dIy[r][c]; - float gradient = std::abs(dx) + std::abs(dy); - float gradientClamped = std::min(gradient, (float)std::numeric_limits::max()); - dI[r][c] = gradientClamped; - } - } - - // Compute the histogram - vpHistogram hist; - const unsigned int nbBins = 256; - hist.calculate(dI, nbBins); - float accu = 0; - float t = (float)(upperThresholdRatio * w * h); - float bon = 0; - for (unsigned int i = 0; i < nbBins; i++) { - float tf = hist[i]; - accu = accu + tf; - if (accu > t) { - bon = (float)i; - break; - } - } - float upperThresh = std::max(bon, 1.f); - lowerThresh = lowerThresholdRatio * bon; - return upperThresh; - } - #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) static float median(const cv::Mat &cv_I); static float median(const vpImage &Isrc); diff --git a/modules/core/include/visp3/core/vpImagePoint.h b/modules/core/include/visp3/core/vpImagePoint.h index 9618b273e4..f1547df123 100644 --- a/modules/core/include/visp3/core/vpImagePoint.h +++ b/modules/core/include/visp3/core/vpImagePoint.h @@ -85,12 +85,12 @@ class VISP_EXPORT vpImagePoint Default constructor that initialize the coordinates of the image point to zero. */ - inline vpImagePoint() : i(0), j(0) {} + inline vpImagePoint() : i(0), j(0) { } /*! Default constructor that initialize the coordinates of the image thanks to the parameters \f$ ii \f$ and \f$ jj \f$. */ - inline vpImagePoint(double ii, double jj) : i(ii), j(jj) {} + inline vpImagePoint(double ii, double jj) : i(ii), j(jj) { } /*! Copy constructor. @@ -98,9 +98,9 @@ class VISP_EXPORT vpImagePoint \param ip : An image point. */ - inline vpImagePoint(const vpImagePoint &ip) : i(ip.i), j(ip.j) {} + inline vpImagePoint(const vpImagePoint &ip) : i(ip.i), j(ip.j) { } //! Destructor. - inline virtual ~vpImagePoint() {} + inline virtual ~vpImagePoint() { } /*! @@ -163,8 +163,8 @@ class VISP_EXPORT vpImagePoint { return ((end.get_j() >= start.get_j() && end.get_j() >= this->j && this->j >= start.get_j()) || (end.get_j() <= start.get_j() && end.get_j() <= this->j && this->j <= start.get_j())) && - ((end.get_i() >= start.get_i() && end.get_i() >= this->i && this->i >= start.get_i()) || - (end.get_i() <= start.get_i() && end.get_i() <= this->i && this->i <= start.get_i())); + ((end.get_i() >= start.get_i() && end.get_i() >= this->i && this->i >= start.get_i()) || + (end.get_i() <= start.get_i() && end.get_i() <= this->i && this->i <= start.get_i())); } /*! @@ -217,18 +217,11 @@ class VISP_EXPORT vpImagePoint const double line_slope = (end.get_i() - start.get_i()) / (end.get_j() - start.get_j()); if (fabs(end.get_j() - this->j) > fabs(end.get_i() - this->i)) { double j_ = (end.get_j() > this->j ? this->j + 1 : this->j - 1); -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) - return {end.get_i() - line_slope * (end.get_j() - j_), j_}; -#else - return vpImagePoint(end.get_i() - line_slope * (end.get_j() - j_), j_); -#endif - } else { + return { end.get_i() - line_slope * (end.get_j() - j_), j_ }; + } + else { double i_ = (end.get_i() > this->i ? this->i + 1 : this->i - 1); -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) - return {i_, end.get_j() - ((end.get_i() - i_) / line_slope)}; -#else - return vpImagePoint(i_, end.get_j() - ((end.get_i() - i_) / line_slope)); -#endif + return { i_, end.get_j() - ((end.get_i() - i_) / line_slope) }; } } @@ -241,7 +234,7 @@ class VISP_EXPORT vpImagePoint this->j = ip.j; return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + /*! Move operator. */ @@ -251,7 +244,6 @@ class VISP_EXPORT vpImagePoint this->j = ip.j; return *this; } -#endif vpImagePoint &operator+=(const vpImagePoint &ip); diff --git a/modules/core/include/visp3/core/vpLinProg.h b/modules/core/include/visp3/core/vpLinProg.h index 38586d341b..8483699958 100644 --- a/modules/core/include/visp3/core/vpLinProg.h +++ b/modules/core/include/visp3/core/vpLinProg.h @@ -61,59 +61,55 @@ class VISP_EXPORT vpLinProg { public: -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! - Used to pass a list of bounded variables to solveLP(), as a list of (index, bound). - - The type is compatible with C++11's braced initialization. - Construction can be done in the call to solveLP or before, as shown in this example: - - \f$\begin{array}{lll} - (x,y,z) = & \arg\min & -2x -3y -4z\\ - & \text{s.t.}& 3x + 2y + z \leq 10\\ - & \text{s.t.}& 2x + 5y + 3z \leq 15\\ - & \text{s.t.}& x, y, z \geq 0\\ - & \text{s.t.}& z \leq 6\end{array}\f$ - - Here the lower bound is built explicitly while the upper one is built during the call to solveLP(): - - \warning This function is only available if c++11 or higher is activated during compilation. Configure ViSP using - cmake -DUSE_CXX_STANDARD=11. - - \code - #include - - int main() - { - vpColVector c(3), x; - vpMatrix C(2, 3); - vpColVector d(2); - c[0] = -2; c[1] = -3; c[2] = -4; - C[0][0] = 3; C[0][1] = 2; C[0][2] = 1; d[0] = 10; - C[1][0] = 2; C[1][1] = 5; C[1][2] = 3; d[1] = 15; - - // build lower bounds explicitly as a std::vector of std::pair - std::vector lower_bound; - for(unsigned int i = 0; i < 3; ++i) - { - vpLinProg::BoundedIndex bound; - bound.first = i; // index - bound.second = 0; // lower bound for this index - lower_bound.push_back(bound); - } - - if(vpLinProg::solveLP(c, vpMatrix(0,0), vpColVector(0), C, d, x, - lower_bound, - {{2,6}})) // upper bound is passed with braced initialization - { - std::cout << "x: " << x.t() << std::endl; - std::cout << "cost: " << c.t()*x << std::endl; - } - } - \endcode - - \sa solveLP() - */ + * Used to pass a list of bounded variables to solveLP(), as a list of (index, bound). + * + * The type is compatible with C++11's braced initialization. + * Construction can be done in the call to solveLP or before, as shown in this example: + * + * \f$\begin{array}{lll} + * (x,y,z) = & \arg\min & -2x -3y -4z\\ + * & \text{s.t.}& 3x + 2y + z \leq 10\\ + * & \text{s.t.}& 2x + 5y + 3z \leq 15\\ + * & \text{s.t.}& x, y, z \geq 0\\ + * & \text{s.t.}& z \leq 6\end{array}\f$ + * + * Here the lower bound is built explicitly while the upper one is built during the call to solveLP(): + * + * \code + * #include + * + * int main() + * { + * vpColVector c(3), x; + * vpMatrix C(2, 3); + * vpColVector d(2); + * c[0] = -2; c[1] = -3; c[2] = -4; + * C[0][0] = 3; C[0][1] = 2; C[0][2] = 1; d[0] = 10; + * C[1][0] = 2; C[1][1] = 5; C[1][2] = 3; d[1] = 15; + * + * // build lower bounds explicitly as a std::vector of std::pair + * std::vector lower_bound; + * for(unsigned int i = 0; i < 3; ++i) + * { + * vpLinProg::BoundedIndex bound; + * bound.first = i; // index + * bound.second = 0; // lower bound for this index + * lower_bound.push_back(bound); + * } + * + * if(vpLinProg::solveLP(c, vpMatrix(0,0), vpColVector(0), C, d, x, + * lower_bound, + * {{2,6}})) // upper bound is passed with braced initialization + * { + * std::cout << "x: " << x.t() << std::endl; + * std::cout << "cost: " << c.t()*x << std::endl; + * } + * } + * \endcode + * + * \sa solveLP() + */ typedef std::pair BoundedIndex; /** @name Solvers */ @@ -125,7 +121,6 @@ class VISP_EXPORT vpLinProg const double &tol = 1e-6); //@} -#endif /** @name Dimension reduction for equality constraints */ //@{ @@ -137,13 +132,13 @@ class VISP_EXPORT vpLinProg /** @name Vector and equality checking */ //@{ /*! - Check if all elements of \f$x\f$ are near zero. - - \param x : vector to be checked - \param tol : tolerance - - \return True if \f$\forall i, |\mathbf{x}_i| < \text{~tol} \f$ - */ + * Check if all elements of \f$x\f$ are near zero. + * + * \param x : vector to be checked + * \param tol : tolerance + * + * \return True if \f$\forall i, |\mathbf{x}_i| < \text{~tol} \f$ + */ static bool allZero(const vpColVector &x, const double &tol = 1e-6) { for (unsigned int i = 0; i < x.getRows(); ++i) { @@ -154,15 +149,15 @@ class VISP_EXPORT vpLinProg } /*! - Check if \f$\mathbf{A}\mathbf{x}\f$ is near \f$\mathbf{b}\f$. - - \param A : matrix (dimension m x n) - \param x : vector (dimension n) - \param b : vector (dimension m) - \param tol : tolerance - - \return True if \f$ \forall i, |\mathbf{A}_i\mathbf{x} - \mathbf{b}_i| < \text{~tol}\f$ - */ + * Check if \f$\mathbf{A}\mathbf{x}\f$ is near \f$\mathbf{b}\f$. + * + * \param A : matrix (dimension m x n) + * \param x : vector (dimension n) + * \param b : vector (dimension m) + * \param tol : tolerance + * + * \return True if \f$ \forall i, |\mathbf{A}_i\mathbf{x} - \mathbf{b}_i| < \text{~tol}\f$ + */ static bool allClose(const vpMatrix &A, const vpColVector &x, const vpColVector &b, const double &tol = 1e-6) { for (unsigned int i = 0; i < b.getRows(); ++i) { @@ -173,14 +168,14 @@ class VISP_EXPORT vpLinProg } /*! - Check if all elements of \f$\mathbf{C}\mathbf{x} - \mathbf{d}\f$ are lesser or equal to threshold. - \param C : matrix (dimension m x n) - \param x : vector (dimension n) - \param d : vector (dimension m) - \param thr : threshold - - \return True if \f$ \forall i, \mathbf{C}_i\mathbf{x} - \mathbf{d}_i \leq \text{~thr}\f$ - */ + * Check if all elements of \f$\mathbf{C}\mathbf{x} - \mathbf{d}\f$ are lesser or equal to threshold. + * \param C : matrix (dimension m x n) + * \param x : vector (dimension n) + * \param d : vector (dimension m) + * \param thr : threshold + * + * \return True if \f$ \forall i, \mathbf{C}_i\mathbf{x} - \mathbf{d}_i \leq \text{~thr}\f$ + */ static bool allLesser(const vpMatrix &C, const vpColVector &x, const vpColVector &d, const double &thr = 1e-6) { for (unsigned int i = 0; i < d.getRows(); ++i) { @@ -191,13 +186,13 @@ class VISP_EXPORT vpLinProg } /*! - Check if all elements of \f$\mathbf{x}\f$ are lesser or equal to threshold. - - \param x : vector (dimension n) - \param thr : threshold - - \return True if \f$ \forall i, \mathbf{x}_i \leq \text{~thr}\f$ - */ + * Check if all elements of \f$\mathbf{x}\f$ are lesser or equal to threshold. + * + * \param x : vector (dimension n) + * \param thr : threshold + * + * \return True if \f$ \forall i, \mathbf{x}_i \leq \text{~thr}\f$ + */ static bool allLesser(const vpColVector &x, const double &thr = 1e-6) { for (unsigned int i = 0; i < x.getRows(); ++i) { @@ -208,13 +203,13 @@ class VISP_EXPORT vpLinProg } /*! - Check if all elements of \f$\mathbf{x}\f$ are greater or equal to threshold. - - \param x : vector (dimension n) - \param thr : threshold - - \return True if \f$ \forall i, \mathbf{x}_i \geq \text{~thr}\f$ - */ + * Check if all elements of \f$\mathbf{x}\f$ are greater or equal to threshold. + * + * \param x : vector (dimension n) + * \param thr : threshold + * + * \return True if \f$ \forall i, \mathbf{x}_i \geq \text{~thr}\f$ + */ static bool allGreater(const vpColVector &x, const double &thr = 1e-6) { for (unsigned int i = 0; i < x.getRows(); ++i) { @@ -225,4 +220,4 @@ class VISP_EXPORT vpLinProg } //@} }; -#endif // vpLinProgh +#endif diff --git a/modules/core/include/visp3/core/vpMatrix.h b/modules/core/include/visp3/core/vpMatrix.h index f1dac9443c..4048374153 100644 --- a/modules/core/include/visp3/core/vpMatrix.h +++ b/modules/core/include/visp3/core/vpMatrix.h @@ -116,10 +116,8 @@ int main() int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix M( {-1, -2, -3}, {4, 5.5, 6.0f} ); std::cout << "M:\n" << M << std::endl; -#endif } \endcode You can also create and initialize a matrix this way: @@ -128,9 +126,7 @@ int main() int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix M(2, 3, {-1, -2, -3, 4, 5.5, 6.0f} ); -#endif } \endcode @@ -138,10 +134,8 @@ int main() \code int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix M; M = { {-1, -2, -3}, {4, 5.5, 6.0f} }; -#endif } \endcode @@ -201,12 +195,10 @@ vpMatrix M(R); vpMatrix(const vpMatrix &A) : vpArray2D(A) { } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix(vpMatrix &&A); explicit vpMatrix(const std::initializer_list &list); explicit vpMatrix(unsigned int nrows, unsigned int ncols, const std::initializer_list &list); explicit vpMatrix(const std::initializer_list > &lists); -#endif /*! Removes all elements from the matrix (which are destroyed), @@ -279,13 +271,11 @@ vpMatrix M(R); vpMatrix &operator<<(double val); vpMatrix &operator,(double val); vpMatrix &operator=(const vpArray2D &A); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix &operator=(const vpMatrix &A); vpMatrix &operator=(vpMatrix &&A); vpMatrix &operator=(const std::initializer_list &list); vpMatrix &operator=(const std::initializer_list > &lists); -#endif vpMatrix &operator=(double x); //@} diff --git a/modules/core/include/visp3/core/vpPoseVector.h b/modules/core/include/visp3/core/vpPoseVector.h index fb59bf63f2..0491d38df4 100644 --- a/modules/core/include/visp3/core/vpPoseVector.h +++ b/modules/core/include/visp3/core/vpPoseVector.h @@ -137,11 +137,8 @@ class vpRowVector; { vpTranslationVector t; vpThetaUVector tu; - - #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) t = { 0.1, 0.2, 0.3 }; tu = { M_PI, M_PI_2, M_PI_4 }; - #endif vpPoseVector pose(t, tu); } \endcode diff --git a/modules/core/include/visp3/core/vpQuadProg.h b/modules/core/include/visp3/core/vpQuadProg.h index e63d638631..138f431316 100644 --- a/modules/core/include/visp3/core/vpQuadProg.h +++ b/modules/core/include/visp3/core/vpQuadProg.h @@ -31,8 +31,8 @@ * Quadratic Programming */ -#ifndef vpQuadProgh -#define vpQuadProgh +#ifndef _vpQuadProg_h_ +#define _vpQuadProg_h_ #include #include @@ -42,34 +42,33 @@ #include /*! - \file vpQuadProg.h - \brief Implementation of Quadratic Program with Active Sets. -*/ + * \file vpQuadProg.h + * \brief Implementation of Quadratic Program with Active Sets. + */ /*! - \class vpQuadProg - \ingroup group_core_optim - \brief This class provides a solver for Quadratic Programs. - - The cost function is written under the form \f$ \min ||\mathbf{Q}\mathbf{x} - \mathbf{r}||^2\f$. - - If a cost function is written under the canonical form \f$\min \frac{1}{2}\mathbf{x}^T\mathbf{H}\mathbf{x} + - \mathbf{c}^T\mathbf{x}\f$ then fromCanonicalCost() can be used to retrieve Q and r from H and c. - - Equality constraints are solved through projection into the kernel. - - Inequality constraints are solved with active sets. - - In order to be used sequentially, the decomposition of the equality constraint may be stored. - The last active set is always stored and used to warm start the next call. - - \warning The solvers are only available if c++11 or higher is activated during build. - Configure ViSP using cmake -DUSE_CXX_STANDARD=11. -*/ + * \class vpQuadProg + * \ingroup group_core_optim + * \brief This class provides a solver for Quadratic Programs. + * + * The cost function is written under the form \f$ \min ||\mathbf{Q}\mathbf{x} - \mathbf{r}||^2\f$. + * + * If a cost function is written under the canonical form \f$\min \frac{1}{2}\mathbf{x}^T\mathbf{H}\mathbf{x} + + * \mathbf{c}^T\mathbf{x}\f$ then fromCanonicalCost() can be used to retrieve Q and r from H and c. + * + * Equality constraints are solved through projection into the kernel. + * + * Inequality constraints are solved with active sets. + * + * In order to be used sequentially, the decomposition of the equality constraint may be stored. + * The last active set is always stored and used to warm start the next call. + * + * \warning The solvers are only available if c++11 or higher is activated during build. + * Configure ViSP using cmake -DUSE_CXX_STANDARD=11. + */ class VISP_EXPORT vpQuadProg { public: -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /** @name Instantiated solvers */ //@{ bool solveQPe(const vpMatrix &Q, const vpColVector &r, vpColVector &x, const double &tol = 1e-6) const; @@ -84,9 +83,10 @@ class VISP_EXPORT vpQuadProg /** @name Managing sequential calls to solvers */ //@{ bool setEqualityConstraint(const vpMatrix &A, const vpColVector &b, const double &tol = 1e-6); + /*! - Resets the active set that was found by a previous call to solveQP() or solveQPi(), if any. - */ + * Resets the active set that was found by a previous call to solveQP() or solveQPi(), if any. + */ void resetActiveSet() { active.clear(); } //@} @@ -97,20 +97,23 @@ class VISP_EXPORT vpQuadProg protected: /*! - Active set from the last call to solveQP() or solveQPi(). Used for warm starting the next call. - */ + * Active set from the last call to solveQP() or solveQPi(). Used for warm starting the next call. + */ std::vector active; + /*! - Inactive set from the last call to solveQP() or solveQPi(). Used for warm starting the next call. - */ + * Inactive set from the last call to solveQP() or solveQPi(). Used for warm starting the next call. + */ std::vector inactive; + /*! - Stored particular solution from the last call to setEqualityConstraint(). - */ + * Stored particular solution from the last call to setEqualityConstraint(). + */ vpColVector x1; + /*! - Stored projection to the kernel from the last call to setEqualityConstraint(). - */ + * Stored projection to the kernel from the last call to setEqualityConstraint(). + */ vpMatrix Z; static vpColVector solveSVDorQR(const vpMatrix &A, const vpColVector &b); @@ -119,20 +122,20 @@ class VISP_EXPORT vpQuadProg const double &tol = 1e-6); /*! - Performs a dimension check of passed QP matrices and vectors. - - If any inconsistency is detected, displays a summary and throws an exception. - - \param Q : cost matrix (dimension c x n) - \param r : cost vector (dimension c) - \param A : pointer to the equality matrix (if any, dimension m x n) - \param b : pointer to the equality vector (if any, dimension m) - \param C : pointer to the inequality matrix (if any, dimension p x n) - \param d : pointer to the inequality vector (if any, dimension p) - \param fct : name of the solver that called this function - - \return the dimension of the search space. - */ + * Performs a dimension check of passed QP matrices and vectors. + * + * If any inconsistency is detected, displays a summary and throws an exception. + * + * \param Q : cost matrix (dimension c x n) + * \param r : cost vector (dimension c) + * \param A : pointer to the equality matrix (if any, dimension m x n) + * \param b : pointer to the equality vector (if any, dimension m) + * \param C : pointer to the inequality matrix (if any, dimension p x n) + * \param d : pointer to the inequality vector (if any, dimension p) + * \param fct : name of the solver that called this function + * + * \return the dimension of the search space. + */ static unsigned int checkDimensions(const vpMatrix &Q, const vpColVector &r, const vpMatrix *A, const vpColVector *b, const vpMatrix *C, const vpColVector *d, const std::string fct) { @@ -144,7 +147,7 @@ class VISP_EXPORT vpQuadProg if ((Ab && n != A->getCols()) || (Cd && n != C->getCols()) || (Ab && A->getRows() != b->getRows()) || (Cd && C->getRows() != d->getRows()) || Q.getRows() != r.getRows()) { std::cout << "vpQuadProg::" << fct << ": wrong dimension\n" - << "Q: " << Q.getRows() << "x" << Q.getCols() << " - r: " << r.getRows() << std::endl; + << "Q: " << Q.getRows() << "x" << Q.getCols() << " - r: " << r.getRows() << std::endl; if (Ab) std::cout << "A: " << A->getRows() << "x" << A->getCols() << " - b: " << b->getRows() << std::endl; if (Cd) @@ -153,6 +156,5 @@ class VISP_EXPORT vpQuadProg } return n; } -#endif }; #endif diff --git a/modules/core/include/visp3/core/vpQuaternionVector.h b/modules/core/include/visp3/core/vpQuaternionVector.h index 93402d38b4..af3fd9e751 100644 --- a/modules/core/include/visp3/core/vpQuaternionVector.h +++ b/modules/core/include/visp3/core/vpQuaternionVector.h @@ -141,10 +141,8 @@ class VISP_EXPORT vpQuaternionVector : public vpRotationVector vpQuaternionVector operator*(const vpQuaternionVector &rq) const; vpQuaternionVector operator/(double l) const; vpQuaternionVector &operator=(const vpColVector &q); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpQuaternionVector &operator=(const vpQuaternionVector &q) = default; vpQuaternionVector &operator=(const std::initializer_list &list); -#endif vpQuaternionVector conjugate() const; vpQuaternionVector inverse() const; diff --git a/modules/core/include/visp3/core/vpRGBa.h b/modules/core/include/visp3/core/vpRGBa.h index f44bf0e735..b36d8af960 100644 --- a/modules/core/include/visp3/core/vpRGBa.h +++ b/modules/core/include/visp3/core/vpRGBa.h @@ -67,7 +67,7 @@ class VISP_EXPORT vpRGBa Build a black value. */ - inline vpRGBa() : R(0), G(0), B(0), A(vpRGBa::alpha_default) {} + inline vpRGBa() : R(0), G(0), B(0), A(vpRGBa::alpha_default) { } /*! Constructor. @@ -81,8 +81,7 @@ class VISP_EXPORT vpRGBa */ inline vpRGBa(unsigned char r, unsigned char g, unsigned char b, unsigned char a = vpRGBa::alpha_default) : R(r), G(g), B(b), A(a) - { - } + { } /*! Constructor. @@ -91,12 +90,12 @@ class VISP_EXPORT vpRGBa \param v : Value to set. */ - inline vpRGBa(unsigned char v) : R(v), G(v), B(v), A(v) {} + inline vpRGBa(unsigned char v) : R(v), G(v), B(v), A(v) { } /*! Copy constructor. */ - inline vpRGBa(const vpRGBa &v) : R(v.R), G(v.G), B(v.B), A(v.A) {} + inline vpRGBa(const vpRGBa &v) : R(v.R), G(v.G), B(v.B), A(v.A) { } /*! Create a RGBa value from a 4 dimension column vector. @@ -115,9 +114,7 @@ class VISP_EXPORT vpRGBa vpRGBa &operator=(const unsigned char &v); vpRGBa &operator=(const vpRGBa &v); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRGBa &operator=(const vpRGBa &&v); -#endif vpRGBa &operator=(const vpColVector &v); bool operator==(const vpRGBa &v) const; bool operator!=(const vpRGBa &v) const; diff --git a/modules/core/include/visp3/core/vpRGBf.h b/modules/core/include/visp3/core/vpRGBf.h index 1db9f4b63e..ba03ebbc21 100644 --- a/modules/core/include/visp3/core/vpRGBf.h +++ b/modules/core/include/visp3/core/vpRGBf.h @@ -61,7 +61,7 @@ class VISP_EXPORT vpRGBf Build a black value. */ - inline vpRGBf() : R(0), G(0), B(0) {} + inline vpRGBf() : R(0), G(0), B(0) { } /*! Constructor. @@ -74,8 +74,7 @@ class VISP_EXPORT vpRGBf */ inline vpRGBf(float r, float g, float b) : R(r), G(g), B(b) - { - } + { } /*! Constructor. @@ -84,12 +83,12 @@ class VISP_EXPORT vpRGBf \param v : Value to set. */ - inline vpRGBf(float v) : R(v), G(v), B(v) {} + inline vpRGBf(float v) : R(v), G(v), B(v) { } /*! Copy constructor. */ - inline vpRGBf(const vpRGBf &v) : R(v.R), G(v.G), B(v.B) {} + inline vpRGBf(const vpRGBf &v) : R(v.R), G(v.G), B(v.B) { } /*! Create a RGB value from a 3 dimensional column vector. @@ -102,9 +101,7 @@ class VISP_EXPORT vpRGBf vpRGBf &operator=(float v); vpRGBf &operator=(const vpRGBf &v); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRGBf &operator=(const vpRGBf &&v); -#endif vpRGBf &operator=(const vpColVector &v); bool operator==(const vpRGBf &v) const; bool operator!=(const vpRGBf &v) const; diff --git a/modules/core/include/visp3/core/vpRectOriented.h b/modules/core/include/visp3/core/vpRectOriented.h index bfdd116a07..7819f3a91e 100644 --- a/modules/core/include/visp3/core/vpRectOriented.h +++ b/modules/core/include/visp3/core/vpRectOriented.h @@ -47,21 +47,13 @@ class VISP_EXPORT vpRectOriented { public: vpRectOriented(); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRectOriented(const vpRectOriented &rect) = default; -#else - vpRectOriented(const vpRectOriented &rect); -#endif vpRectOriented(const vpImagePoint ¢er, double width, double height, double theta = 0); vpRectOriented(const vpRect &rect); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRectOriented &operator=(const vpRectOriented &rect) = default; -#else - vpRectOriented &operator=(const vpRectOriented &rect); -#endif vpRectOriented &operator=(const vpRect &rect); diff --git a/modules/core/include/visp3/core/vpRobust.h b/modules/core/include/visp3/core/vpRobust.h index 0746e9a23c..c01fa0cb25 100644 --- a/modules/core/include/visp3/core/vpRobust.h +++ b/modules/core/include/visp3/core/vpRobust.h @@ -83,7 +83,8 @@ class VISP_EXPORT vpRobust { public: //! Enumeration of influence functions - typedef enum { + typedef enum + { TUKEY, //!< Tukey influence function. CAUCHY, //!< Cauchy influence function. HUBER //!< Huber influence function. @@ -115,7 +116,7 @@ class VISP_EXPORT vpRobust vpRobust(const vpRobust &other); //! Destructor - virtual ~vpRobust(){}; + virtual ~vpRobust() { }; /*! * Return residual vector Median Absolute Deviation (MAD). @@ -130,7 +131,7 @@ class VISP_EXPORT vpRobust /*! * Return the min value used to threshold residual vector Median Absolute Deviation (MAD). - * This value corresponds to the mimimal value of \f$\sigma\f$ computed in MEstimator(). + * This value corresponds to the minimal value of \f$\sigma\f$ computed in MEstimator(). * * \sa setMinMedianAbsoluteDeviation() */ @@ -139,12 +140,10 @@ class VISP_EXPORT vpRobust void MEstimator(const vpRobustEstimatorType method, const vpColVector &residues, vpColVector &weights); vpRobust &operator=(const vpRobust &other); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRobust &operator=(const vpRobust &&other); -#endif /*! - * Set minimal median absolute deviation (MAD) value corresponding to the mimimal value of + * Set minimal median absolute deviation (MAD) value corresponding to the minimal value of * \f$\sigma\f$ computed in MEstimator() with * \f$ \sigma = 1.48{Med}(|r_i - {Med}(r_i)|) \f$. * \param mad_min : Minimal Median Absolute Deviation value. diff --git a/modules/core/include/visp3/core/vpRotationMatrix.h b/modules/core/include/visp3/core/vpRotationMatrix.h index 09c66521ce..c0464c3146 100644 --- a/modules/core/include/visp3/core/vpRotationMatrix.h +++ b/modules/core/include/visp3/core/vpRotationMatrix.h @@ -107,10 +107,8 @@ int main() int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRotationMatrix R{ 0, 0, -1, 0, -1, 0, -1, 0, 0 }; std::cout << "R:\n" << R << std::endl; -#endif } \endcode */ @@ -129,9 +127,7 @@ class VISP_EXPORT vpRotationMatrix : public vpArray2D explicit vpRotationMatrix(const vpMatrix &R); vpRotationMatrix(double tux, double tuy, double tuz); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) explicit vpRotationMatrix(const std::initializer_list &list); -#endif vpRotationMatrix buildFrom(const vpHomogeneousMatrix &M); vpRotationMatrix buildFrom(const vpThetaUVector &v); @@ -156,9 +152,7 @@ class VISP_EXPORT vpRotationMatrix : public vpArray2D vpRotationMatrix &operator=(const vpRotationMatrix &R); // copy operator from vpMatrix (handle with care) vpRotationMatrix &operator=(const vpMatrix &M); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRotationMatrix &operator=(const std::initializer_list &list); -#endif // operation c = A * b (A is unchanged) vpTranslationVector operator*(const vpTranslationVector &tv) const; // operation C = A * B (A is unchanged) diff --git a/modules/core/include/visp3/core/vpRowVector.h b/modules/core/include/visp3/core/vpRowVector.h index be20e8f889..aeffe809be 100644 --- a/modules/core/include/visp3/core/vpRowVector.h +++ b/modules/core/include/visp3/core/vpRowVector.h @@ -90,20 +90,16 @@ int main() int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRowVector v{-1, -2.1, -3}; std::cout << "v:\n" << v << std::endl; -#endif } \endcode The vector could also be initialized using operator=(const std::initializer_list< double > &) \code int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRowVector v; v = {-1, -2.1, -3}; -#endif } \endcode */ @@ -125,10 +121,8 @@ class VISP_EXPORT vpRowVector : public vpArray2D vpRowVector(const vpMatrix &M, unsigned int i); vpRowVector(const std::vector &v); vpRowVector(const std::vector &v); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRowVector(vpRowVector &&v); vpRowVector(const std::initializer_list &list) : vpArray2D(list) { } -#endif /*! Removes all elements from the vector (which are destroyed), @@ -213,10 +207,8 @@ class VISP_EXPORT vpRowVector : public vpArray2D vpRowVector &operator=(const std::vector &v); vpRowVector &operator=(const std::vector &v); vpRowVector &operator=(double x); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRowVector &operator=(vpRowVector &&v); vpRowVector &operator=(const std::initializer_list &list); -#endif //! Comparison operator. bool operator==(const vpRowVector &v) const; bool operator!=(const vpRowVector &v) const; diff --git a/modules/core/include/visp3/core/vpRxyzVector.h b/modules/core/include/visp3/core/vpRxyzVector.h index aa5d3c086e..02d288feef 100644 --- a/modules/core/include/visp3/core/vpRxyzVector.h +++ b/modules/core/include/visp3/core/vpRxyzVector.h @@ -121,9 +121,7 @@ class vpThetaUVector; \endcode Or you can also initialize the vector from a list of doubles if ViSP is build with c++11 enabled: \code -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) rxyz = {M_PI_4, M_PI_2, M_PI}; -#endif \endcode To get the values [rad] use: @@ -201,10 +199,8 @@ class VISP_EXPORT vpRxyzVector : public vpRotationVector vpRxyzVector &operator=(const vpColVector &rxyz); vpRxyzVector &operator=(double x); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRxyzVector &operator=(const vpRxyzVector &rxyz) = default; vpRxyzVector &operator=(const std::initializer_list &list); -#endif }; #endif diff --git a/modules/core/include/visp3/core/vpRzyxVector.h b/modules/core/include/visp3/core/vpRzyxVector.h index da55f25b90..e21bd61a25 100644 --- a/modules/core/include/visp3/core/vpRzyxVector.h +++ b/modules/core/include/visp3/core/vpRzyxVector.h @@ -124,9 +124,7 @@ class vpThetaUVector; \endcode Or you can also initialize the vector from a list of doubles if ViSP is build with c++11 enabled: \code -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) rzyx = {M_PI_4, M_PI_2, M_PI}; -#endif \endcode To get the values [rad] use: @@ -202,10 +200,8 @@ class VISP_EXPORT vpRzyxVector : public vpRotationVector vpRzyxVector &operator=(const vpColVector &rzyx); vpRzyxVector &operator=(double x); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRzyxVector &operator=(const vpRzyxVector &rzyx) = default; vpRzyxVector &operator=(const std::initializer_list &list); -#endif }; #endif diff --git a/modules/core/include/visp3/core/vpRzyzVector.h b/modules/core/include/visp3/core/vpRzyzVector.h index bfc5c3ae09..82fd27d331 100644 --- a/modules/core/include/visp3/core/vpRzyzVector.h +++ b/modules/core/include/visp3/core/vpRzyzVector.h @@ -123,9 +123,7 @@ class vpThetaUVector; \endcode Or you can also initialize the vector from a list of doubles if ViSP is build with c++11 enabled: \code -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) rzyz = {M_PI_4, M_PI_2, M_PI}; -#endif \endcode To get the values [rad] use: @@ -201,9 +199,7 @@ class VISP_EXPORT vpRzyzVector : public vpRotationVector vpRzyzVector &operator=(const vpColVector &rzyz); vpRzyzVector &operator=(double x); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRzyzVector &operator=(const vpRzyzVector &rzyz) = default; vpRzyzVector &operator=(const std::initializer_list &list); -#endif }; #endif diff --git a/modules/core/include/visp3/core/vpThetaUVector.h b/modules/core/include/visp3/core/vpThetaUVector.h index fb442147ba..58df309e97 100644 --- a/modules/core/include/visp3/core/vpThetaUVector.h +++ b/modules/core/include/visp3/core/vpThetaUVector.h @@ -113,9 +113,7 @@ class vpQuaternionVector; \endcode Or you can also initialize the vector from a list of doubles if ViSP is build with c++11 enabled: \code -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) tu = {M_PI_4, M_PI_2, M_PI}; -#endif \endcode To get the values [rad] use: @@ -218,9 +216,7 @@ class VISP_EXPORT vpThetaUVector : public vpRotationVector vpThetaUVector &operator=(double x); vpThetaUVector operator*(const vpThetaUVector &tu_b) const; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpThetaUVector &operator=(const std::initializer_list &list); -#endif }; #endif diff --git a/modules/core/include/visp3/core/vpTime.h b/modules/core/include/visp3/core/vpTime.h index 3bc5d5ae2b..0977febeec 100644 --- a/modules/core/include/visp3/core/vpTime.h +++ b/modules/core/include/visp3/core/vpTime.h @@ -41,9 +41,7 @@ #include #include #include -#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 #include -#endif #include @@ -94,8 +92,7 @@ class VISP_EXPORT vpChrono private: double m_durationMs; -#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 && \ - (defined(_MSC_VER) && _MSC_VER >= 1900 /* VS2015 */ || !defined(_MSC_VER)) +#if (defined(_MSC_VER) && _MSC_VER >= 1900 /* VS2015 */ || !defined(_MSC_VER)) std::chrono::steady_clock::time_point m_lastTimePoint; #else double m_lastTimePoint; diff --git a/modules/core/include/visp3/core/vpTranslationVector.h b/modules/core/include/visp3/core/vpTranslationVector.h index d8576c2ab0..0d9c9a4fd2 100644 --- a/modules/core/include/visp3/core/vpTranslationVector.h +++ b/modules/core/include/visp3/core/vpTranslationVector.h @@ -73,9 +73,7 @@ \endcode Or you can also initialize the vector from a list of doubles if ViSP is build with c++11 enabled: \code -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) t = {0, 0.1, 0.5}; -#endif \endcode To get the values [meters] use: @@ -150,9 +148,7 @@ class VISP_EXPORT vpTranslationVector : public vpArray2D vpTranslationVector &operator=(const vpColVector &tv); vpTranslationVector &operator=(const vpTranslationVector &tv); vpTranslationVector &operator=(double x); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpTranslationVector &operator=(const std::initializer_list &list); -#endif //! Operator that allows to set a value of an element \f$t_i\f$: t[i] = x inline double &operator[](unsigned int n) { return *(data + n); } diff --git a/modules/core/include/visp3/core/vpUniRand.h b/modules/core/include/visp3/core/vpUniRand.h index 8b17b16a24..34dfd32833 100644 --- a/modules/core/include/visp3/core/vpUniRand.h +++ b/modules/core/include/visp3/core/vpUniRand.h @@ -72,13 +72,9 @@ typedef unsigned __int32 uint32_t; #include #endif -#if (VISP_CXX_STANDARD <= VISP_CXX_STANDARD_11) -#include // std::random_shuffle -#else #include // std::shuffle #include // std::mt19937 #include // std::iota -#endif #include /*! @@ -156,11 +152,7 @@ class VISP_EXPORT vpUniRand inline static std::vector shuffleVector(const std::vector &inputVector) { std::vector shuffled = inputVector; -#if (VISP_CXX_STANDARD <= VISP_CXX_STANDARD_11) - std::random_shuffle(shuffled.begin(), shuffled.end()); -#else std::shuffle(shuffled.begin(), shuffled.end(), std::mt19937 { std::random_device{}() }); -#endif return shuffled; } diff --git a/modules/core/src/camera/vpColorDepthConversion.cpp b/modules/core/src/camera/vpColorDepthConversion.cpp index c49b8fb5cd..67774be7e3 100644 --- a/modules/core/src/camera/vpColorDepthConversion.cpp +++ b/modules/core/src/camera/vpColorDepthConversion.cpp @@ -1,5 +1,4 @@ -/**************************************************************************** - * +/* * ViSP, open source Visual Servoing Platform software. * Copyright (C) 2005 - 2023 by Inria. All rights reserved. * @@ -30,16 +29,12 @@ * * Description: * Color to depth conversion. - * - * Authors: - * Julien Dufour - * -*****************************************************************************/ + */ /*! - \file vpColorDepthConversion.cpp - \brief color to depth conversion -*/ + * \file vpColorDepthConversion.cpp + * \brief color to depth conversion + */ #include @@ -64,11 +59,7 @@ namespace */ vpImagePoint adjust2DPointToBoundary(const vpImagePoint &ip, double width, double height) { -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) - return {vpMath::clamp(ip.get_i(), 0., height), vpMath::clamp(ip.get_j(), 0., width)}; -#else - return vpImagePoint(vpMath::clamp(ip.get_i(), 0., height), vpMath::clamp(ip.get_j(), 0., width)); -#endif + return { vpMath::clamp(ip.get_i(), 0., height), vpMath::clamp(ip.get_j(), 0., width) }; } /*! @@ -80,15 +71,9 @@ vpImagePoint adjust2DPointToBoundary(const vpImagePoint &ip, double width, doubl */ vpColVector transform(const vpHomogeneousMatrix &extrinsics_params, vpColVector from_point) { -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) - from_point = {from_point, 0, 3}; - from_point.stack(1.); - return {extrinsics_params * from_point, 0, 3}; -#else - from_point = vpColVector(from_point, 0, 3); + from_point = { from_point, 0, 3 }; from_point.stack(1.); - return vpColVector(extrinsics_params * from_point, 0, 3); -#endif + return { extrinsics_params * from_point, 0, 3 }; } /*! @@ -100,11 +85,7 @@ vpColVector transform(const vpHomogeneousMatrix &extrinsics_params, vpColVector */ vpImagePoint project(const vpCameraParameters &intrinsic_cam_params, const vpColVector &point) { -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) - vpImagePoint iP{}; -#else - vpImagePoint iP; -#endif + vpImagePoint iP {}; vpMeterPixelConversion::convertPoint(intrinsic_cam_params, point[0] / point[2], point[1] / point[2], iP); return iP; @@ -120,20 +101,9 @@ vpImagePoint project(const vpCameraParameters &intrinsic_cam_params, const vpCol */ vpColVector deproject(const vpCameraParameters &intrinsic_cam_params, const vpImagePoint &pixel, double depth) { -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) - double x{0.}, y{0.}; + double x { 0. }, y { 0. }; vpPixelMeterConversion::convertPoint(intrinsic_cam_params, pixel, x, y); - return {x * depth, y * depth, depth}; -#else - double x = 0., y = 0.; - vpPixelMeterConversion::convertPoint(intrinsic_cam_params, pixel, x, y); - - vpColVector p(3); - p[0] = x * depth; - p[1] = y * depth; - p[2] = depth; - return p; -#endif + return { x * depth, y * depth, depth }; } } // namespace @@ -143,12 +113,15 @@ vpColVector deproject(const vpCameraParameters &intrinsic_cam_params, const vpIm * * \param[in] I_depth : Depth raw image. * \param[in] depth_scale : Depth scale to convert depth raw values in [m]. If depth raw values in `I_depth` are in - * [mm], depth scale should be 0.001. \param[in] depth_min : Minimal depth value for correspondance [m]. \param[in] - * depth_max : Maximal depth value for correspondance [m]. \param[in] depth_intrinsics : Intrinsic depth camera - * parameters. \param[in] color_intrinsics : Intrinsic color camera parameters. \param[in] color_M_depth : Relationship - * between color and depth cameras (ie, extrinsic rgbd camera parameters). \param[in] depth_M_color : Relationship - * between depth and color cameras (ie, extrinsic rgbd camera parameters). \param[in] from_pixel : Image point expressed - * into the color camera frame. \return Image point expressed into the depth camera frame. + * [mm], depth scale should be 0.001. + * \param[in] depth_min : Minimal depth value for correspondence [m]. + * \param[in] depth_max : Maximal depth value for correspondence [m]. + * \param[in] depth_intrinsics : Intrinsic depth camera parameters. + * \param[in] color_intrinsics : Intrinsic color camera parameters. + * \param[in] color_M_depth : Relationship between color and depth cameras (ie, extrinsic rgb-d camera parameters). + * \param[in] depth_M_color : Relationship between depth and color cameras (ie, extrinsic rgb-d camera parameters). + * \param[in] from_pixel : Image point expressed into the color camera frame. + * \return Image point expressed into the depth camera frame. */ vpImagePoint vpColorDepthConversion::projectColorToDepth( const vpImage &I_depth, double depth_scale, double depth_min, double depth_max, @@ -164,12 +137,15 @@ vpImagePoint vpColorDepthConversion::projectColorToDepth( * * \param[in] data : Depth raw values. * \param[in] depth_scale : Depth scale to convert depth raw values in [m]. If depth raw values in `data` are in [mm], - * depth scale should be 0.001. \param[in] depth_min : Minimal depth value for correspondance [m]. \param[in] depth_max - * : Maximal depth value for correspondance [m]. \param[in] depth_width : Depth image width [pixel]. \param[in] - * depth_height : Depth image height [pixel]. \param[in] depth_intrinsics : Intrinsic depth camera parameters. + * depth scale should be 0.001. + * \param[in] depth_min : Minimal depth value for correspondence [m]. + * \param[in] depth_max : Maximal depth value for correspondence [m]. + * \param[in] depth_width : Depth image width [pixel]. + * \param[in] depth_height : Depth image height [pixel]. + * \param[in] depth_intrinsics : Intrinsic depth camera parameters. * \param[in] color_intrinsics : Intrinsic color camera parameters. - * \param[in] color_M_depth : Relationship between color and depth cameras (ie, extrinsic rgbd camera parameters). - * \param[in] depth_M_color : Relationship between depth and color cameras (ie, extrinsic rgbd camera parameters). + * \param[in] color_M_depth : Relationship between color and depth cameras (ie, extrinsic rgb-d camera parameters). + * \param[in] depth_M_color : Relationship between depth and color cameras (ie, extrinsic rgb-d camera parameters). * \param[in] from_pixel : Image point expressed into the color camera frame. * \return Image point expressed into the depth camera frame. */ @@ -178,8 +154,7 @@ vpImagePoint vpColorDepthConversion::projectColorToDepth( double depth_height, const vpCameraParameters &depth_intrinsics, const vpCameraParameters &color_intrinsics, const vpHomogeneousMatrix &color_M_depth, const vpHomogeneousMatrix &depth_M_color, const vpImagePoint &from_pixel) { -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) - vpImagePoint depth_pixel{}; + vpImagePoint depth_pixel {}; // Find line start pixel const auto min_point = deproject(color_intrinsics, from_pixel, depth_min); @@ -206,48 +181,12 @@ vpImagePoint vpColorDepthConversion::projectColorToDepth( const auto projected_pixel = project(color_intrinsics, transformed_point); const auto new_dist = vpMath::sqr(projected_pixel.get_v() - from_pixel.get_v()) + - vpMath::sqr(projected_pixel.get_u() - from_pixel.get_u()); - if (new_dist < min_dist || min_dist < 0) { - min_dist = new_dist; - depth_pixel = curr_pixel; - } - } - -#else - vpImagePoint depth_pixel; - - // Find line start pixel - const vpColVector min_point = deproject(color_intrinsics, from_pixel, depth_min); - const vpColVector min_transformed_point = transform(depth_M_color, min_point); - vpImagePoint start_pixel = project(depth_intrinsics, min_transformed_point); - start_pixel = adjust2DPointToBoundary(start_pixel, depth_width, depth_height); - - // Find line end depth pixel - const vpColVector max_point = deproject(color_intrinsics, from_pixel, depth_max); - const vpColVector max_transformed_point = transform(depth_M_color, max_point); - vpImagePoint end_pixel = project(depth_intrinsics, max_transformed_point); - end_pixel = adjust2DPointToBoundary(end_pixel, depth_width, depth_height); - - // search along line for the depth pixel that it's projected pixel is the closest to the input pixel - double min_dist = -1.; - for (vpImagePoint curr_pixel = start_pixel; curr_pixel.inSegment(start_pixel, end_pixel) && curr_pixel != end_pixel; - curr_pixel = curr_pixel.nextInSegment(start_pixel, end_pixel)) { - const double depth = depth_scale * data[static_cast(curr_pixel.get_v() * depth_width + curr_pixel.get_u())]; - if (std::fabs(depth) <= std::numeric_limits::epsilon()) - continue; - - const vpColVector point = deproject(depth_intrinsics, curr_pixel, depth); - const vpColVector transformed_point = transform(color_M_depth, point); - const vpImagePoint projected_pixel = project(color_intrinsics, transformed_point); - - const double new_dist = vpMath::sqr(projected_pixel.get_v() - from_pixel.get_v()) + - vpMath::sqr(projected_pixel.get_u() - from_pixel.get_u()); + vpMath::sqr(projected_pixel.get_u() - from_pixel.get_u()); if (new_dist < min_dist || min_dist < 0) { min_dist = new_dist; depth_pixel = curr_pixel; } } -#endif return depth_pixel; } diff --git a/modules/core/src/image/private/vpImageConvert_impl.h b/modules/core/src/image/private/vpImageConvert_impl.h index b057180907..975c8cdd23 100644 --- a/modules/core/src/image/private/vpImageConvert_impl.h +++ b/modules/core/src/image/private/vpImageConvert_impl.h @@ -41,7 +41,7 @@ #ifndef vpIMAGECONVERT_impl_H #define vpIMAGECONVERT_impl_H -#if defined(VISP_HAVE_OPENMP) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OPENMP) #include #include #endif @@ -60,7 +60,7 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OPENMP) int nThreads = omp_get_max_threads(); std::vector > histograms(nThreads); for (int i = 0; i < nThreads; i++) { @@ -100,9 +100,10 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage(src_depth.bitmap[i]); if (d) { unsigned char f = - static_cast(histogram[d] * 255 / histogram[0xFFFF]); // 0-255 based on histogram location + static_cast(histogram[d] * 255 / histogram[0xFFFF]); // 0-255 based on histogram location dest_depth.bitmap[i] = f; - } else { + } + else { dest_depth.bitmap[i] = 0; } } @@ -119,7 +120,7 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OPENMP) int nThreads = omp_get_max_threads(); std::vector > histograms(nThreads); for (int i = 0; i < nThreads; i++) { @@ -155,9 +156,10 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage(histogram[d] * 255 / histogram[0xFFFF]); // 0-255 based on histogram location + static_cast(histogram[d] * 255 / histogram[0xFFFF]); // 0-255 based on histogram location dest_depth.bitmap[i] = f; - } else { + } + else { dest_depth.bitmap[i] = 0; } } @@ -198,7 +200,8 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage &d dest_depth.bitmap[i].G = 0; dest_depth.bitmap[i].B = f; dest_depth.bitmap[i].A = vpRGBa::alpha_default; - } else { + } + else { dest_depth.bitmap[i].R = 20; dest_depth.bitmap[i].G = 5; dest_depth.bitmap[i].B = 0; @@ -240,7 +243,8 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage dest_depth.bitmap[i].G = 0; dest_depth.bitmap[i].B = f; dest_depth.bitmap[i].A = vpRGBa::alpha_default; - } else { + } + else { dest_depth.bitmap[i].R = 20; dest_depth.bitmap[i].G = 5; dest_depth.bitmap[i].B = 0; diff --git a/modules/core/src/image/vpColormap.cpp b/modules/core/src/image/vpColormap.cpp index 982ac9eb6d..2c1ff37eba 100644 --- a/modules/core/src/image/vpColormap.cpp +++ b/modules/core/src/image/vpColormap.cpp @@ -34,8 +34,6 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - namespace { unsigned char m_autumnSrgbBytes[256][3] = { @@ -1219,5 +1217,3 @@ void vpColormap::convert(const vpImage &I, vpImage &Icolor) } convert(I_float, Icolor); } - -#endif diff --git a/modules/core/src/image/vpFont.cpp b/modules/core/src/image/vpFont.cpp index 24d71eda9f..ff72d5b283 100644 --- a/modules/core/src/image/vpFont.cpp +++ b/modules/core/src/image/vpFont.cpp @@ -61,11 +61,7 @@ #include #include #include -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) #include -#else -#include -#endif #include "private/Font.hpp" #define STB_TRUETYPE_IMPLEMENTATION @@ -203,7 +199,8 @@ class vpFont::Impl curr.x += _currentSize.x; size.x = std::max(size.x, curr.x); size.y = std::max(size.y, curr.y + _currentSize.y); - } else if (text[i] == '\n') { + } + else if (text[i] == '\n') { curr.x = 0; curr.y += _currentSize.y; } @@ -345,7 +342,7 @@ class vpFont::Impl int coeff = 255 - _fontBuffer[y][x]; unsigned char gray = - static_cast((color * _fontBuffer[y][x] + coeff * canvas[dstY][dstX]) / 255); + static_cast((color * _fontBuffer[y][x] + coeff * canvas[dstY][dstX]) / 255); canvas[dstY][dstX] = gray; } } @@ -420,7 +417,7 @@ class vpFont::Impl int G = (color.G * _alpha[i][j] + coeff * canvas[dstY][dstX].G) / 255; int B = (color.B * _alpha[i][j] + coeff * canvas[dstY][dstX].B) / 255; canvas[dstY][dstX] = - vpRGBa(static_cast(R), static_cast(G), static_cast(B)); + vpRGBa(static_cast(R), static_cast(G), static_cast(B)); } } } @@ -459,7 +456,7 @@ class vpFont::Impl int G = (color.G * _fontBuffer[y][x] + coeff * canvas[dstY][dstX].G) / 255; int B = (color.B * _fontBuffer[y][x] + coeff * canvas[dstY][dstX].B) / 255; canvas[dstY][dstX] = - vpRGBa(static_cast(R), static_cast(G), static_cast(B)); + vpRGBa(static_cast(R), static_cast(G), static_cast(B)); } } @@ -504,7 +501,8 @@ class vpFont::Impl } private: - struct Symbol { + struct Symbol + { char value; vpImage image; }; @@ -551,7 +549,8 @@ class vpFont::Impl symbols.push_back(value); } curr.x += _currentSize.x; - } else if (value == '\n') { + } + else if (value == '\n') { curr.x = 0; curr.y += _currentSize.y; } @@ -611,7 +610,8 @@ class vpFont::Impl } } } - } catch (...) { + } + catch (...) { _originalSize = Point(); _originalSymbols.clear(); return false; @@ -2527,7 +2527,6 @@ class vpFont::Impl void LoadTTF(const std::string &filename) { -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::ifstream fontFile(filename.c_str(), std::ios::binary | std::ios::ate); fontFile >> std::noskipws; @@ -2539,25 +2538,6 @@ class vpFont::Impl std::copy(std::istream_iterator(fontFile), std::istream_iterator(), std::back_inserter(fontBuffer)); -#else - // for compatibility with old platform (e.g. Ubuntu 12.04) - FILE *fontFile = fopen(filename.c_str(), "rb"); - if (!fontFile) { - fclose(fontFile); - throw vpIoException(vpIoException::ioError, "Cannot open TTF file: %s", filename.c_str()); - } - - fseek(fontFile, 0, SEEK_END); - size_t fileSize = ftell(fontFile); /* how long is the file? */ - fseek(fontFile, 0, SEEK_SET); /* reset */ - - fontBuffer.resize(fileSize); - if (fread(&fontBuffer[0], sizeof(unsigned char), fontBuffer.size(), fontFile) != fontBuffer.size()) { - fclose(fontFile); - throw vpIoException(vpIoException::ioError, "Error when reading the font file."); - } - fclose(fontFile); -#endif /* prepare font */ if (!stbtt_InitFont(&_info, fontBuffer.data(), 0)) { @@ -2574,21 +2554,25 @@ class vpFont::Impl unsigned int charcode; if (ch <= 127) { charcode = ch; - } else if (ch <= 223 && i + 1 < str.size() && (str[i + 1] & 0xc0) == 0x80) { + } + else if (ch <= 223 && i + 1 < str.size() && (str[i + 1] & 0xc0) == 0x80) { charcode = ((ch & 31) << 6) | (str[i + 1] & 63); i++; - } else if (ch <= 239 && i + 2 < str.size() && (str[i + 1] & 0xc0) == 0x80 && (str[i + 2] & 0xc0) == 0x80) { + } + else if (ch <= 239 && i + 2 < str.size() && (str[i + 1] & 0xc0) == 0x80 && (str[i + 2] & 0xc0) == 0x80) { charcode = ((ch & 15) << 12) | ((str[i + 1] & 63) << 6) | (str[i + 2] & 63); i += 2; - } else if (ch <= 247 && i + 3 < str.size() && (str[i + 1] & 0xc0) == 0x80 && (str[i + 2] & 0xc0) == 0x80 && - (str[i + 3] & 0xc0) == 0x80) { + } + else if (ch <= 247 && i + 3 < str.size() && (str[i + 1] & 0xc0) == 0x80 && (str[i + 2] & 0xc0) == 0x80 && + (str[i + 3] & 0xc0) == 0x80) { int val = (int)(((ch & 15) << 18) | ((str[i + 1] & 63) << 12) | ((str[i + 2] & 63) << 6) | (str[i + 3] & 63)); if (val > 1114111) { val = 65533; } charcode = val; i += 3; - } else { + } + else { charcode = 65533; while (i + 1 < str.size() && (str[i + 1] & 0xc0) == 0x80) { i++; @@ -2613,8 +2597,7 @@ class vpFont::Impl */ vpFont::vpFont(unsigned int height, const vpFontFamily &fontFamily, const std::string &ttfFilename) : m_impl(new Impl(height, fontFamily, ttfFilename)) -{ -} +{ } /*! Destructor. diff --git a/modules/core/src/image/vpImageFilter.cpp b/modules/core/src/image/vpImageFilter.cpp index 94d1111019..20f55874a9 100644 --- a/modules/core/src/image/vpImageFilter.cpp +++ b/modules/core/src/image/vpImageFilter.cpp @@ -643,7 +643,7 @@ std::vector vpImageFilter::median(const vpImage &Isrc) * \param[in] p_cv_dIx : If different from nullptr, the gradient of cv_I with regard to the horizontal axis. * \param[in] p_cv_dIy : If different from nullptr, the gradient of cv_I with regard to the vertical axis. * \param[out] lowerThresh : The lower threshold for the Canny edge filter. - * \param[in] gaussianFilterSize : The size of the mask of the Gaussian filter to apply (an odd number). + * \param[in] gaussianKernelSize : The size of the mask of the Gaussian filter to apply (an odd number). * \param[in] gaussianStdev : The standard deviation of the Gaussian filter to apply. * \param[in] apertureGradient : Size of the mask for the Sobel operator (odd number). * \param[in] lowerThresholdRatio : The ratio of the upper threshold the lower threshold must be equal to. @@ -654,10 +654,10 @@ std::vector vpImageFilter::median(const vpImage &Isrc) * \return The upper Canny edge filter threshold. */ float vpImageFilter::computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *p_cv_dIx, const cv::Mat *p_cv_dIy, - float &lowerThresh, const unsigned int &gaussianKernelSize, - const float &gaussianStdev, const unsigned int &apertureGradient, - const float &lowerThresholdRatio, const float &upperThresholdRatio, - const vpImageFilter::vpCannyFilteringAndGradientType &filteringType) + float &lowerThresh, const unsigned int &gaussianKernelSize, + const float &gaussianStdev, const unsigned int &apertureGradient, + const float &lowerThresholdRatio, const float &upperThresholdRatio, + const vpImageFilter::vpCannyFilteringAndGradientType &filteringType) { double w = cv_I.cols; double h = cv_I.rows; @@ -711,21 +711,22 @@ float vpImageFilter::computeCannyThreshold(const cv::Mat &cv_I, const cv::Mat *p * \param[in] cv_I The input image we want the partial derivatives. * \param[out] cv_dIx The horizontal partial derivative, i.e. horizontal gradient. * \param[out] cv_dIy The vertical partial derivative, i.e. vertical gradient. - * \param[in] computeDx Idicate if we must compute the horizontal gradient. - * \param[in] computeDy Idicate if we must compute the vertical gradient. - * \param[in] normalize Idicate if we must normalize the gradient filters. + * \param[in] computeDx Indicate if we must compute the horizontal gradient. + * \param[in] computeDy Indicate if we must compute the vertical gradient. + * \param[in] normalize Indicate if we must normalize the gradient filters. * \param[in] gaussianKernelSize The size of the kernel of the Gaussian filter used to blur the image. * \param[in] gaussianStdev The standard deviation of the Gaussian filter used to blur the image. + * If it is non-positive, it is computed from kernel size (`gaussianKernelSize` parameter) as + * \f$\sigma = 0.3*((gaussianKernelSize-1)*0.5 - 1) + 0.8\f$. * \param[in] apertureGradient The size of the kernel of the gradient filter. * \param[in] filteringType The type of filters to apply to compute the gradients. - * \param[in] backend The type of backend to use to compute the gradients. */ void vpImageFilter::computePartialDerivatives(const cv::Mat &cv_I, - cv::Mat &cv_dIx, cv::Mat &cv_dIy, - const bool &computeDx, const bool &computeDy, const bool &normalize, - const unsigned int &gaussianKernelSize, const float &gaussianStdev, - const unsigned int &apertureGradient, - const vpImageFilter::vpCannyFilteringAndGradientType &filteringType) + cv::Mat &cv_dIx, cv::Mat &cv_dIy, + const bool &computeDx, const bool &computeDy, const bool &normalize, + const unsigned int &gaussianKernelSize, const float &gaussianStdev, + const unsigned int &apertureGradient, + const vpImageFilter::vpCannyFilteringAndGradientType &filteringType) { if (filteringType == vpImageFilter::CANNY_GBLUR_SCHARR_FILTERING || filteringType == vpImageFilter::CANNY_GBLUR_SOBEL_FILTERING) { @@ -950,80 +951,81 @@ void vpImageFilter::canny(const vpImage &Isrc, vpImage -#include - -int main() -{ - // Constants for the Canny operator. - const unsigned int gaussianFilterSize = 5; - const float gaussianStdev = 2.0f; - const float upperThresholdCanny = 15.f; - const float lowerThresholdCanny = 5.f; - const float upperThresholdRatio = 0.8f; - const float lowerThresholdRatio = 0.6f; - const unsigned int apertureSobel = 3; - const bool normalizeGradient = true; - const vpCannyBackendType cannyBackend = CANNY_OPENCV_BACKEND; // or CANNY_VISP_BACKEND; - const vpCannyFilteringAndGradientType filteringType = CANNY_GBLUR_SOBEL_FILTERING; // or CANNY_GBLUR_SCHARR_FILTERING - - // Image for the Canny edge operator - vpImage Isrc; - vpImage Icanny; - - // First grab the source image Isrc. - - // Apply the Canny edge operator and set the Icanny image. - vpImageFilter::canny(Isrc, Icanny, gaussianFilterSize, lowerThresholdCanny, upperThresholdCanny, apertureSobel, - gaussianStdev, lowerThresholdRatio, upperThresholdRatio, normalizeGradient, - cannyBackend, filteringType); - return (0); -} - \endcode - - \param[in] Isrc : Image to apply the Canny edge detector to. - \param[out] Ires : Filtered image (255 means an edge, 0 otherwise). - \param[in] gaussianFilterSize : The size of the mask of the Gaussian filter to - apply (an odd number). - \param[in] lowerThreshold : The lower threshold for the Canny operator. Values lower - than this value are rejected. If negative, it will be set to one third - of the thresholdCanny . - \param[in] upperThreshold : The upper threshold for the Canny operator. Only value - greater than this value are marked as an edge. If negative, it will be automatically - computed, along with the lower threshold. Otherwise, the lower threshold will be set to one third - of the upper threshold . - \param[in] apertureGradient : Size of the mask for the gardient (Sobel or Scharr) operator (odd number). - \param[in] gaussianStdev : The standard deviation of the Gaussian filter to apply. - \param[in] lowerThresholdRatio : The ratio of the upper threshold the lower threshold must be equal to. - It is used only if the user asks to compute the Canny thresholds. - \param[in] upperThresholdRatio : The ratio of pixels whose absolute gradient Gabs is lower or equal to define - the upper threshold. It is used only if the user asks to compute the Canny thresholds. - \param[in] normalizeGradients : Needs to be true if asking to compute the \b upperThreshold , otherwise it depends on - the user application and user-defined thresholds. - \param[in] cannyBackend : The backend to use to perform the Canny edge filtering. - \param[in] cannyFilteringSteps : The filtering + gradient operators to apply to compute the gradient in the early - stage of the Canny algoritgm. -*/ + * Apply the Canny edge operator on the image \e Isrc and return the resulting + * image \e Ires. + * + * The following example shows how to use the method: + * + * \code + * #include + * #include + * + * int main() + * { + * // Constants for the Canny operator. + * const unsigned int gaussianFilterSize = 5; + * const float gaussianStdev = 2.0f; + * const float upperThresholdCanny = 15.f; + * const float lowerThresholdCanny = 5.f; + * const float upperThresholdRatio = 0.8f; + * const float lowerThresholdRatio = 0.6f; + * const unsigned int apertureSobel = 3; + * const bool normalizeGradient = true; + * const vpCannyBackendType cannyBackend = CANNY_OPENCV_BACKEND; // or CANNY_VISP_BACKEND; + * const vpCannyFilteringAndGradientType filteringType = CANNY_GBLUR_SOBEL_FILTERING; // or CANNY_GBLUR_SCHARR_FILTERING + * + * // Image for the Canny edge operator + * vpImage Isrc; + * vpImage Icanny; + * + * // First grab the source image Isrc. + * + * // Apply the Canny edge operator and set the Icanny image. + * vpImageFilter::canny(Isrc, Icanny, gaussianFilterSize, lowerThresholdCanny, upperThresholdCanny, apertureSobel, + * gaussianStdev, lowerThresholdRatio, upperThresholdRatio, normalizeGradient, + * cannyBackend, filteringType); + * return (0); + * } + * \endcode + * + * \param[in] Isrc : Image to apply the Canny edge detector to. + * \param[out] Ires : Filtered image (255 means an edge, 0 otherwise). + * \param[in] gaussianFilterSize : The size of the mask of the Gaussian filter to + * apply (an odd number). + * \param[in] lowerThreshold : The lower threshold for the Canny operator. Values lower + * than this value are rejected. If negative, it will be set to one third + * of the thresholdCanny. + * \param[in] upperThreshold : The upper threshold for the Canny operator. Only value + * greater than this value are marked as an edge. If negative, it will be automatically + * computed, along with the lower threshold. Otherwise, the lower threshold will be set to one third + * of the upper threshold. + * \param[in] apertureGradient : Size of the mask for the gradient (Sobel or Scharr) operator (odd number). + * \param[in] gaussianStdev : The standard deviation of the Gaussian filter to apply. + * If it is non-positive, it is computed from kernel size (`gaussianKernelSize` parameter) as + * \f$\sigma = 0.3*((gaussianKernelSize-1)*0.5 - 1) + 0.8\f$. + * \param[in] lowerThresholdRatio : The ratio of the upper threshold the lower threshold must be equal to. + * It is used only if the user asks to compute the Canny thresholds. + * \param[in] upperThresholdRatio : The ratio of pixels whose absolute gradient is lower or equal to define + * the upper threshold. It is used only if the user asks to compute the Canny thresholds. + * \param[in] normalizeGradients : Needs to be true if asking to compute the \b upperThreshold, otherwise it depends on + * the user application and user-defined thresholds. + * \param[in] cannyBackend : The backend to use to perform the Canny edge filtering. + * \param[in] cannyFilteringSteps : The filtering + gradient operators to apply to compute the gradient in the early + * stage of the Canny algorithm. + */ void vpImageFilter::canny(const vpImage &Isrc, vpImage &Ires, - const unsigned int &gaussianFilterSize, - const float &lowerThreshold, const float &upperThreshold, const unsigned int &apertureGradient, - const float &gaussianStdev, const float &lowerThresholdRatio, const float &upperThresholdRatio, - const bool &normalizeGradients, - const vpCannyBackendType &cannyBackend, const vpCannyFilteringAndGradientType &cannyFilteringSteps -) + const unsigned int &gaussianFilterSize, + const float &lowerThreshold, const float &upperThreshold, const unsigned int &apertureGradient, + const float &gaussianStdev, const float &lowerThresholdRatio, const float &upperThresholdRatio, + const bool &normalizeGradients, + const vpCannyBackendType &cannyBackend, const vpCannyFilteringAndGradientType &cannyFilteringSteps) { if (cannyBackend == CANNY_OPENCV_BACKEND) { #if defined(HAVE_OPENCV_IMGPROC) cv::Mat img_cvmat, cv_dx, cv_dy, edges_cvmat; vpImageConvert::convert(Isrc, img_cvmat); computePartialDerivatives(img_cvmat, cv_dx, cv_dy, true, true, normalizeGradients, gaussianFilterSize, - gaussianStdev, apertureGradient, cannyFilteringSteps); + gaussianStdev, apertureGradient, cannyFilteringSteps); float upperCannyThresh = upperThreshold; float lowerCannyThresh = lowerThreshold; if (upperCannyThresh < 0) { @@ -1034,7 +1036,13 @@ void vpImageFilter::canny(const vpImage &Isrc, vpImage= 0x030200) cv::Canny(cv_dx, cv_dy, edges_cvmat, lowerCannyThresh, upperCannyThresh, false); +#else + cv::GaussianBlur(img_cvmat, img_cvmat, cv::Size((int)gaussianFilterSize, (int)gaussianFilterSize), + gaussianStdev, gaussianStdev); + cv::Canny(img_cvmat, edges_cvmat, lowerCannyThresh, upperCannyThresh); +#endif vpImageConvert::convert(edges_cvmat, Ires); #else std::string errMsg("[vpImageFilter::canny]You asked for CANNY_OPENCV_BACKEND but ViSP has not been compiled with OpenCV"); diff --git a/modules/core/src/image/vpRGBa.cpp b/modules/core/src/image/vpRGBa.cpp index 69147272c4..61660abc70 100644 --- a/modules/core/src/image/vpRGBa.cpp +++ b/modules/core/src/image/vpRGBa.cpp @@ -70,7 +70,6 @@ vpRGBa &vpRGBa::operator=(const vpRGBa &v) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Move operator. */ @@ -82,7 +81,6 @@ vpRGBa &vpRGBa::operator=(const vpRGBa &&v) this->A = std::move(v.A); return *this; } -#endif /*! Cast a vpColVector in a vpRGBa diff --git a/modules/core/src/image/vpRGBf.cpp b/modules/core/src/image/vpRGBf.cpp index 7822445047..5510bece32 100644 --- a/modules/core/src/image/vpRGBf.cpp +++ b/modules/core/src/image/vpRGBf.cpp @@ -69,7 +69,6 @@ vpRGBf &vpRGBf::operator=(const vpRGBf &v) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Move operator. */ @@ -80,7 +79,6 @@ vpRGBf &vpRGBf::operator=(const vpRGBf &&v) this->B = std::move(v.B); return *this; } -#endif /*! Cast a vpColVector in a vpRGBf @@ -96,9 +94,9 @@ vpRGBf &vpRGBf::operator=(const vpColVector &v) vpERROR_TRACE("Bad vector dimension"); throw(vpException(vpException::dimensionError, "Bad vector dimension")); } - R = (float) v[0]; - G = (float) v[1]; - B = (float) v[2]; + R = (float)v[0]; + G = (float)v[1]; + B = (float)v[2]; return *this; } diff --git a/modules/core/src/math/matrix/vpColVector.cpp b/modules/core/src/math/matrix/vpColVector.cpp index 01fac52a25..7a06e90e30 100644 --- a/modules/core/src/math/matrix/vpColVector.cpp +++ b/modules/core/src/math/matrix/vpColVector.cpp @@ -214,7 +214,6 @@ vpColVector::vpColVector(const std::vector &v) : vpArray2D((unsig (*this)[i] = (double)(v[i]); } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpColVector::vpColVector(vpColVector &&v) : vpArray2D() { rowNum = v.rowNum; @@ -229,7 +228,6 @@ vpColVector::vpColVector(vpColVector &&v) : vpArray2D() v.dsize = 0; v.data = NULL; } -#endif vpColVector vpColVector::operator-() const { @@ -404,8 +402,6 @@ std::vector vpColVector::toStdVector() const return v; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - vpColVector &vpColVector::operator=(vpColVector &&other) { if (this != &other) { @@ -434,7 +430,6 @@ vpColVector &vpColVector::operator=(const std::initializer_list &list) std::copy(list.begin(), list.end(), data); return *this; } -#endif bool vpColVector::operator==(const vpColVector &v) const { diff --git a/modules/core/src/math/matrix/vpMatrix.cpp b/modules/core/src/math/matrix/vpMatrix.cpp index cb7885d26f..d238d8e998 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -197,7 +197,6 @@ vpMatrix::vpMatrix(const vpMatrix &M, unsigned int r, unsigned int c, unsigned i init(M, r, c, nrows, ncols); } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix::vpMatrix(vpMatrix &&A) : vpArray2D() { rowNum = A.rowNum; @@ -224,11 +223,9 @@ vpMatrix::vpMatrix(vpMatrix &&A) : vpArray2D() int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix M( {-1, -2, -3, 4, 5.5, 6.0f} ); M.reshape(2, 3); std::cout << "M:\n" << M << std::endl; -#endif } \endcode It produces the following output: @@ -251,10 +248,8 @@ vpMatrix::vpMatrix(const std::initializer_list &list) : vpArray2D= VISP_CXX_STANDARD_11) vpMatrix M(2, 3, {-1, -2, -3, 4, 5.5, 6}); std::cout << "M:\n" << M << std::endl; -#endif } \endcode It produces the following output: @@ -277,10 +272,8 @@ vpMatrix::vpMatrix(unsigned int nrows, unsigned int ncols, const std::initialize int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix M( { {-1, -2, -3}, {4, 5.5, 6} } ); std::cout << "M:\n" << M << std::endl; -#endif } \endcode It produces the following output: @@ -292,8 +285,6 @@ std::cout << "M:\n" << M << std::endl; */ vpMatrix::vpMatrix(const std::initializer_list > &lists) : vpArray2D(lists) { } -#endif - /*! Initialize the matrix from a part of an input matrix \e M. @@ -658,7 +649,6 @@ vpMatrix &vpMatrix::operator=(const vpArray2D &A) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix &vpMatrix::operator=(const vpMatrix &A) { resize(A.getRows(), A.getCols(), false, false); @@ -765,7 +755,6 @@ vpMatrix &vpMatrix::operator=(const std::initializer_list int main() @@ -5029,7 +5018,7 @@ int main() int rank_out = A.pseudoInverse(A_p, sv, rank_in, imA, imAt, kerAt); if (rank_out != rank_in) { std::cout << "There is a possibility that the pseudo-inverse in wrong." << std::endl; -std::cout << "Are you sure that the matrix rank is " << rank_in << std::endl; + std::cout << "Are you sure that the matrix rank is " << rank_in << std::endl; } A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); diff --git a/modules/core/src/math/matrix/vpRowVector.cpp b/modules/core/src/math/matrix/vpRowVector.cpp index 30561703c7..2fda61340a 100644 --- a/modules/core/src/math/matrix/vpRowVector.cpp +++ b/modules/core/src/math/matrix/vpRowVector.cpp @@ -122,7 +122,6 @@ vpRowVector &vpRowVector::operator=(double x) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRowVector &vpRowVector::operator=(vpRowVector &&other) { if (this != &other) { @@ -169,7 +168,6 @@ vpRowVector &vpRowVector::operator=(const std::initializer_list &list) std::copy(list.begin(), list.end(), data); return *this; } -#endif bool vpRowVector::operator==(const vpRowVector &v) const { @@ -578,7 +576,6 @@ vpRowVector::vpRowVector(const vpRowVector &v, unsigned int c, unsigned int ncol init(v, c, ncols); } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRowVector::vpRowVector(vpRowVector &&v) : vpArray2D() { rowNum = v.rowNum; @@ -593,10 +590,9 @@ vpRowVector::vpRowVector(vpRowVector &&v) : vpArray2D() v.dsize = 0; v.data = NULL; } -#endif /*! - Normalise the vector given as input parameter and return the normalized + Normalize the vector given as input parameter and return the normalized vector: \f[ diff --git a/modules/core/src/math/misc/vpMath.cpp b/modules/core/src/math/misc/vpMath.cpp index ba6b5a12a0..7c3855cc15 100644 --- a/modules/core/src/math/misc/vpMath.cpp +++ b/modules/core/src/math/misc/vpMath.cpp @@ -351,11 +351,7 @@ double vpMath::getStdev(const std::vector &v, bool useBesselCorrection) double mean = getMean(v); std::vector diff(v.size()); -#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 std::transform(v.begin(), v.end(), diff.begin(), std::bind(std::minus(), std::placeholders::_1, mean)); -#else - std::transform(v.begin(), v.end(), diff.begin(), std::bind2nd(std::minus(), mean)); -#endif double sq_sum = std::inner_product(diff.begin(), diff.end(), diff.begin(), 0.0); double divisor = (double)v.size(); @@ -580,11 +576,8 @@ std::vector > vpMath::computeRegularPointsOnSphere(uns double d_phi = a / d_theta; std::vector > lonlat_vec; -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) lonlat_vec.reserve(static_cast(std::sqrt(maxPoints))); -#else - lonlat_vec.reserve(static_cast(std::sqrt(static_cast(maxPoints)))); -#endif + for (int m = 0; m < m_theta; m++) { double theta = M_PI * (m + 0.5) / m_theta; int m_phi = static_cast(round(2.0 * M_PI * sin(theta) / d_phi)); diff --git a/modules/core/src/math/robust/vpRobust.cpp b/modules/core/src/math/robust/vpRobust.cpp index 652840ca5d..14fcf12cf6 100644 --- a/modules/core/src/math/robust/vpRobust.cpp +++ b/modules/core/src/math/robust/vpRobust.cpp @@ -59,11 +59,10 @@ vpRobust::vpRobust() : m_normres(), m_sorted_normres(), m_sorted_residues(), m_mad_min(0.0017), m_mad_prev(0), #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) - m_iter(0), + m_iter(0), #endif - m_size(0), m_mad(0) -{ -} + m_size(0), m_mad(0) +{ } /*! Copy constructor. @@ -88,7 +87,6 @@ vpRobust &vpRobust::operator=(const vpRobust &other) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Move operator. */ @@ -105,7 +103,6 @@ vpRobust &vpRobust::operator=(const vpRobust &&other) m_size = std::move(other.m_size); return *this; } -#endif /*! Resize containers. @@ -205,7 +202,8 @@ void vpRobust::psiTukey(double sig, const vpColVector &x, vpColVector &weights) if (xi > 1.) { weights[i] = 0; - } else { + } + else { xi = 1 - xi; xi *= xi; weights[i] = xi; @@ -312,9 +310,9 @@ double vpRobust::select(vpColVector &a, int l, int r, int k) vpRobust::vpRobust(unsigned int n_data) : m_normres(), m_sorted_normres(), m_sorted_residues(), m_mad_min(0.0017), m_mad_prev(0), #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) - m_iter(0), + m_iter(0), #endif - m_size(n_data), m_mad(0) + m_size(n_data), m_mad(0) { vpCDEBUG(2) << "vpRobust constructor reached" << std::endl; @@ -441,8 +439,9 @@ vpColVector vpRobust::simultMEstimator(vpColVector &residues) double normmedian = select(norm_res, 0, n_data - 1, ind_med); // Normalized Median // 1.48 keeps scale estimate consistent for a normal probability dist. m_mad = 1.4826 * normmedian; // Median Absolute Deviation - } else { - // compute simultaneous scale estimate + } + else { + // compute simultaneous scale estimate m_mad = simultscale(residues); } @@ -546,9 +545,10 @@ double vpRobust::constrainedChiTukey(double x) // sct = // (vpMath::sqr(s*a-x)*vpMath::sqr(s*a+x)*vpMath::sqr(x))/(s*vpMath::sqr(vpMath::sqr(a*vpMath::sqr(s)))); sct = (vpMath::sqr(s * a) * x - s * vpMath::sqr(s * a) - x * vpMath::sqr(x)) * - (vpMath::sqr(s * a) * x + s * vpMath::sqr(s * a) - x * vpMath::sqr(x)) / s * - vpMath::sqr(vpMath::sqr(vpMath::sqr(s))) / vpMath::sqr(vpMath::sqr(a)); - } else + (vpMath::sqr(s * a) * x + s * vpMath::sqr(s * a) - x * vpMath::sqr(x)) / s * + vpMath::sqr(vpMath::sqr(vpMath::sqr(s))) / vpMath::sqr(vpMath::sqr(a)); + } + else sct = -1 / s; return sct; @@ -589,8 +589,9 @@ double vpRobust::simult_chi_huber(double x) if (fabs(u) <= c) { // sct = 0.5*vpMath::sqr(u); sct = vpMath::sqr(u); - } else { - // sct = 0.5*vpMath::sqr(c); + } + else { + // sct = 0.5*vpMath::sqr(c); sct = vpMath::sqr(c); } @@ -609,7 +610,8 @@ double vpRobust::gammp(double a, double x) if (x < (a + 1.0)) { gser(&gamser, a, x, &gln); return gamser; - } else { + } + else { gcf(&gammcf, a, x, &gln); return 1.0 - gammcf; } @@ -623,7 +625,8 @@ void vpRobust::gser(double *gamser, double a, double x, double *gln) std::cout << "x less than 0 in routine GSER"; *gamser = 0.0; return; - } else { + } + else { double ap = a; double sum = 1.0 / a; double del = sum; @@ -673,7 +676,7 @@ void vpRobust::gcf(double *gammcf, double a, double x, double *gln) double vpRobust::gammln(double xx) { double x, tmp, ser; - static double cof[6] = {76.18009173, -86.50532033, 24.01409822, -1.231739516, 0.120858003e-2, -0.536382e-5}; + static double cof[6] = { 76.18009173, -86.50532033, 24.01409822, -1.231739516, 0.120858003e-2, -0.536382e-5 }; x = xx - 1.0; tmp = x + 5.5; diff --git a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp index 061a36c035..ddc87caa35 100644 --- a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp @@ -148,7 +148,6 @@ vpHomogeneousMatrix::vpHomogeneousMatrix(const std::vector &v) : vpArray2 (*this)[3][3] = 1.; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Construct an homogeneous matrix from a list of 12 or 16 double values. \param list : List of double. @@ -158,7 +157,6 @@ vpHomogeneousMatrix::vpHomogeneousMatrix(const std::vector &v) : vpArray2 int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpHomogeneousMatrix M { 0, 0, 1, 0.1, 0, 1, 0, 0.2, @@ -170,7 +168,6 @@ int main() 1, 0, 0, 0.3, 0, 0, 0, 1 }; std::cout << "N:\n" << N << std::endl; -#endif } \endcode It produces the following output: @@ -243,7 +240,6 @@ vpHomogeneousMatrix::vpHomogeneousMatrix(const std::initializer_list &li } } } -#endif /*! Construct an homogeneous matrix from a vector of double. diff --git a/modules/core/src/math/transformation/vpQuaternionVector.cpp b/modules/core/src/math/transformation/vpQuaternionVector.cpp index 7bf8bd44af..64268a6617 100644 --- a/modules/core/src/math/transformation/vpQuaternionVector.cpp +++ b/modules/core/src/math/transformation/vpQuaternionVector.cpp @@ -52,10 +52,10 @@ const double vpQuaternionVector::minimum = 0.0001; */ /*! Default constructor that initialize all the 4 angles to zero. */ -vpQuaternionVector::vpQuaternionVector() : vpRotationVector(4) {} +vpQuaternionVector::vpQuaternionVector() : vpRotationVector(4) { } /*! Copy constructor. */ -vpQuaternionVector::vpQuaternionVector(const vpQuaternionVector &q) : vpRotationVector(q) {} +vpQuaternionVector::vpQuaternionVector(const vpQuaternionVector &q) : vpRotationVector(q) { } //! Constructor from doubles. vpQuaternionVector::vpQuaternionVector(double x_, double y_, double z_, double w_) : vpRotationVector(4) @@ -281,7 +281,8 @@ vpQuaternionVector vpQuaternionVector::inverse() const double mag_square = w() * w() + x() * x() + y() * y() + z() * z(); if (!vpMath::nul(mag_square, std::numeric_limits::epsilon())) { q_inv = this->conjugate() / mag_square; - } else { + } + else { std::cerr << "The current quaternion is null ! The inverse cannot be computed !" << std::endl; } @@ -314,30 +315,29 @@ void vpQuaternionVector::normalize() \return The dot product between q0 and q1. */ -double vpQuaternionVector::dot(const vpQuaternionVector& q0, const vpQuaternionVector& q1) +double vpQuaternionVector::dot(const vpQuaternionVector &q0, const vpQuaternionVector &q1) { return q0.x() * q1.x() + q0.y() * q1.y() + q0.z() * q1.z() + q0.w() * q1.w(); } //! Returns the x-component of the quaternion. -const double& vpQuaternionVector::x() const { return data[0]; } +const double &vpQuaternionVector::x() const { return data[0]; } //! Returns the y-component of the quaternion. -const double& vpQuaternionVector::y() const { return data[1]; } +const double &vpQuaternionVector::y() const { return data[1]; } //! Returns the z-component of the quaternion. -const double& vpQuaternionVector::z() const { return data[2]; } +const double &vpQuaternionVector::z() const { return data[2]; } //! Returns the w-component of the quaternion. -const double& vpQuaternionVector::w() const { return data[3]; } +const double &vpQuaternionVector::w() const { return data[3]; } //! Returns a reference to the x-component of the quaternion. -double& vpQuaternionVector::x() { return data[0]; } +double &vpQuaternionVector::x() { return data[0]; } //! Returns a reference to the y-component of the quaternion. -double& vpQuaternionVector::y() { return data[1]; } +double &vpQuaternionVector::y() { return data[1]; } //! Returns a reference to the z-component of the quaternion. -double& vpQuaternionVector::z() { return data[2]; } +double &vpQuaternionVector::z() { return data[2]; } //! Returns a reference to the w-component of the quaternion. -double& vpQuaternionVector::w() { return data[3]; } +double &vpQuaternionVector::w() { return data[3]; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Set vector from a list of 4 double angle values. \code @@ -359,14 +359,13 @@ vpQuaternionVector &vpQuaternionVector::operator=(const std::initializer_list size()) { throw(vpException( - vpException::dimensionError, - "Cannot set quaternion vector out of bounds. It has only %d values while you try to initialize with %d values", - size(), list.size())); + vpException::dimensionError, + "Cannot set quaternion vector out of bounds. It has only %d values while you try to initialize with %d values", + size(), list.size())); } std::copy(list.begin(), list.end(), data); return *this; } -#endif /*! Compute Quaternion Linear intERPolation (LERP). @@ -440,7 +439,7 @@ vpQuaternionVector vpQuaternionVector::nlerp(const vpQuaternionVector &q0, const \return The interpolated quaternion using the SLERP method. */ -vpQuaternionVector vpQuaternionVector::slerp(const vpQuaternionVector& q0, const vpQuaternionVector& q1, double t) +vpQuaternionVector vpQuaternionVector::slerp(const vpQuaternionVector &q0, const vpQuaternionVector &q1, double t) { assert(t >= 0 && t <= 1); // Some additional references: diff --git a/modules/core/src/math/transformation/vpRotationMatrix.cpp b/modules/core/src/math/transformation/vpRotationMatrix.cpp index 074dd1bb8f..d2e996dba7 100644 --- a/modules/core/src/math/transformation/vpRotationMatrix.cpp +++ b/modules/core/src/math/transformation/vpRotationMatrix.cpp @@ -89,7 +89,6 @@ vpRotationMatrix &vpRotationMatrix::operator=(const vpRotationMatrix &R) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Set a rotation matrix from a list of 9 double values. \param list : List of double. @@ -99,11 +98,9 @@ vpRotationMatrix &vpRotationMatrix::operator=(const vpRotationMatrix &R) int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRotationMatrix R R = { 0, 0, -1, 0, -1, 0, -1, 0, 0 }; std::cout << "R:\n" << R << std::endl; -#endif } \endcode It produces the following output: @@ -137,7 +134,6 @@ vpRotationMatrix &vpRotationMatrix::operator=(const std::initializer_list(3, 3), m_index(0) { buildFrom(q); } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Construct a rotation matrix from a list of 9 double values. \param list : List of double. @@ -549,10 +544,8 @@ vpRotationMatrix::vpRotationMatrix(const vpQuaternionVector &q) : vpArray2D= VISP_CXX_STANDARD_11) vpRotationMatrix R{ 0, 0, -1, 0, -1, 0, -1, 0, 0 }; std::cout << "R:\n" << R << std::endl; -#endif } \endcode It produces the following output: @@ -577,7 +570,6 @@ vpRotationMatrix::vpRotationMatrix(const std::initializer_list &list) } } } -#endif /*! Return the rotation matrix transpose which is also the inverse of the diff --git a/modules/core/src/math/transformation/vpRxyzVector.cpp b/modules/core/src/math/transformation/vpRxyzVector.cpp index 4f026d9a80..d4c48da25d 100644 --- a/modules/core/src/math/transformation/vpRxyzVector.cpp +++ b/modules/core/src/math/transformation/vpRxyzVector.cpp @@ -45,10 +45,10 @@ */ /*! Default constructor that initialize all the 3 angles to zero. */ -vpRxyzVector::vpRxyzVector() : vpRotationVector(3) {} +vpRxyzVector::vpRxyzVector() : vpRotationVector(3) { } /*! Copy constructor. */ -vpRxyzVector::vpRxyzVector(const vpRxyzVector &rxyz) : vpRotationVector(rxyz) {} +vpRxyzVector::vpRxyzVector(const vpRxyzVector &rxyz) : vpRotationVector(rxyz) { } /*! Constructor from 3 angles (in radian). @@ -226,7 +226,6 @@ vpRxyzVector &vpRxyzVector::operator=(const vpColVector &rxyz) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Set vector from a list of 3 double angle values in radians. \code @@ -248,11 +247,10 @@ vpRxyzVector &vpRxyzVector::operator=(const std::initializer_list &list) { if (list.size() > size()) { throw(vpException( - vpException::dimensionError, - "Cannot set Euler x-y-z vector out of bounds. It has only %d values while you try to initialize with %d values", - size(), list.size())); + vpException::dimensionError, + "Cannot set Euler x-y-z vector out of bounds. It has only %d values while you try to initialize with %d values", + size(), list.size())); } std::copy(list.begin(), list.end(), data); return *this; } -#endif diff --git a/modules/core/src/math/transformation/vpRzyxVector.cpp b/modules/core/src/math/transformation/vpRzyxVector.cpp index ed6243ab34..69dbae4959 100644 --- a/modules/core/src/math/transformation/vpRzyxVector.cpp +++ b/modules/core/src/math/transformation/vpRzyxVector.cpp @@ -44,10 +44,10 @@ */ /*! Default constructor that initialize all the 3 angles to zero. */ -vpRzyxVector::vpRzyxVector() : vpRotationVector(3) {} +vpRzyxVector::vpRzyxVector() : vpRotationVector(3) { } /*! Copy constructor. */ -vpRzyxVector::vpRzyxVector(const vpRzyxVector &rzyx) : vpRotationVector(rzyx) {} +vpRzyxVector::vpRzyxVector(const vpRzyxVector &rzyx) : vpRotationVector(rzyx) { } /*! Constructor from 3 angles (in radian). @@ -232,7 +232,6 @@ vpRzyxVector &vpRzyxVector::operator=(const vpColVector &rzyx) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Set vector from a list of 3 double angle values in radians. \code @@ -254,11 +253,10 @@ vpRzyxVector &vpRzyxVector::operator=(const std::initializer_list &list) { if (list.size() > size()) { throw(vpException( - vpException::dimensionError, - "Cannot set Euler x-y-z vector out of bounds. It has only %d values while you try to initialize with %d values", - size(), list.size())); + vpException::dimensionError, + "Cannot set Euler x-y-z vector out of bounds. It has only %d values while you try to initialize with %d values", + size(), list.size())); } std::copy(list.begin(), list.end(), data); return *this; } -#endif diff --git a/modules/core/src/math/transformation/vpRzyzVector.cpp b/modules/core/src/math/transformation/vpRzyzVector.cpp index 0d68df40e2..50fd92dab4 100644 --- a/modules/core/src/math/transformation/vpRzyzVector.cpp +++ b/modules/core/src/math/transformation/vpRzyzVector.cpp @@ -44,9 +44,9 @@ */ /*! Default constructor that initialize all the 3 angles to zero. */ -vpRzyzVector::vpRzyzVector() : vpRotationVector(3) {} +vpRzyzVector::vpRzyzVector() : vpRotationVector(3) { } /*! Copy constructor. */ -vpRzyzVector::vpRzyzVector(const vpRzyzVector &rzyz) : vpRotationVector(rzyz) {} +vpRzyzVector::vpRzyzVector(const vpRzyzVector &rzyz) : vpRotationVector(rzyz) { } /*! Constructor from 3 angles (in radian). @@ -223,7 +223,6 @@ vpRzyzVector &vpRzyzVector::operator=(const vpColVector &rzyz) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Set vector from a list of 3 double angle values in radians. \code @@ -245,11 +244,10 @@ vpRzyzVector &vpRzyzVector::operator=(const std::initializer_list &list) { if (list.size() > size()) { throw(vpException( - vpException::dimensionError, - "Cannot set Euler x-y-z vector out of bounds. It has only %d values while you try to initialize with %d values", - size(), list.size())); + vpException::dimensionError, + "Cannot set Euler x-y-z vector out of bounds. It has only %d values while you try to initialize with %d values", + size(), list.size())); } std::copy(list.begin(), list.end(), data); return *this; } -#endif diff --git a/modules/core/src/math/transformation/vpThetaUVector.cpp b/modules/core/src/math/transformation/vpThetaUVector.cpp index 88e1a05cde..04731f48e7 100644 --- a/modules/core/src/math/transformation/vpThetaUVector.cpp +++ b/modules/core/src/math/transformation/vpThetaUVector.cpp @@ -47,9 +47,9 @@ rotation const double vpThetaUVector::minimum = 0.0001; /*! Default constructor that initialize all the 3 angles to zero. */ -vpThetaUVector::vpThetaUVector() : vpRotationVector(3) {} +vpThetaUVector::vpThetaUVector() : vpRotationVector(3) { } /*! Copy constructor. */ -vpThetaUVector::vpThetaUVector(const vpThetaUVector &tu) : vpRotationVector(tu) {} +vpThetaUVector::vpThetaUVector(const vpThetaUVector &tu) : vpRotationVector(tu) { } /*! Copy constructor from a 3-dimension vector. */ vpThetaUVector::vpThetaUVector(const vpColVector &tu) : vpRotationVector(3) { buildFrom(tu); } /*! @@ -137,7 +137,7 @@ vpThetaUVector vpThetaUVector::buildFrom(const vpRotationMatrix &R) double s, c, theta; s = (R[1][0] - R[0][1]) * (R[1][0] - R[0][1]) + (R[2][0] - R[0][2]) * (R[2][0] - R[0][2]) + - (R[2][1] - R[1][2]) * (R[2][1] - R[1][2]); + (R[2][1] - R[1][2]) * (R[2][1] - R[1][2]); s = sqrt(s) / 2.0; c = (R[0][0] + R[1][1] + R[2][2] - 1.0) / 2.0; theta = atan2(s, c); /* theta in [0, PI] since s > 0 */ @@ -150,7 +150,8 @@ vpThetaUVector vpThetaUVector::buildFrom(const vpRotationMatrix &R) data[0] = (R[2][1] - R[1][2]) / (2 * sinc); data[1] = (R[0][2] - R[2][0]) / (2 * sinc); data[2] = (R[1][0] - R[0][1]) / (2 * sinc); - } else /* theta near PI */ + } + else /* theta near PI */ { double x = 0; if ((R[0][0] - c) > std::numeric_limits::epsilon()) @@ -171,14 +172,16 @@ vpThetaUVector vpThetaUVector::buildFrom(const vpRotationMatrix &R) y = -y; if (vpMath::sign(x) * vpMath::sign(z) != vpMath::sign(R[0][2] + R[2][0])) z = -z; - } else if (y > z) { + } + else if (y > z) { if ((R[0][2] - R[2][0]) < 0) y = -y; if (vpMath::sign(y) * vpMath::sign(x) != vpMath::sign(R[1][0] + R[0][1])) x = -x; if (vpMath::sign(y) * vpMath::sign(z) != vpMath::sign(R[1][2] + R[2][1])) z = -z; - } else { + } + else { if ((R[1][0] - R[0][1]) < 0) z = -z; if (vpMath::sign(z) * vpMath::sign(x) != vpMath::sign(R[2][0] + R[0][2])) @@ -458,13 +461,12 @@ vpThetaUVector vpThetaUVector::operator*(const vpThetaUVector &tu_b) const vpColVector b_hat_sin_2 = b_hat * std::sin(b_2); double c = 2 * std::acos(std::cos(a_2) * std::cos(b_2) - vpColVector::dotProd(a_hat_sin_2, b_hat_sin_2)); vpColVector d = std::sin(a_2) * std::cos(b_2) * a_hat + std::cos(a_2) * std::sin(b_2) * b_hat + - std::sin(a_2) * std::sin(b_2) * vpColVector::crossProd(a_hat, b_hat); + std::sin(a_2) * std::sin(b_2) * vpColVector::crossProd(a_hat, b_hat); d = c * d / std::sin(c / 2); return vpThetaUVector(d); } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Set vector from a list of 3 double angle values in radians. \code @@ -486,11 +488,10 @@ vpThetaUVector &vpThetaUVector::operator=(const std::initializer_list &l { if (list.size() > size()) { throw(vpException( - vpException::dimensionError, - "Cannot set theta u vector out of bounds. It has only %d values while you try to initialize with %d values", - size(), list.size())); + vpException::dimensionError, + "Cannot set theta u vector out of bounds. It has only %d values while you try to initialize with %d values", + size(), list.size())); } std::copy(list.begin(), list.end(), data); return *this; } -#endif diff --git a/modules/core/src/math/transformation/vpTranslationVector.cpp b/modules/core/src/math/transformation/vpTranslationVector.cpp index 19767242a8..2f1babf15e 100644 --- a/modules/core/src/math/transformation/vpTranslationVector.cpp +++ b/modules/core/src/math/transformation/vpTranslationVector.cpp @@ -506,7 +506,6 @@ vpTranslationVector &vpTranslationVector::operator=(double x) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Set vector from a list of 3 double values in meters. \code @@ -535,7 +534,6 @@ vpTranslationVector &vpTranslationVector::operator=(const std::initializer_list< std::copy(list.begin(), list.end(), data); return *this; } -#endif /*! Set vector first element value. diff --git a/modules/core/src/tools/file/vpIoTools.cpp b/modules/core/src/tools/file/vpIoTools.cpp index 11910f1817..a5d90de5f5 100644 --- a/modules/core/src/tools/file/vpIoTools.cpp +++ b/modules/core/src/tools/file/vpIoTools.cpp @@ -130,25 +130,18 @@ void replaceAll(std::string &str, const std::string &search, const std::string & std::string <rim(std::string &s) { -#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 s.erase(s.begin(), std::find_if(s.begin(), s.end(), [](int c) { return !std::isspace(c); })); -#else - s.erase(s.begin(), std::find_if(s.begin(), s.end(), std::not1(std::ptr_fun(std::isspace)))); -#endif + return s; } std::string &rtrim(std::string &s) { -#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 s.erase(std::find_if(s.rbegin(), s.rend(), [](int c) { return !std::isspace(c); }).base(), s.end()); -#else - s.erase(std::find_if(s.rbegin(), s.rend(), std::not1(std::ptr_fun(std::isspace))).base(), s.end()); -#endif return s; } } // namespace @@ -1694,15 +1687,9 @@ std::string vpIoTools::getParent(const std::string &pathname) std::string vpIoTools::toLowerCase(const std::string &input) { std::string out; -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - for (size_t i = 0; i < input.size(); i++) { - out += std::tolower(input[i]); - } -#else for (std::string::const_iterator it = input.cbegin(); it != input.cend(); it++) { out += std::tolower(*it); } -#endif return out; } @@ -1717,15 +1704,9 @@ std::string vpIoTools::toLowerCase(const std::string &input) std::string vpIoTools::toUpperCase(const std::string &input) { std::string out; -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - for (size_t i = 0; i < input.size(); i++) { - out += std::toupper(input[i]); - } -#else for (std::string::const_iterator it = input.cbegin(); it != input.cend(); it++) { out += std::toupper(*it); } -#endif return out; } diff --git a/modules/core/src/tools/geometry/vpPolygon.cpp b/modules/core/src/tools/geometry/vpPolygon.cpp index 99d14fa690..ed23cd6642 100644 --- a/modules/core/src/tools/geometry/vpPolygon.cpp +++ b/modules/core/src/tools/geometry/vpPolygon.cpp @@ -67,14 +67,10 @@ template std::vector convexHull(const IpCon std::transform(cbegin(ips), cend(ips), std::back_inserter(cv_pts), [](const vpImagePoint &ip) { return cv::Point(static_cast(ip.get_u()), static_cast(ip.get_v())); }); -#elif (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#else std::transform(begin(ips), end(ips), std::back_inserter(cv_pts), [](const vpImagePoint &ip) { return cv::Point(static_cast(ip.get_u()), static_cast(ip.get_v())); }); -#else - for (typename IpContainer::const_iterator it = ips.begin(); it != ips.end(); ++it) { - cv_pts.push_back(cv::Point(static_cast(it->get_u()), static_cast(it->get_v()))); - } #endif // Get convex hull from OpenCV @@ -86,18 +82,13 @@ template std::vector convexHull(const IpCon #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_14) std::transform(cbegin(cv_conv_hull_corners), cend(cv_conv_hull_corners), std::back_inserter(conv_hull_corners), [](const cv::Point &pt) { - return vpImagePoint{static_cast(pt.y), static_cast(pt.x)}; + return vpImagePoint { static_cast(pt.y), static_cast(pt.x) }; }); -#elif (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#else std::transform(begin(cv_conv_hull_corners), end(cv_conv_hull_corners), std::back_inserter(conv_hull_corners), [](const cv::Point &pt) { - return vpImagePoint{static_cast(pt.y), static_cast(pt.x)}; + return vpImagePoint { static_cast(pt.y), static_cast(pt.x) }; }); -#else - for (std::vector::const_iterator it = cv_conv_hull_corners.begin(); it != cv_conv_hull_corners.end(); - ++it) { - conv_hull_corners.push_back(vpImagePoint(static_cast(it->y), static_cast(it->x))); - } #endif return conv_hull_corners; @@ -110,8 +101,7 @@ template std::vector convexHull(const IpCon */ vpPolygon::vpPolygon() : _corners(), _center(), _area(0.), _goodPoly(true), _bbox(), m_PnPolyConstants(), m_PnPolyMultiples() -{ -} +{ } /*! Constructor which initialises the polygon thanks to the given corners. @@ -154,14 +144,13 @@ vpPolygon::vpPolygon(const std::list &corners) */ vpPolygon::vpPolygon(const vpPolygon &poly) : _corners(poly._corners), _center(poly._center), _area(poly._area), _goodPoly(poly._goodPoly), _bbox(poly._bbox), - m_PnPolyConstants(poly.m_PnPolyConstants), m_PnPolyMultiples(poly.m_PnPolyMultiples) -{ -} + m_PnPolyConstants(poly.m_PnPolyConstants), m_PnPolyMultiples(poly.m_PnPolyMultiples) +{ } /*! Basic destructor */ -vpPolygon::~vpPolygon() {} +vpPolygon::~vpPolygon() { } /*! Equal operator. @@ -197,7 +186,8 @@ void vpPolygon::buildFrom(const std::vector &corners, const bool c #else vpException(vpException::notImplementedError, "Cannot build a convex hull without OpenCV imgproc module"); #endif - } else { + } + else { init(corners); } } @@ -219,7 +209,8 @@ void vpPolygon::buildFrom(const std::list &corners, const bool cre #else vpException(vpException::notImplementedError, "Cannot build a convex hull without OpenCV imgproc module"); #endif - } else { + } + else { init(corners); } } @@ -423,7 +414,8 @@ bool vpPolygon::isInside(const vpImagePoint &ip, const PointInPolygonMethod &met try { intersection = testIntersectionSegments(ip1, ip2, ip, infPoint); - } catch (...) { + } + catch (...) { return isInside(ip); } @@ -468,10 +460,11 @@ void vpPolygon::precalcValuesPnPoly() if (vpMath::equal(_corners[j].get_v(), _corners[i].get_v(), std::numeric_limits::epsilon())) { m_PnPolyConstants[i] = _corners[i].get_u(); m_PnPolyMultiples[i] = 0.0; - } else { + } + else { m_PnPolyConstants[i] = _corners[i].get_u() - - (_corners[i].get_v() * _corners[j].get_u()) / (_corners[j].get_v() - _corners[i].get_v()) + - (_corners[i].get_v() * _corners[i].get_u()) / (_corners[j].get_v() - _corners[i].get_v()); + (_corners[i].get_v() * _corners[j].get_u()) / (_corners[j].get_v() - _corners[i].get_v()) + + (_corners[i].get_v() * _corners[i].get_u()) / (_corners[j].get_v() - _corners[i].get_v()); m_PnPolyMultiples[i] = (_corners[j].get_u() - _corners[i].get_u()) / (_corners[j].get_v() - _corners[i].get_v()); } @@ -529,28 +522,29 @@ void vpPolygon::updateCenter() double i_tmp = 0; double j_tmp = 0; #if 0 - for(unsigned int i=0; i<(_corners.size()-1); ++i){ + for (unsigned int i = 0; i<(_corners.size()-1); ++i) { i_tmp += (_corners[i].get_i() + _corners[i+1].get_i()) * - (_corners[i+1].get_i() * _corners[i].get_j() - _corners[i+1].get_j() * _corners[i].get_i()); + (_corners[i+1].get_i() * _corners[i].get_j() - _corners[i+1].get_j() * _corners[i].get_i()); j_tmp += (_corners[i].get_j() + _corners[i+1].get_j()) * - (_corners[i+1].get_i() * _corners[i].get_j() - _corners[i+1].get_j() * _corners[i].get_i()); + (_corners[i+1].get_i() * _corners[i].get_j() - _corners[i+1].get_j() * _corners[i].get_i()); } #else for (unsigned int i = 0; i < _corners.size(); ++i) { unsigned int i_p_1 = (i + 1) % _corners.size(); i_tmp += (_corners[i].get_i() + _corners[i_p_1].get_i()) * - (_corners[i_p_1].get_i() * _corners[i].get_j() - _corners[i_p_1].get_j() * _corners[i].get_i()); + (_corners[i_p_1].get_i() * _corners[i].get_j() - _corners[i_p_1].get_j() * _corners[i].get_i()); j_tmp += (_corners[i].get_j() + _corners[i_p_1].get_j()) * - (_corners[i_p_1].get_i() * _corners[i].get_j() - _corners[i_p_1].get_j() * _corners[i].get_i()); + (_corners[i_p_1].get_i() * _corners[i].get_j() - _corners[i_p_1].get_j() * _corners[i].get_i()); } #endif if (_area > 0) { _center.set_i(fabs(i_tmp / (6 * _area))); _center.set_j(fabs(j_tmp / (6 * _area))); - } else { + } + else { _center = _corners[0]; _goodPoly = false; } diff --git a/modules/core/src/tools/geometry/vpRectOriented.cpp b/modules/core/src/tools/geometry/vpRectOriented.cpp index f7dc9862e4..480e5fe6fb 100644 --- a/modules/core/src/tools/geometry/vpRectOriented.cpp +++ b/modules/core/src/tools/geometry/vpRectOriented.cpp @@ -82,30 +82,7 @@ vpRectOriented::vpRectOriented(const vpRect &rect) m_topRight.set_j(m_center.get_j() + m_width / 2.0); } -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) -/** Copy constructor. - * @param rectOriented Oriented rectangle to copy. - */ -vpRectOriented::vpRectOriented(const vpRectOriented &rectOriented) { *this = rectOriented; } - -/** Assignement operator. - * @param rectOriented Oriented rectangle to copy. - */ -vpRectOriented &vpRectOriented::operator=(const vpRectOriented &rectOriented) -{ - m_center = rectOriented.getCenter(); - m_width = rectOriented.getWidth(); - m_height = rectOriented.getHeight(); - m_theta = rectOriented.getOrientation(); - m_topLeft = rectOriented.getTopLeft(); - m_bottomLeft = rectOriented.getBottomLeft(); - m_bottomRight = rectOriented.getBottomRight(); - m_topRight = rectOriented.getTopRight(); - return *this; -} -#endif - -/** Assignement operator from vpRect. +/** Assignment operator from vpRect. * @param rect Rectangle to copy. */ vpRectOriented &vpRectOriented::operator=(const vpRect &rect) diff --git a/modules/core/src/tools/optimization/vpLinProg.cpp b/modules/core/src/tools/optimization/vpLinProg.cpp index 7929acd959..0510854830 100644 --- a/modules/core/src/tools/optimization/vpLinProg.cpp +++ b/modules/core/src/tools/optimization/vpLinProg.cpp @@ -277,7 +277,6 @@ bool vpLinProg::rowReduction(vpMatrix &A, vpColVector &b, const double &tol) return false; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Solves a Linear Program under various constraints @@ -303,9 +302,6 @@ bool vpLinProg::rowReduction(vpMatrix &A, vpColVector &b, const double &tol) Lower and upper bounds may be passed as a list of (index, bound) with C++11's braced initialization. - \warning This function is only available if c++11 or higher is activated during compilation. Configure ViSP using -cmake -DUSE_CXX_STANDARD=11. - Here is an example: \f$\begin{array}{lll} @@ -727,4 +723,3 @@ bool vpLinProg::simplex(const vpColVector &c, vpMatrix A, vpColVector b, vpColVe std::swap(B[k], N[j]); } } -#endif diff --git a/modules/core/src/tools/optimization/vpQuadProg.cpp b/modules/core/src/tools/optimization/vpQuadProg.cpp index e463bf596d..a7feb40b91 100644 --- a/modules/core/src/tools/optimization/vpQuadProg.cpp +++ b/modules/core/src/tools/optimization/vpQuadProg.cpp @@ -40,8 +40,6 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - /*! Changes a canonical quadratic cost \f$\min \frac{1}{2}\mathbf{x}^T\mathbf{H}\mathbf{x} + \mathbf{c}^T\mathbf{x}\f$ to the formulation used by this class \f$ \min ||\mathbf{Q}\mathbf{x} - \mathbf{r}||^2\f$. @@ -127,7 +125,7 @@ void vpQuadProg::fromCanonicalCost(const vpMatrix &H, const vpColVector &c, vpMa r = -Q.t().pseudoInverse() * c; #else throw(vpException(vpException::functionNotImplementedError, "Symmetric matrix decomposition is not implemented. You " - "should install Lapack, Eigen3 or OpenCV 3rd party")); + "should install Lapack, Eigen3 or OpenCV 3rd party")); #endif } @@ -184,7 +182,8 @@ bool vpQuadProg::solveByProjection(const vpMatrix &Q, const vpColVector &r, vpMa x = b + A * (Q * A).solveBySVD(r - Q * b); else x = b; - } else + } + else x = Q.solveBySVD(r); return true; } @@ -246,7 +245,7 @@ bool vpQuadProg::solveQPe(const vpMatrix &Q, const vpColVector &r, vpColVector & unsigned int n = Q.getCols(); if (Q.getRows() != r.getRows() || Z.getRows() != n || x1.getRows() != n) { std::cout << "vpQuadProg::solveQPe: wrong dimension\n" - << "Q: " << Q.getRows() << "x" << Q.getCols() << " - r: " << r.getRows() << std::endl; + << "Q: " << Q.getRows() << "x" << Q.getCols() << " - r: " << r.getRows() << std::endl; std::cout << "Z: " << Z.getRows() << "x" << Z.getCols() << " - x1: " << x1.getRows() << std::endl; throw vpMatrixException::dimensionError; } @@ -255,7 +254,8 @@ bool vpQuadProg::solveQPe(const vpMatrix &Q, const vpColVector &r, vpColVector & x = x1 + Z * (Q * Z).solveBySVD(r - Q * x1); else x = x1; - } else + } + else x = Q.solveBySVD(r); return true; } @@ -386,7 +386,8 @@ bool vpQuadProg::solveQP(const vpMatrix &Q, const vpColVector &r, vpMatrix A, vp if (A.getCols() && solveQPi(Q * A, r - Q * b, C * A, d - C * b, x, false, tol)) { x = b + A * x; return true; - } else if (vpLinProg::allLesser(C, b, d, tol)) // Ax = b has only 1 solution + } + else if (vpLinProg::allLesser(C, b, d, tol)) // Ax = b has only 1 solution { x = b; return true; @@ -451,13 +452,15 @@ bool vpQuadProg::solveQPi(const vpMatrix &Q, const vpColVector &r, const vpMatri // back to initial solution x = x1 + Z * x; return true; - } else if (vpLinProg::allLesser(C, x1, d, tol)) { + } + else if (vpLinProg::allLesser(C, x1, d, tol)) { x = x1; return true; } std::cout << "vpQuadProg::solveQPi: inequality constraint infeasible" << std::endl; return false; - } else + } + else std::cout << "vpQuadProg::solveQPi: use_equality before setEqualityConstraint" << std::endl; } @@ -532,7 +535,8 @@ bool vpQuadProg::solveQPi(const vpMatrix &Q, const vpColVector &r, const vpMatri A_lp[i][2 * n + p + l] = -1; xc[2 * n + p + l] = -e[i]; l++; - } else + } + else xc[2 * n + i] = e[i]; } vpLinProg::simplex(c, A_lp, e, xc); @@ -555,7 +559,8 @@ bool vpQuadProg::solveQPi(const vpMatrix &Q, const vpColVector &r, const vpMatri else active.push_back(i); } - } else // warm start feasible + } + else // warm start feasible { // using previous active set, check that inactive is sync if (active.size() + inactive.size() != p) { @@ -616,7 +621,8 @@ bool vpQuadProg::solveQPi(const vpMatrix &Q, const vpColVector &r, const vpMatri else active.erase(active.begin() + ineqInd); update_Ap = true; - } else // u != 0, can improve xc + } + else // u != 0, can improve xc { unsigned int ineqInd = 0; // step length to next constraint @@ -638,11 +644,13 @@ bool vpQuadProg::solveQPi(const vpMatrix &Q, const vpColVector &r, const vpMatri while (it != active.end() && *it < inactive[ineqInd]) it++; active.insert(it, inactive[ineqInd]); - } else + } + else active.push_back(inactive[ineqInd]); inactive.erase(inactive.begin() + ineqInd); update_Ap = true; - } else + } + else update_Ap = false; // update x for next iteration x += alpha * u; @@ -668,6 +676,3 @@ vpColVector vpQuadProg::solveSVDorQR(const vpMatrix &A, const vpColVector &b) return A.solveBySVD(b); return A.solveByQR(b); } -#else -void dummy_vpQuadProg(){}; -#endif diff --git a/modules/core/src/tools/time/vpTime.cpp b/modules/core/src/tools/time/vpTime.cpp index 408f0c87ab..f1c58f4d91 100644 --- a/modules/core/src/tools/time/vpTime.cpp +++ b/modules/core/src/tools/time/vpTime.cpp @@ -39,8 +39,7 @@ #include // https://devblogs.microsoft.com/cppblog/c14-stl-features-fixes-and-breaking-changes-in-visual-studio-14-ctp1/ -#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 && \ - (defined(_MSC_VER) && _MSC_VER >= 1900 /* VS2015 */ || !defined(_MSC_VER)) +#if (defined(_MSC_VER) && _MSC_VER >= 1900 /* VS2015 */ || !defined(_MSC_VER)) #define USE_CXX11_CHRONO 1 #else #define USE_CXX11_CHRONO 0 diff --git a/modules/core/test/image/testImageOwnership.cpp b/modules/core/test/image/testImageOwnership.cpp index 3f384cd41d..be80db7ead 100644 --- a/modules/core/test/image/testImageOwnership.cpp +++ b/modules/core/test/image/testImageOwnership.cpp @@ -138,7 +138,6 @@ int main(int /* argc */, const char ** /* argv */) delete[] bitmap; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { unsigned char *bitmap = new unsigned char[12]; vpImage I = std::move(vpImage(bitmap, 3, 4, false)); @@ -157,8 +156,8 @@ int main(int /* argc */, const char ** /* argv */) } delete[] bitmap; } -#endif - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << "Exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/math/testJsonArrayConversion.cpp b/modules/core/test/math/testJsonArrayConversion.cpp index c1d51a1361..4a0c9195c7 100644 --- a/modules/core/test/math/testJsonArrayConversion.cpp +++ b/modules/core/test/math/testJsonArrayConversion.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_CATCH2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_CATCH2) #include #include diff --git a/modules/core/test/math/testMath.cpp b/modules/core/test/math/testMath.cpp index 9b9d6266ad..8fedb34bd7 100644 --- a/modules/core/test/math/testMath.cpp +++ b/modules/core/test/math/testMath.cpp @@ -602,21 +602,10 @@ int main() // Test clamp { -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) const double lower { -10. }, upper { +10. }; - std::vector testing_values{5., -15., 15.}; - std::vector expected_values{5., -10., 10.}; -#else - const double lower = -10., upper = +10.; - std::vector testing_values; - testing_values.push_back(5.); - testing_values.push_back(-15.); - testing_values.push_back(15.); - std::vector expected_values; - expected_values.push_back(5.); - expected_values.push_back(-10.); - expected_values.push_back(10.); -#endif + std::vector testing_values { 5., -15., 15. }; + std::vector expected_values { 5., -10., 10. }; + for (size_t i = 0u; i < testing_values.size(); i++) { const double clamp_val = vpMath::clamp(testing_values.at(i), lower, upper); diff --git a/modules/core/test/math/testMatrix.cpp b/modules/core/test/math/testMatrix.cpp index 44d610c409..f32ded2b3a 100644 --- a/modules/core/test/math/testMatrix.cpp +++ b/modules/core/test/math/testMatrix.cpp @@ -414,7 +414,7 @@ int main(int argc, char *argv[]) unsigned int nb = ctest ? 10 : 100; // 10000; const unsigned int size = ctest ? 10 : 100; - vpMatrix m_big(nb * size, 6); + vpMatrix m_big(nb *size, 6); std::vector submatrices(nb); for (size_t cpt = 0; cpt < submatrices.size(); cpt++) { vpMatrix m(size, 6); @@ -562,7 +562,7 @@ int main(int argc, char *argv[]) vpMatrix m_big_stack_static = generateRandomMatrix(ctest ? 100 : 1000, ctest ? 10 : 100, -1000.0, 1000.0); std::cout << "m_big_stack_static: " << m_big_stack_static.getRows() << "x" << m_big_stack_static.getCols() - << std::endl; + << std::endl; vpMatrix m_big_stack_static_row, m_big_stack_static_row_tmp; t = vpTime::measureTimeMs(); @@ -575,8 +575,8 @@ int main(int argc, char *argv[]) if (!equalMatrix(m_big_stack_static, m_big_stack_static_row)) { std::cerr << "Problem with vpMatrix::stack(vpMatrix, vpRowVector, " - "vpMatrix)!" - << std::endl; + "vpMatrix)!" + << std::endl; return EXIT_FAILURE; } @@ -595,8 +595,8 @@ int main(int argc, char *argv[]) if (!equalMatrix(m_big_stack_static, m_big_stack_static_col)) { std::cerr << "Problem with vpMatrix::stack(vpMatrix, vpColVector, " - "vpMatrix)!" - << std::endl; + "vpMatrix)!" + << std::endl; return EXIT_FAILURE; } } @@ -669,7 +669,6 @@ int main(int argc, char *argv[]) std::cout << "juxtaposeM:\n" << juxtaposeM << std::endl; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { std::vector vec_mat; vec_mat.emplace_back(5, 5); @@ -684,7 +683,6 @@ int main(int argc, char *argv[]) res2 = A + B; std::cout << "\n2) A+B:\n" << res2 << std::endl; } -#endif { std::cout << "\n------------------------" << std::endl; @@ -840,7 +838,8 @@ int main(int argc, char *argv[]) std::cout << "\nAll tests succeeded" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/math/testMatrixInitialization.cpp b/modules/core/test/math/testMatrixInitialization.cpp index 0e8e83a126..d7d9e4e0fe 100644 --- a/modules/core/test/math/testMatrixInitialization.cpp +++ b/modules/core/test/math/testMatrixInitialization.cpp @@ -106,11 +106,10 @@ bool equal(const vpRowVector &a1, const vpRowVector &a2, double epsilon) int main() { double epsilon = 1e-10; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpArray2D a{1.f, 2.f, 3.f}; + vpArray2D a { 1.f, 2.f, 3.f }; std::cout << "a:\n" << a << std::endl; - a = {-1, -2, -3, 4, 5.5, 6.0f}; + a = { -1, -2, -3, 4, 5.5, 6.0f }; std::cout << "a:\n" << a << std::endl; a.reshape(2, 3); std::cout << "a.reshape(2,3):\n" << a << std::endl; @@ -119,47 +118,46 @@ int main() vpArray2D a2; a2.resize(2, 2); - a2 = {1, 2, 3, 4}; + a2 = { 1, 2, 3, 4 }; std::cout << "a2:\n" << a2 << std::endl; - vpArray2D a3(2, 3, {1, 2, 3, 4, 5, 6}); + vpArray2D a3(2, 3, { 1, 2, 3, 4, 5, 6 }); std::cout << "a3:\n" << a3 << std::endl; - vpArray2D a4{{1, 2, 3}, {4, 5, 6}, {7, 8, 9}}; + vpArray2D a4 { {1, 2, 3}, {4, 5, 6}, {7, 8, 9} }; std::cout << "a4:\n" << a4 << std::endl; vpArray2D a5; - a5 = {{1, 2, 3}, {4, 5, 6}, {7, 8, 9}}; + a5 = { {1, 2, 3}, {4, 5, 6}, {7, 8, 9} }; std::cout << "a5:\n" << a5 << std::endl; - vpArray2D a6{a5}; + vpArray2D a6 { a5 }; std::cout << "a6:\n" << a6 << std::endl; - vpMatrix m{1, 2, 3}; + vpMatrix m { 1, 2, 3 }; std::cout << "m:\n" << m << std::endl; - m = {-1, -2, -3, -4}; + m = { -1, -2, -3, -4 }; std::cout << "m:\n" << m << std::endl; m.reshape(2, 2); std::cout << "m:\n" << m << std::endl; - vpMatrix m2(3, 2, {1, 2, 3, 4, 5, 6}); + vpMatrix m2(3, 2, { 1, 2, 3, 4, 5, 6 }); std::cout << "m2:\n" << m2 << std::endl; - vpMatrix m3{{1, 2, 3}, {4, 5, 6}, {7, 8, 9}}; + vpMatrix m3 { {1, 2, 3}, {4, 5, 6}, {7, 8, 9} }; std::cout << "m3:\n" << m3 << std::endl; vpMatrix m4; - m4 = {{1, 2, 3}, {4, 5, 6}, {7, 8, 9}}; + m4 = { {1, 2, 3}, {4, 5, 6}, {7, 8, 9} }; std::cout << "m4:\n" << m4 << std::endl; - vpMatrix m5{m4}; + vpMatrix m5 { m4 }; std::cout << "m5:\n" << m5 << std::endl; // vpMatrix m6; // m6 = {m2}; // Fails on travis // std::cout << "m6:\n" << m6 << std::endl; } -#endif { vpMatrix m1; @@ -189,9 +187,8 @@ int main() c_ref[i] = i; } std::cout << "c_ref: " << c_ref.t() << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpColVector c{0, 1, 2, 3, 4, 5}; + vpColVector c { 0, 1, 2, 3, 4, 5 }; std::cout << "c: " << c.t() << std::endl; if (!equal(c_ref, c, epsilon)) { return EXIT_FAILURE; @@ -199,7 +196,7 @@ int main() c_ref.resize(3, false); c_ref *= -1; std::cout << "c_ref: " << c_ref.t() << std::endl; - c = {0, -1, -2}; + c = { 0, -1, -2 }; std::cout << "c: " << c.t() << std::endl; if (!equal(c_ref, c, epsilon)) { return EXIT_FAILURE; @@ -221,7 +218,6 @@ int main() return EXIT_FAILURE; } } -#endif { vpColVector c; c << 1, 2, 3, 4; @@ -232,7 +228,8 @@ int main() std::cout << "after c.reshape(2, 2): " << c.t() << std::endl; c = c.reshape(2, 2); std::cout << "c:" << c << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Exception expected: c = c.reshape(2, 2);\n" << e.what() << std::endl; } @@ -253,9 +250,8 @@ int main() r_ref[i] = i; } std::cout << "r_ref: " << r_ref << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpRowVector r{0, 1, 2, 3, 4, 5}; + vpRowVector r { 0, 1, 2, 3, 4, 5 }; std::cout << "r: " << r << std::endl; if (!equal(r_ref, r, epsilon)) { return EXIT_FAILURE; @@ -263,7 +259,7 @@ int main() r_ref.resize(3, false); r_ref *= -1; std::cout << "r_ref: " << r_ref << std::endl; - r = {0, -1, -2}; + r = { 0, -1, -2 }; std::cout << "r: " << r << std::endl; if (!equal(r_ref, r, epsilon)) { return EXIT_FAILURE; @@ -285,7 +281,6 @@ int main() return EXIT_FAILURE; } } -#endif { vpRowVector r; r << 1, 2, 3; @@ -297,7 +292,8 @@ int main() try { r.reshape(3, 1); std::cout << "after r.reshape(3, 1): " << r << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Exception: r.reshape(3, 1);\n" << e.what() << std::endl; } } @@ -307,15 +303,13 @@ int main() std::cout << "** Test vpThetaUVector" << std::endl; vpThetaUVector tu_ref(0, M_PI_2, M_PI); std::cout << "tu_ref: " << tu_ref.t() << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpThetaUVector tu = {0, M_PI_2, M_PI}; + vpThetaUVector tu = { 0, M_PI_2, M_PI }; std::cout << "tu: " << tu.t() << std::endl; if (!equal(tu_ref, tu, epsilon)) { return EXIT_FAILURE; } } -#endif { vpThetaUVector tu; tu << 0, M_PI_2, M_PI; @@ -336,15 +330,13 @@ int main() std::cout << "** Test vpRxyzVector" << std::endl; vpRxyzVector rxyz_ref(0, M_PI_2, M_PI); std::cout << "rxyz_ref: " << rxyz_ref.t() << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpRxyzVector rxyz = {0, M_PI_2, M_PI}; + vpRxyzVector rxyz = { 0, M_PI_2, M_PI }; std::cout << "rxyz: " << rxyz.t() << std::endl; if (!equal(rxyz_ref, rxyz, epsilon)) { return EXIT_FAILURE; } } -#endif { vpRxyzVector rxyz; rxyz << 0, M_PI_2, M_PI; @@ -365,15 +357,13 @@ int main() std::cout << "** Test vpRzyxVector" << std::endl; vpRzyxVector rzyx_ref(0, M_PI_2, M_PI); std::cout << "rzyx_ref: " << rzyx_ref.t() << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpRzyxVector rzyx = {0, M_PI_2, M_PI}; + vpRzyxVector rzyx = { 0, M_PI_2, M_PI }; std::cout << "rzyx: " << rzyx.t() << std::endl; if (!equal(rzyx_ref, rzyx, epsilon)) { return EXIT_FAILURE; } } -#endif { vpRzyxVector rzyx; rzyx << 0, M_PI_2, M_PI; @@ -394,15 +384,13 @@ int main() std::cout << "** Test vpRzyzVector" << std::endl; vpRzyzVector rzyz_ref(0, M_PI_2, M_PI); std::cout << "rzyz_ref: " << rzyz_ref.t() << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpRzyzVector rzyz = {0, M_PI_2, M_PI}; + vpRzyzVector rzyz = { 0, M_PI_2, M_PI }; std::cout << "rzyz: " << rzyz.t() << std::endl; if (!equal(rzyz_ref, rzyz, epsilon)) { return EXIT_FAILURE; } } -#endif { vpRzyzVector rzyz; rzyz << 0, M_PI_2, M_PI; @@ -424,15 +412,13 @@ int main() vpThetaUVector tu_ref(0, M_PI_2, M_PI); vpQuaternionVector q_ref(tu_ref); std::cout << "q_ref: " << q_ref.t() << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpQuaternionVector q = {q_ref[0], q_ref[1], q_ref[2], q_ref[3]}; + vpQuaternionVector q = { q_ref[0], q_ref[1], q_ref[2], q_ref[3] }; std::cout << "q: " << q.t() << std::endl; if (!equal(q_ref, q, epsilon)) { return EXIT_FAILURE; } } -#endif { vpQuaternionVector q; q << q_ref[0], q_ref[1], q_ref[2], q_ref[3]; @@ -453,15 +439,13 @@ int main() std::cout << "** Test vpTranslationVector" << std::endl; vpTranslationVector t_ref(0, 0.1, 0.5); std::cout << "t_ref: " << t_ref.t() << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpTranslationVector t = {t_ref[0], t_ref[1], t_ref[2]}; + vpTranslationVector t = { t_ref[0], t_ref[1], t_ref[2] }; std::cout << "t: " << t.t() << std::endl; if (!equal(t_ref, t, epsilon)) { return EXIT_FAILURE; } } -#endif { vpTranslationVector t; t << 0, 0.1, 0.5; @@ -482,9 +466,8 @@ int main() std::cout << "** Test vpRotationMatrix" << std::endl; vpRotationMatrix R_ref(vpRxyzVector(0, -M_PI_2, M_PI)); std::cout << "R_ref:\n" << R_ref << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { - vpRotationMatrix R({0, 0, -1, 0, -1, 0, -1, 0, 0}); + vpRotationMatrix R({ 0, 0, -1, 0, -1, 0, -1, 0, 0 }); std::cout << "R:\n" << R << std::endl; if (!equal(R_ref, R, epsilon)) { return EXIT_FAILURE; @@ -492,13 +475,12 @@ int main() } { vpRotationMatrix R; - R = {0, 0, -1, 0, -1, 0, -1, 0, 0}; + R = { 0, 0, -1, 0, -1, 0, -1, 0, 0 }; std::cout << "R:\n" << R << std::endl; if (!equal(R_ref, R, epsilon)) { return EXIT_FAILURE; } } -#endif { vpRotationMatrix R; R << 0, 0, -1, 0, -1, 0, -1, 0, 0; diff --git a/modules/core/test/tools/geometry/testPolygon2.cpp b/modules/core/test/tools/geometry/testPolygon2.cpp index 6cbdbf513d..7653e78a15 100644 --- a/modules/core/test/tools/geometry/testPolygon2.cpp +++ b/modules/core/test/tools/geometry/testPolygon2.cpp @@ -55,26 +55,21 @@ TEST_CASE("Check OpenCV-bsed convex hull") { SECTION("From vpRect") { - const vpRect rect{0, 0, 200, 400}; - const std::vector rect_corners{rect.getTopLeft(), rect.getTopRight(), rect.getBottomRight(), - rect.getBottomLeft()}; + const vpRect rect { 0, 0, 200, 400 }; + const std::vector rect_corners { rect.getTopLeft(), rect.getTopRight(), rect.getBottomRight(), + rect.getBottomLeft() }; - vpPolygon poly{}; + vpPolygon poly {}; poly.buildFrom(rect_corners, true); #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_14) for (const auto &poly_corner : poly.getCorners()) { REQUIRE(std::find(cbegin(rect_corners), cend(rect_corners), poly_corner) != cend(rect_corners)); } -#elif (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#else for (const auto &poly_corner : poly.getCorners()) { REQUIRE(std::find(begin(rect_corners), end(rect_corners), poly_corner) != end(rect_corners)); } -#else - for (std::vector::const_iterator it = poly.getCorners().begin(); it != poly.getCorners().end(); - ++it) { - REQUIRE(std::find(rect_corners.begin(), rect_corners.end(), *it) != rect_corners.end()); - } #endif } } @@ -109,18 +104,12 @@ bool testConvexHull() return false; } } -#elif (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#else for (const auto &poly_corner : poly.getCorners()) { if (std::find(begin(rect_corners), end(rect_corners), poly_corner) == end(rect_corners)) { return false; } } -#else - for (std::vector::const_iterator it = poly.getCorners().begin(); it != poly.getCorners().end(); ++it) { - if (std::find(rect_corners.begin(), rect_corners.end(), *it) == rect_corners.end()) { - return false; - } - } #endif #endif @@ -130,7 +119,7 @@ bool testConvexHull() int main() { - if (! testConvexHull()) { + if (!testConvexHull()) { return EXIT_FAILURE; } diff --git a/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h b/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h index b0974ecb5e..b95e7f5dcc 100755 --- a/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h +++ b/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h @@ -40,7 +40,6 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /** * \brief Class that furnishes a set of colors that color blind people * should be able to distinguish one from another. @@ -199,5 +198,4 @@ std::ostream &operator<<(std::ostream &os, const vpColorBlindFriendlyPalette &co */ std::istream &operator>>(std::istream &is, vpColorBlindFriendlyPalette &color); -#endif #endif // _vpColorBlindFliendlyPalette_h_ diff --git a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h index 1fdff217ee..b977619fbf 100644 --- a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h +++ b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h @@ -38,9 +38,7 @@ #if defined(HAVE_OPENCV_HIGHGUI) -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include -#endif #include #include @@ -267,9 +265,7 @@ class VISP_EXPORT vpDisplayOpenCV : public vpDisplay static void on_mouse(int event, int x, int y, int flags, void *param); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) void overlay(std::function overlay_function, double opacity); -#endif }; #endif diff --git a/modules/gui/include/visp3/gui/vpPclViewer.h b/modules/gui/include/visp3/gui/vpPclViewer.h index 5f2ea4e227..ace4fb1363 100755 --- a/modules/gui/include/visp3/gui/vpPclViewer.h +++ b/modules/gui/include/visp3/gui/vpPclViewer.h @@ -37,7 +37,7 @@ #include -#if defined(VISP_HAVE_PCL) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PCL) // System #include #include diff --git a/modules/gui/src/display/vpDisplayOpenCV.cpp b/modules/gui/src/display/vpDisplayOpenCV.cpp index 69f4b2f354..56e28f2bac 100644 --- a/modules/gui/src/display/vpDisplayOpenCV.cpp +++ b/modules/gui/src/display/vpDisplayOpenCV.cpp @@ -102,14 +102,14 @@ unsigned int vpDisplayOpenCV::m_nbWindows = 0; vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleType) : vpDisplay(), #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(NULL), col(NULL), cvcolor(), font(NULL), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif - fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), - x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), - x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), - y_rbuttonup(0), rbuttonup(false) + fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), + x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), + x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), + y_rbuttonup(0), rbuttonup(false) { setScale(scaleType, I.getWidth(), I.getHeight()); init(I); @@ -142,14 +142,14 @@ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, int x, int y, const vpScaleType scaleType) : vpDisplay(), #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(NULL), col(NULL), cvcolor(), font(NULL), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif - fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), - x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), - x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), - y_rbuttonup(0), rbuttonup(false) + fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), + x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), + x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), + y_rbuttonup(0), rbuttonup(false) { setScale(scaleType, I.getWidth(), I.getHeight()); init(I, x, y, title); @@ -176,14 +176,14 @@ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, int x, int y, const vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleType) : #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(NULL), col(NULL), cvcolor(), font(NULL), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif - fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), - x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), - x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), - y_rbuttonup(0), rbuttonup(false) + fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), + x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), + x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), + y_rbuttonup(0), rbuttonup(false) { setScale(scaleType, I.getWidth(), I.getHeight()); init(I); @@ -212,14 +212,14 @@ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleType) vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, int x, int y, const std::string &title, vpScaleType scaleType) : #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(NULL), col(NULL), cvcolor(), font(NULL), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif - fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), - x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), - x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), - y_rbuttonup(0), rbuttonup(false) + fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), + x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), + x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), + y_rbuttonup(0), rbuttonup(false) { setScale(scaleType, I.getWidth(), I.getHeight()); init(I, x, y, title); @@ -250,21 +250,22 @@ int main() vpDisplayOpenCV::vpDisplayOpenCV(int x, int y, const std::string &title) : #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(NULL), col(NULL), cvcolor(), font(NULL), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif - fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), - x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), - x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), - y_rbuttonup(0), rbuttonup(false) + fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), + x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), + x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), + y_rbuttonup(0), rbuttonup(false) { m_windowXPosition = x; m_windowYPosition = y; if (!title.empty()) { m_title = title; - } else { + } + else { std::ostringstream s; s << m_nbWindows++; m_title = std::string("Window ") + s.str(); @@ -309,16 +310,15 @@ int main() vpDisplayOpenCV::vpDisplayOpenCV() : #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(NULL), col(NULL), cvcolor(), font(NULL), + m_background(NULL), col(NULL), cvcolor(), font(NULL), #else - m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), + m_background(), col(NULL), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), #endif - fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), - x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), - x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), - y_rbuttonup(0), rbuttonup(false) -{ -} + fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), + x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), + x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), + y_rbuttonup(0), rbuttonup(false) +{ } /*! Destructor. @@ -401,7 +401,8 @@ void vpDisplayOpenCV::init(unsigned int w, unsigned int h, int x, int y, const s if (m_title.empty()) { if (!title.empty()) { m_title = std::string(title); - } else { + } + else { std::ostringstream s; s << m_nbWindows++; @@ -561,7 +562,8 @@ void vpDisplayOpenCV::setWindowPosition(int winx, int winy) #else cv::moveWindow(this->m_title.c_str(), winx, winy); #endif - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -590,7 +592,8 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) cvReleaseImage(&m_background); m_background = cvCreateImage(size, depth, channels); } - } else { + } + else { m_background = cvCreateImage(size, depth, channels); } @@ -604,7 +607,8 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) *(dst_24++) = val; } } - } else { + } + else { for (unsigned int i = 0; i < m_height; i++) { unsigned char *dst_24 = (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep); for (unsigned int j = 0; j < m_width; j++) { @@ -635,7 +639,8 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) *(dst_24++) = val; } } - } else { + } + else { for (unsigned int i = 0; i < m_height; i++) { unsigned char *dst_24 = (unsigned char *)m_background.data + (int)(i * 3 * m_width); for (unsigned int j = 0; j < m_width; j++) { @@ -648,7 +653,8 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) } #endif - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -683,7 +689,8 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpI cvReleaseImage(&m_background); m_background = cvCreateImage(size, depth, channels); } - } else { + } + else { m_background = cvCreateImage(size, depth, channels); } @@ -694,7 +701,7 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpI unsigned int j_max = (std::min)(j_min + w, m_width); for (unsigned int i = i_min; i < i_max; i++) { unsigned char *dst_24 = - (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); + (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); for (unsigned int j = j_min; j < j_max; j++) { unsigned char val = I[i][j]; *(dst_24++) = val; @@ -702,14 +709,15 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpI *(dst_24++) = val; } } - } else { + } + else { int i_min = (std::max)((int)ceil(iP.get_i() / m_scale), 0); int j_min = (std::max)((int)ceil(iP.get_j() / m_scale), 0); int i_max = (std::min)((int)ceil((iP.get_i() + h) / m_scale), (int)m_height); int j_max = (std::min)((int)ceil((iP.get_j() + w) / m_scale), (int)m_width); for (int i = i_min; i < i_max; i++) { unsigned char *dst_24 = - (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); + (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); for (int j = j_min; j < j_max; j++) { unsigned char val = I[i * m_scale][j * m_scale]; *(dst_24++) = val; @@ -742,7 +750,8 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpI *(dst_24++) = val; } } - } else { + } + else { int i_min = (std::max)((int)ceil(iP.get_i() / m_scale), 0); int j_min = (std::max)((int)ceil(iP.get_j() / m_scale), 0); int i_max = (std::min)((int)ceil((iP.get_i() + h) / m_scale), (int)m_height); @@ -758,7 +767,8 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpI } } #endif - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -789,7 +799,8 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) cvReleaseImage(&m_background); m_background = cvCreateImage(size, depth, channels); } - } else { + } + else { m_background = cvCreateImage(size, depth, channels); } @@ -803,7 +814,8 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) *(dst_24++) = val.R; } } - } else { + } + else { for (unsigned int i = 0; i < m_height; i++) { unsigned char *dst_24 = (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep); for (unsigned int j = 0; j < m_width; j++) { @@ -833,7 +845,8 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) *(dst_24++) = val.R; } } - } else { + } + else { for (unsigned int i = 0; i < m_height; i++) { unsigned char *dst_24 = (unsigned char *)m_background.data + (int)(i * 3 * m_width); for (unsigned int j = 0; j < m_width; j++) { @@ -845,7 +858,8 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) } } #endif - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -879,7 +893,8 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpImagePoi cvReleaseImage(&m_background); m_background = cvCreateImage(size, depth, channels); } - } else { + } + else { m_background = cvCreateImage(size, depth, channels); } @@ -890,7 +905,7 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpImagePoi unsigned int j_max = (std::min)(j_min + w, m_width); for (unsigned int i = i_min; i < i_max; i++) { unsigned char *dst_24 = - (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); + (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); for (unsigned int j = j_min; j < j_max; j++) { vpRGBa val = I[i][j]; *(dst_24++) = val.B; @@ -898,14 +913,15 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpImagePoi *(dst_24++) = val.R; } } - } else { + } + else { int i_min = (std::max)((int)ceil(iP.get_i() / m_scale), 0); int j_min = (std::max)((int)ceil(iP.get_j() / m_scale), 0); int i_max = (std::min)((int)ceil((iP.get_i() + h) / m_scale), (int)m_height); int j_max = (std::min)((int)ceil((iP.get_j() + w) / m_scale), (int)m_width); for (int i = i_min; i < i_max; i++) { unsigned char *dst_24 = - (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); + (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); for (int j = j_min; j < j_max; j++) { vpRGBa val = I[i * m_scale][j * m_scale]; *(dst_24++) = val.B; @@ -937,7 +953,8 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpImagePoi *(dst_24++) = val.R; } } - } else { + } + else { int i_min = (std::max)((int)ceil(iP.get_i() / m_scale), 0); int j_min = (std::max)((int)ceil(iP.get_j() / m_scale), 0); int i_max = (std::min)((int)ceil((iP.get_i() + h) / m_scale), (int)m_height); @@ -953,7 +970,8 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpImagePoi } } #endif - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1019,7 +1037,8 @@ void vpDisplayOpenCV::flushDisplay() cv::imshow(this->m_title, m_background); cv::waitKey(5); #endif - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1040,7 +1059,8 @@ void vpDisplayOpenCV::flushDisplayROI(const vpImagePoint & /*iP*/, const unsigne cv::imshow(this->m_title.c_str(), m_background); cv::waitKey(5); #endif - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1076,7 +1096,8 @@ void vpDisplayOpenCV::displayArrow(const vpImagePoint &ip1, const vpImagePoint & if ((std::fabs(a) <= std::numeric_limits::epsilon()) && (std::fabs(b) <= std::numeric_limits::epsilon())) { // DisplayCrossLarge(i1,j1,3,col) ; - } else { + } + else { a /= lg; b /= lg; @@ -1099,7 +1120,8 @@ void vpDisplayOpenCV::displayArrow(const vpImagePoint &ip1, const vpImagePoint & displayLine(ip1, ip2, color, thickness); } - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1128,7 +1150,8 @@ void vpDisplayOpenCV::displayCharString(const vpImagePoint &ip, const char *text cv::Point(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale + fontHeight)), font, fontScale, col[color.id]); #endif - } else { + } + else { cvcolor = CV_RGB(color.R, color.G, color.B); #if VISP_HAVE_OPENCV_VERSION < 0x020408 cvPutText(m_background, text, @@ -1140,7 +1163,8 @@ void vpDisplayOpenCV::displayCharString(const vpImagePoint &ip, const char *text font, fontScale, cvcolor); #endif } - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1166,7 +1190,8 @@ void vpDisplayOpenCV::displayCircle(const vpImagePoint ¢er, unsigned int rad cv::Scalar cv_color; if (color.id < vpColor::id_unknown) { cv_color = col[color.id]; - } else { + } + else { cv_color = CV_RGB(color.R, color.G, color.B); } @@ -1177,13 +1202,13 @@ void vpDisplayOpenCV::displayCircle(const vpImagePoint ¢er, unsigned int rad #else cv::circle(m_background, cv::Point(x, y), r, cv_color, cv_thickness); #endif - } else { + } + else { #if VISP_HAVE_OPENCV_VERSION >= 0x030000 int filled = cv::FILLED; #else int filled = CV_FILLED; #endif -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) double opacity = static_cast(color.A) / 255.0; #if VISP_HAVE_OPENCV_VERSION < 0x020408 overlay([x, y, r, cv_color, filled](cv::Mat image) { cvCircle(image, cvPoint(x, y), r, cv_color, filled); }, @@ -1191,16 +1216,10 @@ void vpDisplayOpenCV::displayCircle(const vpImagePoint ¢er, unsigned int rad #else overlay([x, y, r, cv_color, filled](cv::Mat image) { cv::circle(image, cv::Point(x, y), r, cv_color, filled); }, opacity); -#endif -#else -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvCircle(m_background, cvPoint(x, y), r, cv_color, filled); -#else - cv::circle(m_background, cv::Point(x, y), r, cv_color, filled); -#endif #endif } - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1227,7 +1246,8 @@ void vpDisplayOpenCV::displayCross(const vpImagePoint &ip, unsigned int size, co right.set_j(ip.get_j() + size / 2); displayLine(top, bottom, color, thickness); displayLine(left, right, color, thickness); - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1253,7 +1273,8 @@ void vpDisplayOpenCV::displayDotLine(const vpImagePoint &ip1, const vpImagePoint if (ip2_.get_i() < ip1_.get_i()) { std::swap(ip1_, ip2_); } - } else if (ip2_.get_j() < ip1_.get_j()) { + } + else if (ip2_.get_j() < ip1_.get_j()) { std::swap(ip1_, ip2_); } @@ -1268,13 +1289,15 @@ void vpDisplayOpenCV::displayDotLine(const vpImagePoint &ip1, const vpImagePoint double j = ip1_.get_j(); displayLine(vpImagePoint(i, j), vpImagePoint(i + deltai, j), color, thickness); } - } else { + } + else { for (unsigned int j = (unsigned int)ip1_.get_j(); j < ip2_.get_j(); j += (unsigned int)(2 * deltaj)) { double i = slope * j + orig; displayLine(vpImagePoint(i, j), vpImagePoint(i + deltai, j + deltaj), color, thickness); } } - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1299,7 +1322,8 @@ void vpDisplayOpenCV::displayLine(const vpImagePoint &ip1, const vpImagePoint &i cv::Point(vpMath::round(ip2.get_u() / m_scale), vpMath::round(ip2.get_v() / m_scale)), col[color.id], (int)thickness); #endif - } else { + } + else { cvcolor = CV_RGB(color.R, color.G, color.B); #if VISP_HAVE_OPENCV_VERSION < 0x020408 cvLine(m_background, cvPoint(vpMath::round(ip1.get_u() / m_scale), vpMath::round(ip1.get_v() / m_scale)), @@ -1311,7 +1335,8 @@ void vpDisplayOpenCV::displayLine(const vpImagePoint &ip1, const vpImagePoint &i (int)thickness); #endif } - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1336,7 +1361,8 @@ void vpDisplayOpenCV::displayPoint(const vpImagePoint &ip, const vpColor &color, cv::Point(vpMath::round(ip.get_u() / m_scale + thickness - 1), vpMath::round(ip.get_v() / m_scale)), col[color.id], (int)thickness); #endif - } else { + } + else { cvcolor = CV_RGB(color.R, color.G, color.B); #if VISP_HAVE_OPENCV_VERSION < 0x020408 cvLine(m_background, cvPoint(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale)), @@ -1349,7 +1375,8 @@ void vpDisplayOpenCV::displayPoint(const vpImagePoint &ip, const vpColor &color, #endif } } - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1380,7 +1407,8 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, unsigned int cv::Scalar cv_color; if (color.id < vpColor::id_unknown) { cv_color = col[color.id]; - } else { + } + else { cv_color = CV_RGB(color.R, color.G, color.B); } @@ -1391,17 +1419,17 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, unsigned int #else cv::rectangle(m_background, cv::Point(left, top), cv::Point(right, bottom), cv_color, cv_thickness); #endif - } else { + } + else { #if VISP_HAVE_OPENCV_VERSION >= 0x030000 int filled = cv::FILLED; #else int filled = CV_FILLED; #endif -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) double opacity = static_cast(color.A) / 255.0; #if VISP_HAVE_OPENCV_VERSION < 0x020408 overlay([left, top, right, bottom, cv_color, filled]( - cv::Mat image) { cvRectangle(image, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); }, + cv::Mat image) { cvRectangle(image, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); }, opacity); #else overlay( @@ -1409,16 +1437,10 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, unsigned int cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); }, opacity); -#endif -#else -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); -#else - cv::rectangle(m_background, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); -#endif #endif } - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1447,7 +1469,8 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, const vpImag cv::Scalar cv_color; if (color.id < vpColor::id_unknown) { cv_color = col[color.id]; - } else { + } + else { cv_color = CV_RGB(color.R, color.G, color.B); } @@ -1458,17 +1481,17 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, const vpImag #else cv::rectangle(m_background, cv::Point(left, top), cv::Point(right, bottom), cv_color, cv_thickness); #endif - } else { + } + else { #if VISP_HAVE_OPENCV_VERSION >= 0x030000 int filled = cv::FILLED; #else int filled = CV_FILLED; #endif -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) double opacity = static_cast(color.A) / 255.0; #if VISP_HAVE_OPENCV_VERSION < 0x020408 overlay([left, top, right, bottom, cv_color, filled]( - cv::Mat image) { cvRectangle(image, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); }, + cv::Mat image) { cvRectangle(image, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); }, opacity); #else overlay( @@ -1476,16 +1499,10 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, const vpImag cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); }, opacity); -#endif -#else -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); -#else - cv::rectangle(m_background, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); -#endif #endif } - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1513,7 +1530,8 @@ void vpDisplayOpenCV::displayRectangle(const vpRect &rectangle, const vpColor &c cv::Scalar cv_color; if (color.id < vpColor::id_unknown) { cv_color = col[color.id]; - } else { + } + else { cv_color = CV_RGB(color.R, color.G, color.B); } @@ -1524,17 +1542,17 @@ void vpDisplayOpenCV::displayRectangle(const vpRect &rectangle, const vpColor &c #else cv::rectangle(m_background, cv::Point(left, top), cv::Point(right, bottom), cv_color, cv_thickness); #endif - } else { + } + else { #if VISP_HAVE_OPENCV_VERSION >= 0x030000 int filled = cv::FILLED; #else int filled = CV_FILLED; #endif -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) double opacity = static_cast(color.A) / 255.0; #if VISP_HAVE_OPENCV_VERSION < 0x020408 overlay([left, top, right, bottom, cv_color, filled]( - cv::Mat image) { cvRectangle(image, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); }, + cv::Mat image) { cvRectangle(image, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); }, opacity); #else overlay( @@ -1542,16 +1560,10 @@ void vpDisplayOpenCV::displayRectangle(const vpRect &rectangle, const vpColor &c cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); }, opacity); -#endif -#else -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); -#else - cv::rectangle(m_background, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); -#endif #endif } - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -1601,7 +1613,8 @@ bool vpDisplayOpenCV::getClick(bool blocking) cv::waitKey(10); #endif } while (ret == false && blocking == true); - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } return ret; @@ -1668,7 +1681,8 @@ bool vpDisplayOpenCV::getClick(vpImagePoint &ip, bool blocking) cv::waitKey(10); #endif } while (ret == false && blocking == true); - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } return ret; @@ -1739,7 +1753,8 @@ bool vpDisplayOpenCV::getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonTyp cv::waitKey(10); #endif } while (ret == false && blocking == true); - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } return ret; @@ -1812,7 +1827,8 @@ bool vpDisplayOpenCV::getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonT cv::waitKey(10); #endif } while (ret == false && blocking == true); - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } return ret; @@ -1949,7 +1965,8 @@ bool vpDisplayOpenCV::getKeyboardEvent(bool blocking) if (key_pressed == -1) return false; return true; - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } // return false; // Never reached after throw() @@ -1996,7 +2013,8 @@ bool vpDisplayOpenCV::getKeyboardEvent(std::string &key, bool blocking) key = ss.str(); } return true; - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } // return false; // Never reached after throw() @@ -2056,7 +2074,8 @@ bool vpDisplayOpenCV::getPointerPosition(vpImagePoint &ip) ip.set_v(v); } return false; - } else { + } + else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); } } @@ -2103,7 +2122,7 @@ void vpDisplayOpenCV::getScreenSize(unsigned int &w, unsigned int &h) h = GetSystemMetrics(SM_CYSCREEN); #else throw(vpException(vpException::functionNotImplementedError, "The function vpDisplayOpenCV::getScreenSize() is not " - "implemented on winrt")); + "implemented on winrt")); #endif #endif } @@ -2128,7 +2147,6 @@ unsigned int vpDisplayOpenCV::getScreenHeight() return height; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! * Initialize display overlay layer for transparency. * \param overlay_function : Overlay function @@ -2141,8 +2159,9 @@ void vpDisplayOpenCV::overlay(std::function overlay_function, d if (opacity < 1.0) { // Deep copy overlay = m_background.clone(); - } else { - // Shallow copy + } + else { + // Shallow copy overlay = m_background; } @@ -2153,10 +2172,9 @@ void vpDisplayOpenCV::overlay(std::function overlay_function, d cv::addWeighted(overlay, opacity, m_background, 1.0 - opacity, 0.0, m_background); } } -#endif #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpDisplayOpenCV.cpp.o) has no // symbols -void dummy_vpDisplayOpenCV(){}; +void dummy_vpDisplayOpenCV() { }; #endif diff --git a/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp b/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp index 248582888a..c0874dfdf4 100755 --- a/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp +++ b/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp @@ -35,7 +35,6 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) std::vector vpColorBlindFriendlyPalette::s_paletteNames = { @@ -206,5 +205,3 @@ std::istream &operator>>(std::istream &is, vpColorBlindFriendlyPalette &color) color.set_fromString(nameColor); return is; } - -#endif diff --git a/modules/gui/src/pointcloud/vpPclViewer.cpp b/modules/gui/src/pointcloud/vpPclViewer.cpp index a8ed45b2cb..93e14b888d 100755 --- a/modules/gui/src/pointcloud/vpPclViewer.cpp +++ b/modules/gui/src/pointcloud/vpPclViewer.cpp @@ -35,7 +35,7 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS #include -#if defined(VISP_HAVE_PCL) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PCL) // PCL #include diff --git a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h index 953fbc920b..c711968932 100644 --- a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h +++ b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h @@ -46,8 +46,6 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - // 3rd parties inclue #ifdef VISP_HAVE_NLOHMANN_JSON #include @@ -439,7 +437,6 @@ class VISP_EXPORT vpCircleHoughTransform */ std::vector detect(const vpImage &I); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /** * \brief Perform Circle Hough Transform to detect the circles in in a gray-scale image. * Get only the \b nbCircles circles having the greatest number of votes. @@ -451,7 +448,6 @@ class VISP_EXPORT vpCircleHoughTransform * of votes detected in the image. */ std::vector detect(const vpImage &I, const int &nbCircles); -#endif //@} /** @name Configuration from files */ @@ -956,4 +952,3 @@ class VISP_EXPORT vpCircleHoughTransform std::vector m_finalCircleVotes; /*!< Number of votes for the final circles.*/ }; #endif -#endif diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index 20e4f40667..de36e4f398 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -34,7 +34,6 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpCircleHoughTransform::vpCircleHoughTransform() : m_algoParams() { @@ -98,7 +97,6 @@ vpCircleHoughTransform::saveConfigurationInJSON(const std::string &jsonPath) con { m_algoParams.saveConfigurationInJSON(jsonPath); } -#endif void vpCircleHoughTransform::initGaussianFilters() diff --git a/modules/imgproc/src/vpRetinex.cpp b/modules/imgproc/src/vpRetinex.cpp index 4ef77185dc..dea7f9a4da 100644 --- a/modules/imgproc/src/vpRetinex.cpp +++ b/modules/imgproc/src/vpRetinex.cpp @@ -215,11 +215,8 @@ void MSRCR(vpImage &I, int _scale, int scaleDiv, int level, double dynam std::vector diff(dest.size()); -#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 std::transform(dest.begin(), dest.end(), diff.begin(), std::bind(std::minus(), std::placeholders::_1, mean)); -#else - std::transform(dest.begin(), dest.end(), diff.begin(), std::bind2nd(std::minus(), mean)); -#endif + double sq_sum = std::inner_product(diff.begin(), diff.end(), diff.begin(), 0.0); double stdev = std::sqrt(sq_sum / dest.size()); diff --git a/modules/io/include/visp3/io/vpImageQueue.h b/modules/io/include/visp3/io/vpImageQueue.h index 97ca1c4c91..f7ea820a87 100644 --- a/modules/io/include/visp3/io/vpImageQueue.h +++ b/modules/io/include/visp3/io/vpImageQueue.h @@ -36,8 +36,6 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - #include #include #include @@ -284,4 +282,3 @@ template class vpImageQueue }; #endif -#endif diff --git a/modules/io/include/visp3/io/vpImageStorageWorker.h b/modules/io/include/visp3/io/vpImageStorageWorker.h index 9fc16fab51..a69fe16750 100644 --- a/modules/io/include/visp3/io/vpImageStorageWorker.h +++ b/modules/io/include/visp3/io/vpImageStorageWorker.h @@ -36,8 +36,6 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - #include #include @@ -134,4 +132,3 @@ template class vpImageStorageWorker }; #endif -#endif diff --git a/modules/io/src/image/private/vpImageIoBackend.h b/modules/io/src/image/private/vpImageIoBackend.h index 10fde6b763..dc823322dc 100644 --- a/modules/io/src/image/private/vpImageIoBackend.h +++ b/modules/io/src/image/private/vpImageIoBackend.h @@ -90,10 +90,8 @@ void readSimdlib(vpImage &I, const std::string &filename); void readSimdlib(vpImage &I, const std::string &filename); // TinyEXR lib -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) void readEXRTiny(vpImage &I, const std::string &filename); void readEXRTiny(vpImage &I, const std::string &filename); -#endif void writeJPEGSimdlib(const vpImage &I, const std::string &filename, int quality); void writeJPEGSimdlib(const vpImage &I, const std::string &filename, int quality); @@ -112,9 +110,7 @@ void writePNGStb(const vpImage &I, const std::string &filename); void writePNGStb(const vpImage &I, const std::string &filename); // TinyEXR lib -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) void writeEXRTiny(const vpImage &I, const std::string &filename); void writeEXRTiny(const vpImage &I, const std::string &filename); -#endif #endif diff --git a/modules/io/src/image/private/vpImageIoTinyEXR.cpp b/modules/io/src/image/private/vpImageIoTinyEXR.cpp index 02766d6822..780c903ca5 100644 --- a/modules/io/src/image/private/vpImageIoTinyEXR.cpp +++ b/modules/io/src/image/private/vpImageIoTinyEXR.cpp @@ -38,8 +38,6 @@ #include "vpImageIoBackend.h" -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - #define TINYEXR_USE_MINIZ 0 #define TINYEXR_USE_STB_ZLIB 1 #include @@ -65,7 +63,7 @@ void readEXRTiny(vpImage &I, const std::string &filename) EXRHeader exr_header; InitEXRHeader(&exr_header); - const char* err = NULL; // or `nullptr` in C++11 or later. + const char *err = NULL; // or `nullptr` in C++11 or later. ret = ParseEXRHeaderFromFile(&exr_header, &exr_version, filename.c_str(), &err); if (ret != 0) { std::string err_msg(err); @@ -97,7 +95,8 @@ void readEXRTiny(vpImage &I, const std::string &filename) if (exr_image.images) { I.resize(exr_image.height, exr_image.width); memcpy(I.bitmap, exr_image.images[0], exr_image.height*exr_image.width*sizeof(float)); - } else if (exr_image.tiles) { + } + else if (exr_image.tiles) { I.resize(exr_image.height, exr_image.width); size_t data_width = static_cast(exr_header.data_window.max_x - exr_header.data_window.min_x + 1); @@ -137,7 +136,7 @@ void readEXRTiny(vpImage &I, const std::string &filename) EXRHeader exr_header; InitEXRHeader(&exr_header); - const char* err = NULL; // or `nullptr` in C++11 or later. + const char *err = NULL; // or `nullptr` in C++11 or later. ret = ParseEXRHeaderFromFile(&exr_header, &exr_version, filename.c_str(), &err); if (ret != 0) { std::string err_msg(err); @@ -175,7 +174,8 @@ void readEXRTiny(vpImage &I, const std::string &filename) I[i][j].B = reinterpret_cast(exr_image.images)[0][i * exr_image.width + j]; } } - } else if (exr_image.tiles) { + } + else if (exr_image.tiles) { I.resize(exr_image.height, exr_image.width); size_t data_width = static_cast(exr_header.data_window.max_x - exr_header.data_window.min_x + 1); @@ -219,7 +219,7 @@ void writeEXRTiny(const vpImage &I, const std::string &filename) image.num_channels = 1; - image.images = (unsigned char**)&I.bitmap; + image.images = (unsigned char **)&I.bitmap; image.width = I.getWidth(); image.height = I.getHeight(); @@ -236,7 +236,7 @@ void writeEXRTiny(const vpImage &I, const std::string &filename) header.requested_pixel_types[i] = TINYEXR_PIXELTYPE_FLOAT; // pixel type of output image to be stored in .EXR } - const char* err = NULL; // or nullptr in C++11 or later. + const char *err = NULL; // or nullptr in C++11 or later. int ret = SaveEXRImageToFile(&image, &header, filename.c_str(), &err); if (ret != TINYEXR_SUCCESS) { std::string err_msg(err); @@ -274,12 +274,12 @@ void writeEXRTiny(const vpImage &I, const std::string &filename) images[2][i] = I.bitmap[i].B; } - float* image_ptr[3]; + float *image_ptr[3]; image_ptr[0] = &(images[2].at(0)); // B image_ptr[1] = &(images[1].at(0)); // G image_ptr[2] = &(images[0].at(0)); // R - image.images = (unsigned char**)image_ptr; + image.images = (unsigned char **)image_ptr; image.width = I.getWidth(); image.height = I.getHeight(); @@ -298,7 +298,7 @@ void writeEXRTiny(const vpImage &I, const std::string &filename) header.requested_pixel_types[i] = TINYEXR_PIXELTYPE_FLOAT; // pixel type of output image to be stored in .EXR } - const char* err = NULL; // or nullptr in C++11 or later. + const char *err = NULL; // or nullptr in C++11 or later. int ret = SaveEXRImageToFile(&image, &header, filename.c_str(), &err); if (ret != TINYEXR_SUCCESS) { std::string err_msg(err); @@ -313,5 +313,3 @@ void writeEXRTiny(const vpImage &I, const std::string &filename) free(header.requested_pixel_types); free(header.pixel_types); } - -#endif diff --git a/modules/io/src/image/vpImageIo.cpp b/modules/io/src/image/vpImageIo.cpp index a74a61b529..9980c2f3d2 100644 --- a/modules/io/src/image/vpImageIo.cpp +++ b/modules/io/src/image/vpImageIo.cpp @@ -397,16 +397,18 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, if (backend == IO_SYSTEM_LIB_BACKEND) { #if !defined(VISP_HAVE_JPEG) std::string message = - "Libjpeg backend is not available to read file \"" + filename + "\": switch to stb_image backend"; + "Libjpeg backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = - "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; + "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif - } else if (backend == IO_DEFAULT_BACKEND) { + } + else if (backend == IO_DEFAULT_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) backend = IO_OPENCV_BACKEND; #elif defined(VISP_HAVE_JPEG) @@ -420,13 +422,16 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, #if defined(VISP_HAVE_JPEG) readJPEGLibjpeg(I, filename); #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) readOpenCV(I, filename); #endif - } else if (backend == IO_STB_IMAGE_BACKEND) { + } + else if (backend == IO_STB_IMAGE_BACKEND) { readStb(I, filename); - } else if (backend == IO_SIMDLIB_BACKEND) { + } + else if (backend == IO_SIMDLIB_BACKEND) { readSimdlib(I, filename); } } @@ -446,16 +451,18 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, int ba if (backend == IO_SYSTEM_LIB_BACKEND) { #if !defined(VISP_HAVE_JPEG) std::string message = - "Libjpeg backend is not available to read file \"" + filename + "\": switch to stb_image backend"; + "Libjpeg backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = - "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; + "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif - } else if (backend == IO_DEFAULT_BACKEND) { + } + else if (backend == IO_DEFAULT_BACKEND) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS) backend = IO_OPENCV_BACKEND; #elif defined(VISP_HAVE_JPEG) @@ -469,13 +476,16 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, int ba #if defined(VISP_HAVE_JPEG) readJPEGLibjpeg(I, filename); #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) readOpenCV(I, filename); #endif - } else if (backend == IO_STB_IMAGE_BACKEND) { + } + else if (backend == IO_STB_IMAGE_BACKEND) { readStb(I, filename); - } else if (backend == IO_SIMDLIB_BACKEND) { + } + else if (backend == IO_SIMDLIB_BACKEND) { readSimdlib(I, filename); } } @@ -495,16 +505,18 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, if (backend == IO_SYSTEM_LIB_BACKEND) { #if !defined(VISP_HAVE_PNG) std::string message = - "Libpng backend is not available to read file \"" + filename + "\": switch to stb_image backend"; + "Libpng backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = - "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; + "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif - } else if (backend == IO_DEFAULT_BACKEND) { + } + else if (backend == IO_DEFAULT_BACKEND) { #if defined(VISP_HAVE_PNG) backend = IO_SYSTEM_LIB_BACKEND; #elif defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS) @@ -518,13 +530,16 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, #if defined(VISP_HAVE_PNG) readPNGLibpng(I, filename); #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) readOpenCV(I, filename); #endif - } else if (backend == IO_STB_IMAGE_BACKEND) { + } + else if (backend == IO_STB_IMAGE_BACKEND) { readStb(I, filename); - } else if (backend == IO_SIMDLIB_BACKEND) { + } + else if (backend == IO_SIMDLIB_BACKEND) { readSimdlib(I, filename); } } @@ -544,16 +559,18 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, int bac if (backend == IO_SYSTEM_LIB_BACKEND) { #if !defined(VISP_HAVE_PNG) std::string message = - "Libpng backend is not available to read file \"" + filename + "\": switch to stb_image backend"; + "Libpng backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = - "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; + "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif - } else if (backend == IO_DEFAULT_BACKEND) { + } + else if (backend == IO_DEFAULT_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) backend = IO_OPENCV_BACKEND; #else @@ -565,13 +582,16 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, int bac #if defined(VISP_HAVE_PNG) readPNGLibpng(I, filename); #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) readOpenCV(I, filename); #endif - } else if (backend == IO_STB_IMAGE_BACKEND) { + } + else if (backend == IO_STB_IMAGE_BACKEND) { readStb(I, filename); - } else if (backend == IO_SIMDLIB_BACKEND) { + } + else if (backend == IO_SIMDLIB_BACKEND) { readSimdlib(I, filename); } } @@ -588,12 +608,13 @@ void vpImageIo::readEXR(vpImage &I, const std::string &filename, int back { if (backend == IO_SYSTEM_LIB_BACKEND || backend == IO_SIMDLIB_BACKEND || backend == IO_STB_IMAGE_BACKEND) { std::string message = - "This backend cannot read file \"" + filename + "\": switch to the default TinyEXR backend"; + "This backend cannot read file \"" + filename + "\": switch to the default TinyEXR backend"; backend = IO_DEFAULT_BACKEND; - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = - "OpenCV backend is not available to read file \"" + filename + "\": switch to the default TinyEXR backend"; + "OpenCV backend is not available to read file \"" + filename + "\": switch to the default TinyEXR backend"; backend = IO_DEFAULT_BACKEND; #endif } @@ -602,15 +623,9 @@ void vpImageIo::readEXR(vpImage &I, const std::string &filename, int back #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) readOpenCV(I, filename); #endif - } else if (backend == IO_DEFAULT_BACKEND) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + } + else if (backend == IO_DEFAULT_BACKEND) { readEXRTiny(I, filename); -#else - (void)I; - std::string message = - "TinyEXR backend is not available to read file \"" + filename + "\": cxx standard should be greater or equal to cxx11"; - throw(vpImageException(vpImageException::ioError, message)); -#endif } } @@ -626,12 +641,13 @@ void vpImageIo::readEXR(vpImage &I, const std::string &filename, int bac { if (backend == IO_SYSTEM_LIB_BACKEND || backend == IO_SIMDLIB_BACKEND || backend == IO_STB_IMAGE_BACKEND) { std::string message = - "This backend cannot read file \"" + filename + "\": switch to the default TinyEXR backend"; + "This backend cannot read file \"" + filename + "\": switch to the default TinyEXR backend"; backend = IO_DEFAULT_BACKEND; - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = - "OpenCV backend is not available to read file \"" + filename + "\": switch to the default TinyEXR backend"; + "OpenCV backend is not available to read file \"" + filename + "\": switch to the default TinyEXR backend"; backend = IO_DEFAULT_BACKEND; #endif } @@ -640,15 +656,9 @@ void vpImageIo::readEXR(vpImage &I, const std::string &filename, int bac #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) readOpenCV(I, filename); #endif - } else if (backend == IO_DEFAULT_BACKEND) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + } + else if (backend == IO_DEFAULT_BACKEND) { readEXRTiny(I, filename); -#else - (void)I; - std::string message = - "TinyEXR backend is not available to read file \"" + filename + "\": cxx standard should be greater or equal to cxx11"; - throw(vpImageException(vpImageException::ioError, message)); -#endif } } @@ -670,12 +680,14 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &fi std::string message = "Libjpeg backend is not available to save file \"" + filename + "\": switch to simd backend"; backend = IO_SIMDLIB_BACKEND; #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = "OpenCV backend is not available to save file \"" + filename + "\": switch to simd backend"; backend = IO_SIMDLIB_BACKEND; #endif - } else if (backend == IO_DEFAULT_BACKEND) { + } + else if (backend == IO_DEFAULT_BACKEND) { #if defined(VISP_HAVE_JPEG) backend = IO_SYSTEM_LIB_BACKEND; #elif defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS) @@ -689,13 +701,16 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &fi #if defined(VISP_HAVE_JPEG) writeJPEGLibjpeg(I, filename, quality); #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) writeOpenCV(I, filename, quality); #endif - } else if (backend == IO_SIMDLIB_BACKEND) { + } + else if (backend == IO_SIMDLIB_BACKEND) { writeJPEGSimdlib(I, filename, quality); - } else if (backend == IO_STB_IMAGE_BACKEND) { + } + else if (backend == IO_STB_IMAGE_BACKEND) { writeJPEGStb(I, filename, quality); } } @@ -718,12 +733,14 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &filename, std::string message = "Libjpeg backend is not available to save file \"" + filename + "\": switch to simd backend"; backend = IO_SIMDLIB_BACKEND; #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = "OpenCV backend is not available to save file \"" + filename + "\": switch to simd backend"; backend = IO_SIMDLIB_BACKEND; #endif - } else if (backend == IO_DEFAULT_BACKEND) { + } + else if (backend == IO_DEFAULT_BACKEND) { #if defined(VISP_HAVE_JPEG) backend = IO_SYSTEM_LIB_BACKEND; #elif defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS) @@ -737,13 +754,16 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &filename, #if defined(VISP_HAVE_JPEG) writeJPEGLibjpeg(I, filename, quality); #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) writeOpenCV(I, filename, quality); #endif - } else if (backend == IO_SIMDLIB_BACKEND) { + } + else if (backend == IO_SIMDLIB_BACKEND) { writeJPEGSimdlib(I, filename, quality); - } else if (backend == IO_STB_IMAGE_BACKEND) { + } + else if (backend == IO_STB_IMAGE_BACKEND) { writeJPEGStb(I, filename, quality); } } @@ -765,12 +785,14 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &fil std::string message = "Libpng backend is not available to save file \"" + filename + "\": switch to simd backend"; backend = IO_SIMDLIB_BACKEND; #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = "OpenCV backend is not available to save file \"" + filename + "\": switch to simd backend"; backend = IO_SIMDLIB_BACKEND; #endif - } else if (backend == IO_DEFAULT_BACKEND) { + } + else if (backend == IO_DEFAULT_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) backend = IO_OPENCV_BACKEND; #else @@ -782,11 +804,14 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &fil #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) writeOpenCV(I, filename, 90); #endif - } else if (backend == IO_SIMDLIB_BACKEND) { + } + else if (backend == IO_SIMDLIB_BACKEND) { writePNGSimdlib(I, filename); - } else if (backend == IO_STB_IMAGE_BACKEND) { + } + else if (backend == IO_STB_IMAGE_BACKEND) { writePNGStb(I, filename); - } else if (backend == IO_SYSTEM_LIB_BACKEND) { + } + else if (backend == IO_SYSTEM_LIB_BACKEND) { #if defined(VISP_HAVE_PNG) writePNGLibpng(I, filename); #endif @@ -810,12 +835,14 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &filename, std::string message = "Libpng backend is not available to save file \"" + filename + "\": switch to simd backend"; backend = IO_SIMDLIB_BACKEND; #endif - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) std::string message = "OpenCV backend is not available to save file \"" + filename + "\": switch to simd backend"; backend = IO_SIMDLIB_BACKEND; #endif - } else if (backend == IO_DEFAULT_BACKEND) { + } + else if (backend == IO_DEFAULT_BACKEND) { #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) backend = IO_OPENCV_BACKEND; #else @@ -827,11 +854,14 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &filename, #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) writeOpenCV(I, filename, 90); #endif - } else if (backend == IO_SIMDLIB_BACKEND) { + } + else if (backend == IO_SIMDLIB_BACKEND) { writePNGSimdlib(I, filename); - } else if (backend == IO_STB_IMAGE_BACKEND) { + } + else if (backend == IO_STB_IMAGE_BACKEND) { writePNGStb(I, filename); - } else if (backend == IO_SYSTEM_LIB_BACKEND) { + } + else if (backend == IO_SYSTEM_LIB_BACKEND) { #if defined(VISP_HAVE_PNG) writePNGLibpng(I, filename); #endif @@ -850,13 +880,14 @@ void vpImageIo::writeEXR(const vpImage &I, const std::string &filename, i { if (backend == IO_SYSTEM_LIB_BACKEND || backend == IO_SIMDLIB_BACKEND || backend == IO_STB_IMAGE_BACKEND) { std::string message = - "This backend cannot save file \"" + filename + "\": switch to the default TinyEXR backend"; + "This backend cannot save file \"" + filename + "\": switch to the default TinyEXR backend"; backend = IO_DEFAULT_BACKEND; - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) (void)I; std::string message = - "OpenCV backend is not available to save file \"" + filename + "\": switch to the default TinyEXR backend"; + "OpenCV backend is not available to save file \"" + filename + "\": switch to the default TinyEXR backend"; backend = IO_DEFAULT_BACKEND; #endif } @@ -865,14 +896,9 @@ void vpImageIo::writeEXR(const vpImage &I, const std::string &filename, i #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) writeOpenCV(I, filename); #endif - } else if (backend == IO_DEFAULT_BACKEND) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + } + else if (backend == IO_DEFAULT_BACKEND) { writeEXRTiny(I, filename); -#else - std::string message = - "TinyEXR backend is not available to save file \"" + filename + "\": cxx standard should be greater or equal to cxx11"; - throw(vpImageException(vpImageException::ioError, message)); -#endif } } @@ -888,13 +914,14 @@ void vpImageIo::writeEXR(const vpImage &I, const std::string &filename, { if (backend == IO_SYSTEM_LIB_BACKEND || backend == IO_SIMDLIB_BACKEND || backend == IO_STB_IMAGE_BACKEND) { std::string message = - "This backend cannot save file \"" + filename + "\": switch to the default TinyEXR backend"; + "This backend cannot save file \"" + filename + "\": switch to the default TinyEXR backend"; backend = IO_DEFAULT_BACKEND; - } else if (backend == IO_OPENCV_BACKEND) { + } + else if (backend == IO_OPENCV_BACKEND) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) (void)I; std::string message = - "OpenCV backend is not available to save file \"" + filename + "\": switch to the default TinyEXR backend"; + "OpenCV backend is not available to save file \"" + filename + "\": switch to the default TinyEXR backend"; backend = IO_DEFAULT_BACKEND; #endif } @@ -903,14 +930,9 @@ void vpImageIo::writeEXR(const vpImage &I, const std::string &filename, #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) writeOpenCV(I, filename); #endif - } else if (backend == IO_DEFAULT_BACKEND) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + } + else if (backend == IO_DEFAULT_BACKEND) { writeEXRTiny(I, filename); -#else - std::string message = - "TinyEXR backend is not available to save file \"" + filename + "\": cxx standard should be greater or equal to cxx11"; - throw(vpImageException(vpImageException::ioError, message)); -#endif } } diff --git a/modules/robot/include/visp3/robot/vpRobotUniversalRobots.h b/modules/robot/include/visp3/robot/vpRobotUniversalRobots.h index 30651d1c23..cab6ec6248 100644 --- a/modules/robot/include/visp3/robot/vpRobotUniversalRobots.h +++ b/modules/robot/include/visp3/robot/vpRobotUniversalRobots.h @@ -38,7 +38,7 @@ #include -#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UR_RTDE) #include diff --git a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp index 73329e7ac6..950c6e5b0c 100644 --- a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp +++ b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UR_RTDE) #include #include @@ -473,8 +473,8 @@ void vpRobotUniversalRobots::setPosition(const vpRobot::vpControlFrameType frame if (vpRobot::STATE_POSITION_CONTROL != getRobotState()) { std::cout << "Robot is not in position-based control. " - "Modification of the robot state" - << std::endl; + "Modification of the robot state" + << std::endl; setRobotState(vpRobot::STATE_POSITION_CONTROL); } @@ -482,12 +482,14 @@ void vpRobotUniversalRobots::setPosition(const vpRobot::vpControlFrameType frame double speed_factor = m_positioningVelocity / 100.; std::vector new_q = position.toStdVector(); m_rtde_control->moveJ(new_q, m_max_joint_speed * speed_factor); - } else if (frame == vpRobot::END_EFFECTOR_FRAME) { + } + else if (frame == vpRobot::END_EFFECTOR_FRAME) { double speed_factor = m_positioningVelocity / 100.; std::vector new_pose = position.toStdVector(); // Move synchronously to ensure a the blocking behaviour m_rtde_control->moveL(new_pose, m_max_linear_speed * speed_factor); - } else if (frame == vpRobot::CAMERA_FRAME) { + } + else if (frame == vpRobot::CAMERA_FRAME) { double speed_factor = m_positioningVelocity / 100.; vpTranslationVector f_t_c(position.extract(0, 3)); @@ -498,7 +500,8 @@ void vpRobotUniversalRobots::setPosition(const vpRobot::vpControlFrameType frame std::vector new_pose = fPe.toStdVector(); // Move synchronously to ensure a the blocking behaviour m_rtde_control->moveL(new_pose, m_max_linear_speed * speed_factor); - } else { + } + else { throw(vpException(vpRobotException::functionNotImplementedError, "Cannot move the robot to a cartesian position. Only joint positioning is implemented")); } @@ -563,7 +566,7 @@ void vpRobotUniversalRobots::setPosition(const vpRobot::vpControlFrameType frame int main() { -#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UR_RTDE) vpRobotUniversalRobots robot; vpColVector qd(6); @@ -632,21 +635,25 @@ void vpRobotUniversalRobots::setVelocity(const vpRobot::vpControlFrameType frame double dt = 1.0 / 1000; // 2ms double acceleration = 0.5; m_rtde_control->speedJ(vel_sat.toStdVector(), acceleration, dt); - } else if (frame == vpRobot::REFERENCE_FRAME) { + } + else if (frame == vpRobot::REFERENCE_FRAME) { double dt = 1.0 / 1000; // 2ms double acceleration = 0.25; m_rtde_control->speedL(vel_sat.toStdVector(), acceleration, dt); - } else if (frame == vpRobot::END_EFFECTOR_FRAME) { + } + else if (frame == vpRobot::END_EFFECTOR_FRAME) { double dt = 1.0 / 1000; // 2ms double acceleration = 0.25; vpVelocityTwistMatrix fVe(get_fMe(), false); m_rtde_control->speedL((fVe * vel_sat).toStdVector(), acceleration, dt); - } else if (frame == vpRobot::CAMERA_FRAME) { + } + else if (frame == vpRobot::CAMERA_FRAME) { double dt = 1.0 / 1000; // 2ms double acceleration = 0.25; vpColVector w_v_e = vpVelocityTwistMatrix(get_fMe(), false) * vpVelocityTwistMatrix(m_eMc) * vel_sat; m_rtde_control->speedL(w_v_e.toStdVector(), acceleration, dt); - } else { + } + else { throw(vpException(vpRobotException::functionNotImplementedError, "Cannot move the robot in velocity in the specified frame: not implemented")); } @@ -847,8 +854,9 @@ vpRobot::vpRobotStateType vpRobotUniversalRobots::setRobotState(vpRobot::vpRobot throw(vpException(vpException::fatalError, "Cannot stop UR robot: robot is not connected")); } m_rtde_control->speedStop(); - } else { - // std::cout << "Change the control mode from stop to position control" << std::endl; + } + else { + // std::cout << "Change the control mode from stop to position control" << std::endl; } break; } @@ -868,5 +876,5 @@ vpRobot::vpRobotStateType vpRobotUniversalRobots::setRobotState(vpRobot::vpRobot #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotUniversalRobots.cpp.o) has no // symbols -void dummy_vpRobotUniversalRobots(){}; +void dummy_vpRobotUniversalRobots() { }; #endif diff --git a/modules/robot/test/servo-afma6/testRobotAfma6Pose.cpp b/modules/robot/test/servo-afma6/testRobotAfma6Pose.cpp index dd67da4f26..5334db4234 100644 --- a/modules/robot/test/servo-afma6/testRobotAfma6Pose.cpp +++ b/modules/robot/test/servo-afma6/testRobotAfma6Pose.cpp @@ -149,7 +149,7 @@ int main() } // From now, in target[i], we have the 3D coordinates of a point in the - // object frame, and their correspondances in the camera frame. We can now + // object frame, and their correspondences in the camera frame. We can now // compute the pose cMo between the camera and the object. vpPose pose; // Add the 4 points to compute the pose diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsCartPosition.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsCartPosition.cpp index e97d42ecdb..032adcbcd3 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsCartPosition.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsCartPosition.cpp @@ -43,7 +43,7 @@ #include -#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UR_RTDE) #include @@ -54,9 +54,10 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip " << robot_ip << "] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -67,8 +68,8 @@ int main(int argc, char **argv) std::cout << "Connected robot model: " << robot.getRobotModel() << std::endl; std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -106,10 +107,12 @@ int main(int argc, char **argv) // Move to cartesian position robot.setPosition(vpRobot::CAMERA_FRAME, vpPoseVector(fMc)); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -121,12 +124,7 @@ int main(int argc, char **argv) #else int main() { -#if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." - << std::endl; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif + << std::endl; } #endif diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsCartVelocity.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsCartVelocity.cpp index 7d47529d54..f1ca50e1b9 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsCartVelocity.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsCartVelocity.cpp @@ -43,7 +43,7 @@ #include -#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UR_RTDE) #include @@ -54,9 +54,10 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip " << robot_ip << "] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -66,8 +67,8 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -120,10 +121,12 @@ int main(int argc, char **argv) std::cout << "Ask to stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -135,13 +138,8 @@ int main(int argc, char **argv) #else int main() { -#if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." - << std::endl; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif + << std::endl; } #endif diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsGetData.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsGetData.cpp index deeb52ec00..b4efff7e50 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsGetData.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsGetData.cpp @@ -43,7 +43,7 @@ #include -#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UR_RTDE) #include @@ -54,9 +54,10 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip " << robot_ip << "] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -74,10 +75,12 @@ int main(int argc, char **argv) std::cout << "Robot model : " << db_client->getRobotModel() << std::endl; std::cout << "PolyScope version: " << db_client->polyscopeVersion() << std::endl; robot.disconnect(); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -147,13 +150,16 @@ int main(int argc, char **argv) return EXIT_FAILURE; } } - } else { + } + else { std::cout << "To proceed with this test you need to power on the robot" << std::endl; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -177,10 +183,12 @@ int main(int argc, char **argv) std::cout << "Camera or tool frame force/torque: " << cFc.t() << std::endl; vpTime::wait(10); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -192,12 +200,8 @@ int main(int argc, char **argv) #else int main() { -#if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." - << std::endl; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif + << std::endl; + } #endif diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsJointPosition.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsJointPosition.cpp index 9b601f5cac..62512b5990 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsJointPosition.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsJointPosition.cpp @@ -43,7 +43,7 @@ #include -#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UR_RTDE) #include @@ -54,9 +54,10 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip " << robot_ip << "] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -66,8 +67,8 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); // Get current position @@ -98,10 +99,12 @@ int main(int argc, char **argv) // Move back to initial position std::cout << "Move to joint position [rad]: " << q_init.t() << std::endl; robot.setPosition(vpRobot::JOINT_STATE, q_init); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -113,12 +116,7 @@ int main(int argc, char **argv) #else int main() { -#if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." - << std::endl; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif + << std::endl; } #endif diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsJointVelocity.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsJointVelocity.cpp index 8a13c81419..059ecf1a1a 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsJointVelocity.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsJointVelocity.cpp @@ -43,7 +43,7 @@ #include -#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UR_RTDE) #include @@ -54,9 +54,10 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip " << robot_ip << "] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -66,8 +67,8 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -114,10 +115,12 @@ int main(int argc, char **argv) std::cout << "Ask to stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "ur_rtde exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -129,12 +132,7 @@ int main(int argc, char **argv) #else int main() { -#if !defined(VISP_HAVE_UR_RTDE) std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..." - << std::endl; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl; -#endif + << std::endl; } #endif diff --git a/modules/robot/test/servo-viper/testRobotViper850Pose.cpp b/modules/robot/test/servo-viper/testRobotViper850Pose.cpp index ad6847b7f5..c53da9058c 100644 --- a/modules/robot/test/servo-viper/testRobotViper850Pose.cpp +++ b/modules/robot/test/servo-viper/testRobotViper850Pose.cpp @@ -151,7 +151,7 @@ int main() } // From now, in target[i], we have the 3D coordinates of a point in the - // object frame, and their correspondances in the camera frame. We can now + // object frame, and their correspondences in the camera frame. We can now // compute the pose cMo between the camera and the object. vpPose pose; // Add the 4 points to compute the pose diff --git a/modules/sensor/include/visp3/sensor/vpLaserScan.h b/modules/sensor/include/visp3/sensor/vpLaserScan.h index e454eda119..2c659552f2 100644 --- a/modules/sensor/include/visp3/sensor/vpLaserScan.h +++ b/modules/sensor/include/visp3/sensor/vpLaserScan.h @@ -65,13 +65,12 @@ class VISP_EXPORT vpLaserScan */ vpLaserScan() : listScanPoints(), startTimestamp(0), endTimestamp(0), measurementId(0), numSteps(0), startAngle(0), stopAngle(0), - numPoints(0) - { - } + numPoints(0) + { } /*! Copy constructor. */ vpLaserScan(const vpLaserScan &scan) : listScanPoints(scan.listScanPoints), startTimestamp(0), endTimestamp(0), measurementId(0), numSteps(0), - startAngle(0), stopAngle(0), numPoints(0) + startAngle(0), stopAngle(0), numPoints(0) { startTimestamp = scan.startTimestamp; endTimestamp = scan.endTimestamp; @@ -82,7 +81,7 @@ class VISP_EXPORT vpLaserScan numPoints = scan.numPoints; } /*! Default destructor that does nothing. */ - virtual ~vpLaserScan(){}; + virtual ~vpLaserScan() { }; /*! Add the scan point at the end of the list. */ inline void addPoint(const vpScanPoint &p) { listScanPoints.push_back(p); } /*! Drop the list of points. */ @@ -90,9 +89,7 @@ class VISP_EXPORT vpLaserScan /*! Get the list of points. */ inline std::vector getScanPoints() { return listScanPoints; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpLaserScan &operator=(const vpLaserScan &scan) = default; -#endif /*! Specifies the id of former measurements and increases with every measurement. */ diff --git a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h index f0d102746c..4f06577a7a 100644 --- a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h +++ b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) #include #include diff --git a/modules/sensor/include/visp3/sensor/vpRealSense.h b/modules/sensor/include/visp3/sensor/vpRealSense.h index 50887f98ab..d64c5ed770 100644 --- a/modules/sensor/include/visp3/sensor/vpRealSense.h +++ b/modules/sensor/include/visp3/sensor/vpRealSense.h @@ -46,7 +46,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE) #include @@ -413,7 +413,8 @@ class VISP_EXPORT vpRealSense friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRealSense &rs); - struct vpRsStreamParams { + struct vpRsStreamParams + { int m_streamWidth; int m_streamHeight; rs::format m_streamFormat; @@ -421,15 +422,13 @@ class VISP_EXPORT vpRealSense vpRsStreamParams() : m_streamWidth(640), m_streamHeight(480), m_streamFormat(rs::format::rgba8), m_streamFramerate(30) - { - } + { } vpRsStreamParams(const int streamWidth, const int streamHeight, const rs::format &streamFormat, const int streamFramerate) : m_streamWidth(streamWidth), m_streamHeight(streamHeight), m_streamFormat(streamFormat), - m_streamFramerate(streamFramerate) - { - } + m_streamFramerate(streamFramerate) + { } }; void setEnableStream(const rs::stream &stream, bool status); diff --git a/modules/sensor/include/visp3/sensor/vpRealSense2.h b/modules/sensor/include/visp3/sensor/vpRealSense2.h index 3d7aa491d6..40f5c9c0f5 100644 --- a/modules/sensor/include/visp3/sensor/vpRealSense2.h +++ b/modules/sensor/include/visp3/sensor/vpRealSense2.h @@ -38,7 +38,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE2) #include #include diff --git a/modules/sensor/include/visp3/sensor/vpScanPoint.h b/modules/sensor/include/visp3/sensor/vpScanPoint.h index 9222320201..f2633e72ef 100644 --- a/modules/sensor/include/visp3/sensor/vpScanPoint.h +++ b/modules/sensor/include/visp3/sensor/vpScanPoint.h @@ -73,7 +73,7 @@ class /* VISP_EXPORT */ vpScanPoint // Note that here VISP_EXPORT should not { public: /*! Default constructor. */ - inline vpScanPoint() : rDist(0), hAngle(0), vAngle(0) {} + inline vpScanPoint() : rDist(0), hAngle(0), vAngle(0) { } /*! Copy constructor. */ inline vpScanPoint(const vpScanPoint &scanpoint) : rDist(0), hAngle(0), vAngle(0) { @@ -94,7 +94,7 @@ class /* VISP_EXPORT */ vpScanPoint // Note that here VISP_EXPORT should not this->vAngle = v_angle; } /*! Destructor that does nothing. */ - inline virtual ~vpScanPoint(){}; + inline virtual ~vpScanPoint() { }; /*! Set the polar point coordinates. \param r_dist : Radial distance in meter. @@ -143,9 +143,7 @@ class /* VISP_EXPORT */ vpScanPoint // Note that here VISP_EXPORT should not */ inline double getZ() const { return (rDist * cos(this->hAngle) * sin(this->vAngle)); } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpScanPoint &operator=(const vpScanPoint &) = default; -#endif friend inline std::ostream &operator<<(std::ostream &s, const vpScanPoint &p); diff --git a/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp b/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp index 61f96720ea..f6aec9b132 100644 --- a/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp +++ b/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp @@ -517,7 +517,7 @@ void vp1394CMUGrabber::displayCameraModel() \param format : Camera video format. \param mode : Camera video mode. - See the following table for the correspondances between the input + See the following table for the correspondences between the input format and mode and the resulting video color coding. @@ -617,7 +617,7 @@ void vp1394CMUGrabber::setVideoMode(unsigned long format, unsigned long mode) Set camera framerate rate. This method has to be called before open(). \param fps : Value between 0 to 7 used to select a specific camera - framerate. See the following table for the correspondances between the input + framerate. See the following table for the correspondences between the input value and the framerate.
@@ -682,7 +682,7 @@ void vp1394CMUGrabber::setFramerate(unsigned long fps) Get the video framerate. \return Value between 0 to 7 corresponding to a specific camera framerate. - See the following table for the correspondances between the returned + See the following table for the correspondences between the returned value and the framerate.
diff --git a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp index 340ef5bcf5..b5e8ac3fc8 100644 --- a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp +++ b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) #include #include #include @@ -55,7 +55,7 @@ /*! * Default constructor. */ -vpOccipitalStructure::vpOccipitalStructure() : m_invalidDepthValue(0.0f), m_maxZ(15000.0f) {} +vpOccipitalStructure::vpOccipitalStructure() : m_invalidDepthValue(0.0f), m_maxZ(15000.0f) { } /*! * Default destructor that stops the streaming. @@ -571,7 +571,7 @@ void vpOccipitalStructure::getIMUData(vpColVector *imu_vel, vpColVector *imu_acc (*imu_vel)[1] = imu_rotationRate.y; (*imu_vel)[2] = imu_rotationRate.z; imu_vel_timestamp = - m_delegate.m_gyroscopeEvent.arrivalTimestamp(); // Relative to an unspecified epoch. (see documentation). + m_delegate.m_gyroscopeEvent.arrivalTimestamp(); // Relative to an unspecified epoch. (see documentation). } if (imu_acc != NULL) { @@ -610,9 +610,9 @@ bool vpOccipitalStructure::open(const ST::CaptureSessionSettings &settings) // recieves the first frame or a timeout. std::unique_lock u(m_delegate.m_sampleLock); std::cv_status var = - m_delegate.cv_sampleLock.wait_for(u, std::chrono::seconds(20)); // Make sure a device is connected. + m_delegate.cv_sampleLock.wait_for(u, std::chrono::seconds(20)); // Make sure a device is connected. - // In case the device is not connected, open() should return false. +// In case the device is not connected, open() should return false. if (var == std::cv_status::timeout) { m_init = false; return m_init; @@ -926,7 +926,7 @@ vpCameraParameters vpOccipitalStructure::getCameraParameters(const vpOccipitalSt if (proj_type == vpCameraParameters::perspectiveProjWithoutDistortion) m_visible_camera_parameters = - vpCameraParameters(cam_intrinsics.fx, cam_intrinsics.fy, cam_intrinsics.cx, cam_intrinsics.cy); + vpCameraParameters(cam_intrinsics.fx, cam_intrinsics.fy, cam_intrinsics.cx, cam_intrinsics.cy); return m_visible_camera_parameters; break; @@ -934,7 +934,7 @@ vpCameraParameters vpOccipitalStructure::getCameraParameters(const vpOccipitalSt case vpOccipitalStructureStream::depth: cam_intrinsics = m_delegate.m_depthFrame.intrinsics(); m_depth_camera_parameters = - vpCameraParameters(cam_intrinsics.fx, cam_intrinsics.fy, cam_intrinsics.cx, cam_intrinsics.cy); + vpCameraParameters(cam_intrinsics.fx, cam_intrinsics.fy, cam_intrinsics.cx, cam_intrinsics.cy); return m_depth_camera_parameters; break; @@ -1135,7 +1135,8 @@ void vpOccipitalStructure::getColoredPointcloud(pcl::PointCloudpoints[(size_t)depth_pixel_index].g = (uint8_t)0; pointcloud->points[(size_t)depth_pixel_index].b = (uint8_t)0; #endif - } else { + } + else { unsigned int i_ = (unsigned int)color_pixel.x; unsigned int j_ = (unsigned int)color_pixel.y; @@ -1143,44 +1144,48 @@ void vpOccipitalStructure::getColoredPointcloud(pcl::PointCloud(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]) | - static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 | - static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]) - << 16); - } else { + (static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]) | + static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 | + static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]) + << 16); + } + else { rgb = - (static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]) << 16 | - static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 | - static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2])); + (static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]) << 16 | + static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 | + static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2])); } pointcloud->points[(size_t)(i * depth_width + j)].rgb = *reinterpret_cast(&rgb); #else if (swap_rb) { pointcloud->points[(size_t)depth_pixel_index].b = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]; pointcloud->points[(size_t)depth_pixel_index].g = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]; pointcloud->points[(size_t)depth_pixel_index].r = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]; - } else { + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]; + } + else { pointcloud->points[(size_t)depth_pixel_index].r = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]; pointcloud->points[(size_t)depth_pixel_index].g = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]; pointcloud->points[(size_t)depth_pixel_index].b = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]; } #endif } - } else { + } + else { #if PCL_VERSION_COMPARE(<, 1, 1, 0) uint32_t rgb = 0; if (swap_rb) { rgb = (static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]) | static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]) << 8 | static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]) << 16); - } else { + } + else { rgb = (static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]) << 16 | static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]) << 8 | static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2])); @@ -1190,18 +1195,19 @@ void vpOccipitalStructure::getColoredPointcloud(pcl::PointCloudpoints[(size_t)depth_pixel_index].b = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]; pointcloud->points[(size_t)depth_pixel_index].g = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]; pointcloud->points[(size_t)depth_pixel_index].r = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]; - } else { + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]; + } + else { pointcloud->points[(size_t)depth_pixel_index].r = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]; pointcloud->points[(size_t)depth_pixel_index].g = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]; pointcloud->points[(size_t)depth_pixel_index].b = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]; } #endif } diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp index f3dee5d119..b1b084f5af 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp @@ -39,7 +39,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE) #include "vpRealSense_impl.h" @@ -48,7 +48,7 @@ */ vpRealSense::vpRealSense() : m_context(), m_device(NULL), m_num_devices(0), m_serial_no(), m_intrinsics(), m_max_Z(8), m_enableStreams(), - m_useStreamPresets(), m_streamPresets(), m_streamParams(), m_invalidDepthValue(0.0f) + m_useStreamPresets(), m_streamPresets(), m_streamParams(), m_invalidDepthValue(0.0f) { initStream(); } @@ -137,8 +137,8 @@ void vpRealSense::open() // Enable only infrared2 stream if supported m_enableStreams[rs::stream::infrared2] = m_enableStreams[rs::stream::infrared2] - ? m_device->supports(rs::capabilities::infrared2) - : m_enableStreams[rs::stream::infrared2]; + ? m_device->supports(rs::capabilities::infrared2) + : m_enableStreams[rs::stream::infrared2]; if (m_device->is_streaming()) { m_device->stop(); @@ -155,7 +155,8 @@ void vpRealSense::open() if (m_enableStreams[rs::stream::color]) { if (m_useStreamPresets[rs::stream::color]) { m_device->enable_stream(rs::stream::color, m_streamPresets[rs::stream::color]); - } else { + } + else { m_device->enable_stream(rs::stream::color, m_streamParams[rs::stream::color].m_streamWidth, m_streamParams[rs::stream::color].m_streamHeight, m_streamParams[rs::stream::color].m_streamFormat, @@ -166,7 +167,8 @@ void vpRealSense::open() if (m_enableStreams[rs::stream::depth]) { if (m_useStreamPresets[rs::stream::depth]) { m_device->enable_stream(rs::stream::depth, m_streamPresets[rs::stream::depth]); - } else { + } + else { m_device->enable_stream(rs::stream::depth, m_streamParams[rs::stream::depth].m_streamWidth, m_streamParams[rs::stream::depth].m_streamHeight, m_streamParams[rs::stream::depth].m_streamFormat, @@ -177,7 +179,8 @@ void vpRealSense::open() if (m_enableStreams[rs::stream::infrared]) { if (m_useStreamPresets[rs::stream::infrared]) { m_device->enable_stream(rs::stream::infrared, m_streamPresets[rs::stream::infrared]); - } else { + } + else { m_device->enable_stream(rs::stream::infrared, m_streamParams[rs::stream::infrared].m_streamWidth, m_streamParams[rs::stream::infrared].m_streamHeight, m_streamParams[rs::stream::infrared].m_streamFormat, @@ -188,7 +191,8 @@ void vpRealSense::open() if (m_enableStreams[rs::stream::infrared2]) { if (m_useStreamPresets[rs::stream::infrared2]) { m_device->enable_stream(rs::stream::infrared2, m_streamPresets[rs::stream::infrared2]); - } else { + } + else { m_device->enable_stream(rs::stream::infrared2, m_streamParams[rs::stream::infrared2].m_streamWidth, m_streamParams[rs::stream::infrared2].m_streamHeight, m_streamParams[rs::stream::infrared2].m_streamFormat, @@ -213,19 +217,19 @@ void vpRealSense::open() if (m_enableStreams[rs::stream::depth]) { m_intrinsics[rs::stream::color_aligned_to_depth] = - m_device->get_stream_intrinsics(rs::stream::color_aligned_to_depth); + m_device->get_stream_intrinsics(rs::stream::color_aligned_to_depth); m_intrinsics[rs::stream::depth_aligned_to_color] = - m_device->get_stream_intrinsics(rs::stream::depth_aligned_to_color); + m_device->get_stream_intrinsics(rs::stream::depth_aligned_to_color); m_intrinsics[rs::stream::depth_aligned_to_rectified_color] = - m_device->get_stream_intrinsics(rs::stream::depth_aligned_to_rectified_color); + m_device->get_stream_intrinsics(rs::stream::depth_aligned_to_rectified_color); } } if (m_enableStreams[rs::stream::depth] && m_enableStreams[rs::stream::infrared2]) { m_intrinsics[rs::stream::depth_aligned_to_infrared2] = - m_device->get_stream_intrinsics(rs::stream::depth_aligned_to_infrared2); + m_device->get_stream_intrinsics(rs::stream::depth_aligned_to_infrared2); m_intrinsics[rs::stream::infrared2_aligned_to_depth] = - m_device->get_stream_intrinsics(rs::stream::infrared2_aligned_to_depth); + m_device->get_stream_intrinsics(rs::stream::infrared2_aligned_to_depth); } // Start device @@ -294,7 +298,8 @@ vpCameraParameters vpRealSense::getCameraParameters(const rs::stream &stream, if (type == vpCameraParameters::perspectiveProjWithDistortion) { double kdu = intrinsics.coeffs[0]; cam.initPersProjWithDistortion(px, py, u0, v0, -kdu, kdu); - } else { + } + else { cam.initPersProjWithoutDistortion(px, py, u0, v0); } return cam; @@ -1032,7 +1037,7 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense &rs) auto intrin = rs.getHandler()->get_stream_intrinsics(stream); std::cout << "Capturing " << stream << " at " << intrin.width << " x " << intrin.height; std::cout << std::setprecision(1) << std::fixed << ", fov = " << intrin.hfov() << " x " << intrin.vfov() - << ", distortion = " << intrin.model() << std::endl; + << ", distortion = " << intrin.model() << std::endl; } std::cout.precision(ss); @@ -1042,5 +1047,5 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense &rs) #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vpRealSense.cpp.o) has no // symbols -void dummy_vpRealSense(){}; +void dummy_vpRealSense() { }; #endif diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp index 053906f150..4ed0468df4 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE2) #include #include #include @@ -70,9 +70,8 @@ bool operator==(const rs2_extrinsics &lhs, const rs2_extrinsics &rhs) */ vpRealSense2::vpRealSense2() : m_depthScale(0.0f), m_invalidDepthValue(0.0f), m_max_Z(8.0f), m_pipe(), m_pipelineProfile(), m_pointcloud(), - m_points(), m_pos(), m_quat(), m_rot(), m_product_line(), m_init(false) -{ -} + m_points(), m_pos(), m_quat(), m_rot(), m_product_line(), m_init(false) +{ } /*! * Default destructor that stops the streaming. @@ -734,14 +733,17 @@ void vpRealSense2::getColorFrame(const rs2::frame &frame, vpImage &color if (frame.get_profile().format() == RS2_FORMAT_RGB8) { vpImageConvert::RGBToRGBa(const_cast(static_cast(frame.get_data())), reinterpret_cast(color.bitmap), width, height); - } else if (frame.get_profile().format() == RS2_FORMAT_RGBA8) { + } + else if (frame.get_profile().format() == RS2_FORMAT_RGBA8) { memcpy(reinterpret_cast(color.bitmap), const_cast(static_cast(frame.get_data())), width * height * sizeof(vpRGBa)); - } else if (frame.get_profile().format() == RS2_FORMAT_BGR8) { + } + else if (frame.get_profile().format() == RS2_FORMAT_BGR8) { vpImageConvert::BGRToRGBa(const_cast(static_cast(frame.get_data())), reinterpret_cast(color.bitmap), width, height); - } else { + } + else { throw vpException(vpException::fatalError, "RealSense Camera - color stream not supported!"); } } @@ -785,13 +787,16 @@ void vpRealSense2::getGreyFrame(const rs2::frame &frame, vpImage if (frame.get_profile().format() == RS2_FORMAT_RGB8) { vpImageConvert::RGBToGrey(const_cast(static_cast(frame.get_data())), grey.bitmap, width, height); - } else if (frame.get_profile().format() == RS2_FORMAT_RGBA8) { + } + else if (frame.get_profile().format() == RS2_FORMAT_RGBA8) { vpImageConvert::RGBaToGrey(const_cast(static_cast(frame.get_data())), grey.bitmap, width * height); - } else if (frame.get_profile().format() == RS2_FORMAT_BGR8) { + } + else if (frame.get_profile().format() == RS2_FORMAT_BGR8) { vpImageConvert::BGRToGrey(const_cast(static_cast(frame.get_data())), grey.bitmap, width, height); - } else { + } + else { throw vpException(vpException::fatalError, "RealSense Camera - color stream not supported!"); } } @@ -862,7 +867,7 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, std::vecto auto pixels_distance = m_depthScale * p_depth_frame[depth_pixel_index]; float points[3]; - const float pixel[] = {(float)j, (float)i}; + const float pixel[] = { (float)j, (float)i }; rs2_deproject_pixel_to_point(points, &depth_intrinsics, pixel, pixels_distance); if (pixels_distance > m_max_Z) @@ -915,7 +920,7 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, pcl::Point auto pixels_distance = m_depthScale * p_depth_frame[depth_pixel_index]; float points[3]; - const float pixel[] = {(float)j, (float)i}; + const float pixel[] = { (float)j, (float)i }; rs2_deproject_pixel_to_point(points, &depth_intrinsics, pixel, pixels_distance); if (pixels_distance > m_max_Z) @@ -935,7 +940,8 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, pcl::Point pointcloud->points[i].x = m_invalidDepthValue; pointcloud->points[i].y = m_invalidDepthValue; pointcloud->points[i].z = m_invalidDepthValue; - } else { + } + else { pointcloud->points[i].x = vertices[i].x; pointcloud->points[i].y = vertices[i].y; pointcloud->points[i].z = vertices[i].z; @@ -964,8 +970,8 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2: const uint16_t *p_depth_frame = reinterpret_cast(depth_frame.get_data()); const rs2_extrinsics depth2ColorExtrinsics = - depth_frame.get_profile().as().get_extrinsics_to( - color_frame.get_profile().as()); + depth_frame.get_profile().as().get_extrinsics_to( + color_frame.get_profile().as()); const rs2_intrinsics depth_intrinsics = depth_frame.get_profile().as().get_intrinsics(); const rs2_intrinsics color_intrinsics = color_frame.get_profile().as().get_intrinsics(); @@ -980,10 +986,10 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2: identity.rotation[i * 3 + i] = 1; } const bool registered_streams = - (depth2ColorExtrinsics == identity) && (color_width == depth_width) && (color_height == depth_height); + (depth2ColorExtrinsics == identity) && (color_width == depth_width) && (color_height == depth_height); - // Multi-threading if OpenMP - // Concurrent writes at different locations are safe +// Multi-threading if OpenMP +// Concurrent writes at different locations are safe #pragma omp parallel for schedule(dynamic) for (int i = 0; i < depth_height; i++) { auto depth_pixel_index = i * depth_width; @@ -1014,7 +1020,7 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2: auto pixels_distance = m_depthScale * p_depth_frame[depth_pixel_index]; float depth_point[3]; - const float pixel[] = {(float)j, (float)i}; + const float pixel[] = { (float)j, (float)i }; rs2_deproject_pixel_to_point(depth_point, &depth_intrinsics, pixel, pixels_distance); if (pixels_distance > m_max_Z) { @@ -1046,7 +1052,8 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2: pointcloud->points[(size_t)depth_pixel_index].g = (uint8_t)157; pointcloud->points[(size_t)depth_pixel_index].b = (uint8_t)198; #endif - } else { + } + else { unsigned int i_ = (unsigned int)color_pixel[1]; unsigned int j_ = (unsigned int)color_pixel[0]; @@ -1054,44 +1061,48 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2: uint32_t rgb = 0; if (swap_rb) { rgb = - (static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]) | - static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 | - static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]) - << 16); - } else { + (static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]) | + static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 | + static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]) + << 16); + } + else { rgb = - (static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]) << 16 | - static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 | - static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2])); + (static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]) << 16 | + static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 | + static_cast(p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2])); } pointcloud->points[(size_t)(i * depth_width + j)].rgb = *reinterpret_cast(&rgb); #else if (swap_rb) { pointcloud->points[(size_t)depth_pixel_index].b = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]; pointcloud->points[(size_t)depth_pixel_index].g = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]; pointcloud->points[(size_t)depth_pixel_index].r = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]; - } else { + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]; + } + else { pointcloud->points[(size_t)depth_pixel_index].r = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel]; pointcloud->points[(size_t)depth_pixel_index].g = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 1]; pointcloud->points[(size_t)depth_pixel_index].b = - p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]; + p_color_frame[(i_ * (unsigned int)color_width + j_) * nb_color_pixel + 2]; } #endif } - } else { + } + else { #if PCL_VERSION_COMPARE(<, 1, 1, 0) uint32_t rgb = 0; if (swap_rb) { rgb = (static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]) | static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]) << 8 | static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]) << 16); - } else { + } + else { rgb = (static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]) << 16 | static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]) << 8 | static_cast(p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2])); @@ -1101,18 +1112,19 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2: #else if (swap_rb) { pointcloud->points[(size_t)depth_pixel_index].b = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]; pointcloud->points[(size_t)depth_pixel_index].g = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]; pointcloud->points[(size_t)depth_pixel_index].r = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]; - } else { + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]; + } + else { pointcloud->points[(size_t)depth_pixel_index].r = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel]; pointcloud->points[(size_t)depth_pixel_index].g = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 1]; pointcloud->points[(size_t)depth_pixel_index].b = - p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]; + p_color_frame[(i * (unsigned int)color_width + j) * nb_color_pixel + 2]; } #endif } @@ -1456,20 +1468,20 @@ void print(const rs2_intrinsics &intrinsics, std::ostream &os) { std::stringstream ss; ss << std::left << std::setw(14) << "Width: " - << "\t" << intrinsics.width << "\n" - << std::left << std::setw(14) << "Height: " - << "\t" << intrinsics.height << "\n" - << std::left << std::setw(14) << "PPX: " - << "\t" << std::setprecision(15) << intrinsics.ppx << "\n" - << std::left << std::setw(14) << "PPY: " - << "\t" << std::setprecision(15) << intrinsics.ppy << "\n" - << std::left << std::setw(14) << "Fx: " - << "\t" << std::setprecision(15) << intrinsics.fx << "\n" - << std::left << std::setw(14) << "Fy: " - << "\t" << std::setprecision(15) << intrinsics.fy << "\n" - << std::left << std::setw(14) << "Distortion: " - << "\t" << rs2_distortion_to_string(intrinsics.model) << "\n" - << std::left << std::setw(14) << "Coeffs: "; + << "\t" << intrinsics.width << "\n" + << std::left << std::setw(14) << "Height: " + << "\t" << intrinsics.height << "\n" + << std::left << std::setw(14) << "PPX: " + << "\t" << std::setprecision(15) << intrinsics.ppx << "\n" + << std::left << std::setw(14) << "PPY: " + << "\t" << std::setprecision(15) << intrinsics.ppy << "\n" + << std::left << std::setw(14) << "Fx: " + << "\t" << std::setprecision(15) << intrinsics.fx << "\n" + << std::left << std::setw(14) << "Fy: " + << "\t" << std::setprecision(15) << intrinsics.fy << "\n" + << std::left << std::setw(14) << "Distortion: " + << "\t" << rs2_distortion_to_string(intrinsics.model) << "\n" + << std::left << std::setw(14) << "Coeffs: "; for (size_t i = 0; i < sizeof(intrinsics.coeffs) / sizeof(intrinsics.coeffs[0]); ++i) ss << "\t" << std::setprecision(15) << intrinsics.coeffs[i] << " "; @@ -1481,15 +1493,16 @@ void safe_get_intrinsics(const rs2::video_stream_profile &profile, rs2_intrinsic { try { intrinsics = profile.get_intrinsics(); - } catch (...) { + } + catch (...) { } } bool operator==(const rs2_intrinsics &lhs, const rs2_intrinsics &rhs) { return lhs.width == rhs.width && lhs.height == rhs.height && lhs.ppx == rhs.ppx && lhs.ppy == rhs.ppy && - lhs.fx == rhs.fx && lhs.fy == rhs.fy && lhs.model == rhs.model && - !std::memcmp(lhs.coeffs, rhs.coeffs, sizeof(rhs.coeffs)); + lhs.fx == rhs.fx && lhs.fy == rhs.fy && lhs.model == rhs.model && + !std::memcmp(lhs.coeffs, rhs.coeffs, sizeof(rhs.coeffs)); } std::string get_str_formats(const std::set &formats) @@ -1501,7 +1514,8 @@ std::string get_str_formats(const std::set &formats) return ss.str(); } -struct stream_and_resolution { +struct stream_and_resolution +{ rs2_stream stream; int stream_index; int width; @@ -1515,7 +1529,8 @@ struct stream_and_resolution { } }; -struct stream_and_index { +struct stream_and_index +{ rs2_stream stream; int stream_index; @@ -1550,16 +1565,16 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs) { rs2::device dev = rs.m_pipelineProfile.get_device(); os << std::left << std::setw(30) << dev.get_info(RS2_CAMERA_INFO_NAME) << std::setw(20) - << dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER) << std::setw(20) << dev.get_info(RS2_CAMERA_INFO_FIRMWARE_VERSION) - << std::endl; + << dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER) << std::setw(20) << dev.get_info(RS2_CAMERA_INFO_FIRMWARE_VERSION) + << std::endl; - // Show which options are supported by this device + // Show which options are supported by this device os << " Device info: \n"; for (auto j = 0; j < RS2_CAMERA_INFO_COUNT; ++j) { auto param = static_cast(j); if (dev.supports(param)) os << " " << std::left << std::setw(30) << rs2_camera_info_to_string(rs2_camera_info(param)) << ": \t" - << dev.get_info(param) << "\n"; + << dev.get_info(param) << "\n"; } os << "\n"; @@ -1568,13 +1583,13 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs) os << "Options for " << sensor.get_info(RS2_CAMERA_INFO_NAME) << std::endl; os << std::setw(55) << " Supported options:" << std::setw(10) << "min" << std::setw(10) << " max" << std::setw(6) - << " step" << std::setw(10) << " default" << std::endl; + << " step" << std::setw(10) << " default" << std::endl; for (auto j = 0; j < RS2_OPTION_COUNT; ++j) { auto opt = static_cast(j); if (sensor.supports(opt)) { auto range = sensor.get_option_range(opt); os << " " << std::left << std::setw(50) << opt << " : " << std::setw(5) << range.min << "... " - << std::setw(12) << range.max << std::setw(6) << range.step << std::setw(10) << range.def << "\n"; + << std::setw(12) << range.max << std::setw(6) << range.step << std::setw(10) << range.def << "\n"; } } @@ -1585,14 +1600,15 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs) os << "Stream Profiles supported by " << sensor.get_info(RS2_CAMERA_INFO_NAME) << "\n"; os << std::setw(55) << " Supported modes:" << std::setw(10) << "stream" << std::setw(10) << " resolution" - << std::setw(6) << " fps" << std::setw(10) << " format" - << "\n"; - // Show which streams are supported by this device + << std::setw(6) << " fps" << std::setw(10) << " format" + << "\n"; + // Show which streams are supported by this device for (auto &&profile : sensor.get_stream_profiles()) { if (auto video = profile.as()) { os << " " << profile.stream_name() << "\t " << video.width() << "x" << video.height() << "\t@ " - << profile.fps() << "Hz\t" << profile.format() << "\n"; - } else { + << profile.fps() << "Hz\t" << profile.format() << "\n"; + } + else { os << " " << profile.stream_name() << "\t@ " << profile.fps() << "Hz\t" << profile.format() << "\n"; } } @@ -1606,20 +1622,21 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs) // Intrinsics for (auto &&profile : sensor.get_stream_profiles()) { if (auto video = profile.as()) { - if (streams.find(stream_and_index{profile.stream_type(), profile.stream_index()}) == streams.end()) { - streams[stream_and_index{profile.stream_type(), profile.stream_index()}] = profile; + if (streams.find(stream_and_index { profile.stream_type(), profile.stream_index() }) == streams.end()) { + streams[stream_and_index { profile.stream_type(), profile.stream_index() }] = profile; } - rs2_intrinsics intrinsics{}; - stream_and_resolution stream_res{profile.stream_type(), profile.stream_index(), video.width(), video.height(), - profile.stream_name()}; + rs2_intrinsics intrinsics {}; + stream_and_resolution stream_res { profile.stream_type(), profile.stream_index(), video.width(), video.height(), + profile.stream_name() }; safe_get_intrinsics(video, intrinsics); auto it = std::find_if( (intrinsics_map[stream_res]).begin(), (intrinsics_map[stream_res]).end(), [&](const std::pair, rs2_intrinsics> &kvp) { return intrinsics == kvp.second; }); if (it == (intrinsics_map[stream_res]).end()) { - (intrinsics_map[stream_res]).push_back({{profile.format()}, intrinsics}); - } else { + (intrinsics_map[stream_res]).push_back({ {profile.format()}, intrinsics }); + } + else { it->first.insert(profile.format()); // If the intrinsics are equals, // add the profile format to // format set @@ -1634,10 +1651,11 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs) for (auto &intrinsics : kvp.second) { auto formats = get_str_formats(intrinsics.first); os << "Intrinsic of \"" << stream_res.stream_name << "\"\t " << stream_res.width << "x" << stream_res.height - << "\t " << formats << "\n"; - if (intrinsics.second == rs2_intrinsics{}) { + << "\t " << formats << "\n"; + if (intrinsics.second == rs2_intrinsics {}) { os << "Intrinsic NOT available!\n\n"; - } else { + } + else { print(intrinsics.second, os); } } @@ -1648,8 +1666,8 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs) for (auto kvp1 = streams.begin(); kvp1 != streams.end(); ++kvp1) { for (auto kvp2 = streams.begin(); kvp2 != streams.end(); ++kvp2) { os << "Extrinsic from \"" << kvp1->second.stream_name() << "\"\t " - << "To" - << "\t \"" << kvp2->second.stream_name() << "\"\n"; + << "To" + << "\t \"" << kvp2->second.stream_name() << "\"\n"; auto extrinsics = kvp1->second.get_extrinsics_to(kvp2->second); print(extrinsics, os); } @@ -1661,5 +1679,5 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs) #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vpRealSense2.cpp.o) has no // symbols -void dummy_vpRealSense2(){}; +void dummy_vpRealSense2() { }; #endif diff --git a/modules/sensor/test/mocap/testMocapQualisys.cpp b/modules/sensor/test/mocap/testMocapQualisys.cpp index a674985472..ec1a79255b 100644 --- a/modules/sensor/test/mocap/testMocapQualisys.cpp +++ b/modules/sensor/test/mocap/testMocapQualisys.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_QUALISYS) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_QUALISYS) #include #include @@ -66,39 +66,39 @@ void quitHandler(int sig) void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--server-address
] [-sa]" - << " [--only-body] [-ob]" - << " [--all-bodies]" - << " [--verbose] [-v]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--server-address
] [-sa]" + << " [--only-body] [-ob]" + << " [--all-bodies]" + << " [--verbose] [-v]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --server-address
" << std::endl - << " Server address." << std::endl - << " Default: 192.168.30.42." << std::endl - << std::endl - << " --only-body " << std::endl - << " Name of the specific body you want to be displayed." << std::endl - << " Default: ''" << std::endl - << std::endl - << " --all-bodies" << std::endl - << " When used, get all bodies pose including non visible bodies." << std::endl - << std::endl - << " --verbose, -v" << std::endl - << " Enable verbose mode." << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --server-address
" << std::endl + << " Server address." << std::endl + << " Default: 192.168.30.42." << std::endl + << std::endl + << " --only-body " << std::endl + << " Name of the specific body you want to be displayed." << std::endl + << " Default: ''" << std::endl + << std::endl + << " --all-bodies" << std::endl + << " When used, get all bodies pose including non visible bodies." << std::endl + << std::endl + << " --verbose, -v" << std::endl + << " Enable verbose mode." << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to test Qualisys connection:" << std::endl - << " " << argv[0] << " --server-address 127.0.0.1 --verbose" << std::endl - << std::endl; + << " Example to test Qualisys connection:" << std::endl + << " " << argv[0] << " --server-address 127.0.0.1 --verbose" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } @@ -119,7 +119,8 @@ void mocap_loop(std::mutex &lock, bool opt_verbose, bool opt_all_bodies, std::st if (!qualisys.getBodiesPose(bodies_pose, opt_all_bodies)) { std::cout << "Qualisys error. Check the Qualisys Task Manager" << std::endl; } - } else { + } + else { vpHomogeneousMatrix pose; if (!qualisys.getSpecificBodyPose(opt_onlyBody, pose)) { std::cout << "Qualisys error. Check the Qualisys Task Manager" << std::endl; @@ -149,7 +150,7 @@ void display_loop(std::mutex &lock, const std::mapfirst << std::endl; if (verbose) { std::cout << " Translation [m]: " << it->second.getTranslationVector().t() << std::endl - << " Quaternion: " << vpQuaternionVector(it->second.getRotationMatrix()).t() << std::endl; + << " Quaternion: " << vpQuaternionVector(it->second.getRotationMatrix()).t() << std::endl; std::cout << " Roll/pitch/yaw [deg]: "; for (unsigned int i = 0; i < 3; i++) { std::cout << vpMath::deg(rxyz[i]) << " "; @@ -178,18 +179,23 @@ int main(int argc, const char *argv[]) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { opt_verbose = true; - } else if (std::string(argv[i]) == "--server-address" || std::string(argv[i]) == "-sa") { + } + else if (std::string(argv[i]) == "--server-address" || std::string(argv[i]) == "-sa") { opt_serverAddress = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--only-body" || std::string(argv[i]) == "-ob") { + } + else if (std::string(argv[i]) == "--only-body" || std::string(argv[i]) == "-ob") { opt_onlyBody = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--all-bodies") { + } + else if (std::string(argv[i]) == "--all-bodies") { opt_all_bodies = true; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -211,12 +217,8 @@ int main(int argc, const char *argv[]) #else int main() { -#ifndef VISP_HAVE_QUALISYS std::cout << "Install qualisys_cpp_sdk to be able to test Qualisys Mocap System using ViSP" << std::endl; -#endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "This test required c++11 or more recent c++ standard." << std::endl; -#endif + return EXIT_SUCCESS; } #endif diff --git a/modules/sensor/test/mocap/testMocapVicon.cpp b/modules/sensor/test/mocap/testMocapVicon.cpp index 23fd27844a..10c1f4c274 100644 --- a/modules/sensor/test/mocap/testMocapVicon.cpp +++ b/modules/sensor/test/mocap/testMocapVicon.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_VICON) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_VICON) #include #include @@ -68,39 +68,39 @@ void quitHandler(int sig) void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--server-address
]" - << " [--only-body]" - << " [--all-bodies]" - << " [--verbose] [-v]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--server-address
]" + << " [--only-body]" + << " [--all-bodies]" + << " [--verbose] [-v]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --server-address
" << std::endl - << " Server address." << std::endl - << " Default: 192.168.30.1." << std::endl - << std::endl - << " --only-body " << std::endl - << " Name of the specific body you want to be displayed." << std::endl - << " Default: ''" << std::endl - << std::endl - << " --all-bodies" << std::endl - << " When used, get all bodies pose including non visible bodies." << std::endl - << std::endl - << " --verbose, -v" << std::endl - << " Enable verbose mode." << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --server-address
" << std::endl + << " Server address." << std::endl + << " Default: 192.168.30.1." << std::endl + << std::endl + << " --only-body " << std::endl + << " Name of the specific body you want to be displayed." << std::endl + << " Default: ''" << std::endl + << std::endl + << " --all-bodies" << std::endl + << " When used, get all bodies pose including non visible bodies." << std::endl + << std::endl + << " --verbose, -v" << std::endl + << " Enable verbose mode." << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to test Vicon connection:" << std::endl - << " " << argv[0] << " --server-address 127.0.0.1 --verbose" << std::endl - << std::endl; + << " Example to test Vicon connection:" << std::endl + << " " << argv[0] << " --server-address 127.0.0.1 --verbose" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } @@ -116,7 +116,8 @@ void mocap_loop(std::mutex &lock, bool opt_verbose, bool opt_all_bodies, std::st if (opt_onlyBody == "") { vicon.getBodiesPose(bodies_pose, opt_all_bodies); - } else { + } + else { vpHomogeneousMatrix pose; vicon.getSpecificBodyPose(opt_onlyBody, pose); bodies_pose[opt_onlyBody] = pose; @@ -144,7 +145,7 @@ void display_loop(std::mutex &lock, const std::mapfirst << std::endl; if (verbose) { std::cout << " Translation [m]: " << it->second.getTranslationVector().t() << std::endl - << " Quaternion: " << vpQuaternionVector(it->second.getRotationMatrix()).t() << std::endl; + << " Quaternion: " << vpQuaternionVector(it->second.getRotationMatrix()).t() << std::endl; std::cout << " Roll/pitch/yaw [deg]: "; for (unsigned int i = 0; i < 3; i++) { std::cout << vpMath::deg(rxyz[i]) << " "; @@ -172,18 +173,23 @@ int main(int argc, const char *argv[]) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { opt_verbose = true; - } else if (std::string(argv[i]) == "--server-address") { + } + else if (std::string(argv[i]) == "--server-address") { opt_serverAddress = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--only-body") { + } + else if (std::string(argv[i]) == "--only-body") { opt_onlyBody = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--all-bodies") { + } + else if (std::string(argv[i]) == "--all-bodies") { opt_all_bodies = true; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -205,12 +211,8 @@ int main(int argc, const char *argv[]) #else int main() { -#ifndef VISP_HAVE_VICON std::cout << "Install Vicon Datastream SDK to be able to test Vicon Mocap System using ViSP" << std::endl; -#endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "This test required c++11 or more recent c++ standard." << std::endl; -#endif + return EXIT_SUCCESS; } #endif diff --git a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp index e4e8445646..3fbbaee648 100644 --- a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp +++ b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp @@ -43,8 +43,7 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include @@ -79,12 +78,12 @@ int main() #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) I_visible = - vpImage(sc.getHeight(vpOccipitalStructure::visible), sc.getWidth(vpOccipitalStructure::visible), 0); + vpImage(sc.getHeight(vpOccipitalStructure::visible), sc.getWidth(vpOccipitalStructure::visible), 0); display_visible.setDownScalingFactor(display_scale); display_visible.init(I_visible, 10, 10, "Visible image"); I_depth_raw = - vpImage(sc.getHeight(vpOccipitalStructure::depth), sc.getWidth(vpOccipitalStructure::depth), 0); + vpImage(sc.getHeight(vpOccipitalStructure::depth), sc.getWidth(vpOccipitalStructure::depth), 0); I_depth = vpImage(sc.getHeight(vpOccipitalStructure::depth), sc.getWidth(vpOccipitalStructure::depth)); display_depth.setDownScalingFactor(display_scale); display_depth.init(I_depth, static_cast(I_visible.getWidth() / display_scale) + 20, 10, "Depth image"); @@ -109,9 +108,11 @@ int main() std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Structure SDK error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -125,10 +126,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install libStructure, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #elif !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) std::cout << "You don't have X11 or GDI display capabilities" << std::endl; #endif diff --git a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp index 12d5fb39d0..05be0da7a8 100644 --- a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp +++ b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp @@ -43,7 +43,7 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) #include #include @@ -104,9 +104,11 @@ int main() quit = true; } } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Structure SDK error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -115,16 +117,9 @@ int main() #else int main() { -#if !defined(VISP_HAVE_OCCIPITAL_STRUCTURE) std::cout << "You do not have Occipital Structure SDK functionality enabled..." << std::endl; std::cout << "Tip:" << std::endl; std::cout << "- Install libStructure, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; -#endif - return EXIT_SUCCESS; } #endif diff --git a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp index 428c72375a..d585e7d3bc 100644 --- a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp +++ b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp @@ -43,7 +43,7 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_PCL)) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (defined(VISP_HAVE_PCL)) #ifdef VISP_HAVE_PCL #include @@ -111,7 +111,8 @@ int main() viewer->addPointCloud(pointcloud, rgb, "sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); update = true; - } else { + } + else { viewer->updatePointCloud(pointcloud, rgb, "sample cloud"); } @@ -119,9 +120,11 @@ int main() std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Structure SDK error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -135,10 +138,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install libStructure, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #elif !defined(VISP_HAVE_PCL) std::cout << "You do not have PCL 3rd party installed." << std::endl; #endif diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp index 69fbbf0271..85b2c97c06 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp @@ -41,8 +41,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include @@ -135,7 +134,7 @@ int main(int argc, char *argv[]) d4.close(infrared2); std::cout << "Acquisition1 - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; width = 640; height = 480; @@ -185,7 +184,7 @@ int main(int argc, char *argv[]) } std::cout << "Acquisition2 - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; return EXIT_SUCCESS; } @@ -196,11 +195,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense2 to make this test work." << std::endl; #endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) " - "to make this test work" - << std::endl; -#endif #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) std::cout << "X11 or GDI are needed." << std::endl; #endif diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp index 6191d5967b..be5ea0b7ab 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp @@ -40,8 +40,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_PCL) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_PCL) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include @@ -99,11 +98,14 @@ int main(int argc, char *argv[]) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--align_to_depth") { align_to_depth = true; - } else if (std::string(argv[i]) == "--color") { + } + else if (std::string(argv[i]) == "--color") { color_pointcloud = true; - } else if (std::string(argv[i]) == "--col_vector") { + } + else if (std::string(argv[i]) == "--col_vector") { col_vector = true; - } else if (std::string(argv[i]) == "--no_align") { + } + else if (std::string(argv[i]) == "--no_align") { no_align = true; } } @@ -142,14 +144,15 @@ int main(int argc, char *argv[]) rs2::align align_to(align_to_depth ? RS2_STREAM_DEPTH : RS2_STREAM_COLOR); vpCameraParameters cam_projection = - align_to_depth ? rs.getCameraParameters(RS2_STREAM_DEPTH) : rs.getCameraParameters(RS2_STREAM_COLOR); + align_to_depth ? rs.getCameraParameters(RS2_STREAM_DEPTH) : rs.getCameraParameters(RS2_STREAM_COLOR); while (true) { if (color_pointcloud) { rs.acquire(reinterpret_cast(I_color.bitmap), reinterpret_cast(I_depth_raw.bitmap), &vp_pointcloud, pointcloud_color, NULL, no_align ? NULL : &align_to); - } else { + } + else { rs.acquire(reinterpret_cast(I_color.bitmap), reinterpret_cast(I_depth_raw.bitmap), &vp_pointcloud, pointcloud, NULL, no_align ? NULL : &align_to); @@ -170,14 +173,15 @@ int main(int argc, char *argv[]) vpImagePoint imPt; vpMeterPixelConversion::convertPoint(cam_projection, x, y, imPt); unsigned int u = - std::min(static_cast(width - 1), static_cast(std::max(0.0, imPt.get_u()))); + std::min(static_cast(width - 1), static_cast(std::max(0.0, imPt.get_u()))); unsigned int v = - std::min(static_cast(height - 1), static_cast(std::max(0.0, imPt.get_v()))); + std::min(static_cast(height - 1), static_cast(std::max(0.0, imPt.get_v()))); I_pcl[v][u] = vpRGBa(pcl_pt.r, pcl_pt.g, pcl_pt.b); } } } - } else { + } + else { createDepthHist(histogram, pointcloud, depth_scale); for (uint32_t i = 0; i < pointcloud->height; i++) { @@ -191,9 +195,9 @@ int main(int argc, char *argv[]) vpImagePoint imPt; vpMeterPixelConversion::convertPoint(cam_projection, x, y, imPt); unsigned int u = - std::min(static_cast(width - 1), static_cast(std::max(0.0, imPt.get_u()))); + std::min(static_cast(width - 1), static_cast(std::max(0.0, imPt.get_u()))); unsigned int v = - std::min(static_cast(height - 1), static_cast(std::max(0.0, imPt.get_v()))); + std::min(static_cast(height - 1), static_cast(std::max(0.0, imPt.get_v()))); unsigned char depth_viz = getDepthColor(histogram, pcl_pt.z, depth_scale); I_pcl[v][u] = vpRGBa(depth_viz, depth_viz, depth_viz); } @@ -213,9 +217,9 @@ int main(int argc, char *argv[]) vpImagePoint imPt; vpMeterPixelConversion::convertPoint(cam_projection, x, y, imPt); unsigned int u = - std::min(static_cast(width - 1), static_cast(std::max(0.0, imPt.get_u()))); + std::min(static_cast(width - 1), static_cast(std::max(0.0, imPt.get_u()))); unsigned int v = - std::min(static_cast(height - 1), static_cast(std::max(0.0, imPt.get_v()))); + std::min(static_cast(height - 1), static_cast(std::max(0.0, imPt.get_v()))); unsigned char depth_viz = getDepthColor(histogram2, Z, depth_scale); I_pcl2[v][u] = vpRGBa(depth_viz, depth_viz, depth_viz); } diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp index b01c7bd1e1..f2cc0fe227 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (VISP_HAVE_OPENCV_VERSION >= 0x030000) #include @@ -54,10 +54,11 @@ namespace { -struct float3 { +struct float3 +{ float x, y, z; - float3() : x(0), y(0), z(0) {} - float3(float x_, float y_, float z_) : x(x_), y(y_), z(z_) {} + float3() : x(0), y(0), z(0) { } + float3(float x_, float y_, float z_) : x(x_), y(y_), z(z_) { } }; void getPointcloud(const rs2::depth_frame &depth_frame, std::vector &pointcloud) @@ -141,10 +142,12 @@ void frame_to_mat(const rs2::frame &f, cv::Mat &img) if (f.get_profile().format() == RS2_FORMAT_BGR8) { memcpy(static_cast(img.ptr()), f.get_data(), size * 3); - } else if (f.get_profile().format() == RS2_FORMAT_RGB8) { + } + else if (f.get_profile().format() == RS2_FORMAT_RGB8) { cv::Mat tmp(h, w, CV_8UC3, const_cast(f.get_data()), cv::Mat::AUTO_STEP); cv::cvtColor(tmp, img, cv::COLOR_RGB2BGR); - } else if (f.get_profile().format() == RS2_FORMAT_Y8) { + } + else if (f.get_profile().format() == RS2_FORMAT_Y8) { memcpy(img.ptr(), f.get_data(), size); } } @@ -238,7 +241,7 @@ int main() } std::cout << "Acquisition - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; return EXIT_SUCCESS; } @@ -248,11 +251,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense2 to make this test work." << std::endl; #endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) " - "to make this test work" - << std::endl; -#endif #if !(VISP_HAVE_OPENCV_VERSION >= 0x030000) std::cout << "Install OpenCV version >= 3 to make this test work." << std::endl; #endif diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp index da220b1881..50b6005887 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp @@ -41,8 +41,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PCL) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PCL) #include #include @@ -66,7 +65,7 @@ bool cancelled = false, update_pointcloud = false; class ViewerWorker { public: - explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {} + explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { } void run() { @@ -96,7 +95,8 @@ class ViewerWorker if (local_update) { if (m_colorMode) { local_pointcloud_color = pointcloud_color->makeShared(); - } else { + } + else { local_pointcloud = pointcloud->makeShared(); } } @@ -111,15 +111,18 @@ class ViewerWorker viewer->addPointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "RGB sample cloud"); - } else { + } + else { viewer->addPointCloud(local_pointcloud, "sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); } init = false; - } else { + } + else { if (m_colorMode) { viewer->updatePointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - } else { + } + else { viewer->updatePointCloud(local_pointcloud, "sample cloud"); } } @@ -144,7 +147,8 @@ int main(int argc, char *argv[]) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--pcl_color") { pcl_color = true; - } else if (std::string(argv[i]) == "--show_infrared2") { + } + else if (std::string(argv[i]) == "--show_infrared2") { show_infrared2 = true; } } @@ -191,7 +195,8 @@ int main(int argc, char *argv[]) rs.acquire(reinterpret_cast(color.bitmap), reinterpret_cast(depth_raw.bitmap), NULL, pointcloud_color, reinterpret_cast(infrared1.bitmap), show_infrared2 ? reinterpret_cast(infrared2.bitmap) : NULL, NULL); - } else { + } + else { rs.acquire(reinterpret_cast(color.bitmap), reinterpret_cast(depth_raw.bitmap), NULL, pointcloud, reinterpret_cast(infrared1.bitmap), show_infrared2 ? reinterpret_cast(infrared2.bitmap) : NULL, NULL); @@ -232,7 +237,7 @@ int main(int argc, char *argv[]) viewer_thread.join(); std::cout << "Acquisition - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; return EXIT_SUCCESS; } @@ -243,11 +248,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense2 to make this test work." << std::endl; #endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) " - "to make this test work" - << std::endl; -#endif #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) std::cout << "X11 or GDI are needed." << std::endl; #endif diff --git a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp index 1b70b9dcd3..12cb8b1725 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp @@ -42,8 +42,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #ifdef VISP_HAVE_PCL #include @@ -74,7 +73,7 @@ bool cancelled = false, update_pointcloud = false; class ViewerWorker { public: - explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {} + explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { } void run() { @@ -104,7 +103,8 @@ class ViewerWorker if (local_update) { if (m_colorMode) { local_pointcloud_color = pointcloud_color->makeShared(); - } else { + } + else { local_pointcloud = pointcloud->makeShared(); } } @@ -119,15 +119,18 @@ class ViewerWorker viewer->addPointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "RGB sample cloud"); - } else { + } + else { viewer->addPointCloud(local_pointcloud, "sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); } init = false; - } else { + } + else { if (m_colorMode) { viewer->updatePointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - } else { + } + else { viewer->updatePointCloud(local_pointcloud, "sample cloud"); } } @@ -161,7 +164,8 @@ void getPointcloud(const rs2::depth_frame &depth_frame, std::vector v[1] = vertices[i].y; v[2] = vertices[i].z; v[3] = 1.0; - } else { + } + else { v[0] = 0.0; v[1] = 0.0; v[2] = 0.0; @@ -213,10 +217,12 @@ void frame_to_mat(const rs2::frame &f, cv::Mat &img) if (f.get_profile().format() == RS2_FORMAT_BGR8) { memcpy(static_cast(img.ptr()), f.get_data(), size * 3); - } else if (f.get_profile().format() == RS2_FORMAT_RGB8) { + } + else if (f.get_profile().format() == RS2_FORMAT_RGB8) { cv::Mat tmp(h, w, CV_8UC3, (void *)f.get_data(), cv::Mat::AUTO_STEP); cv::cvtColor(tmp, img, cv::COLOR_RGB2BGR); - } else if (f.get_profile().format() == RS2_FORMAT_Y8) { + } + else if (f.get_profile().format() == RS2_FORMAT_Y8) { memcpy(img.ptr(), f.get_data(), size); } } @@ -242,10 +248,10 @@ int main(int argc, char *argv[]) else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--show_info]" #ifdef VISP_HAVE_PCL - << " [--pcl_color]" + << " [--pcl_color]" #endif - << " [--help] [-h]" - << "\n"; + << " [--help] [-h]" + << "\n"; return EXIT_SUCCESS; } } @@ -295,23 +301,23 @@ int main(int argc, char *argv[]) rs2::pipeline &pipe = rs.getPipeline(); std::cout << "Color intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithoutDistortion) - << std::endl; + << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithoutDistortion) + << std::endl; std::cout << "Color intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl; + << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl; std::cout << "Depth intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithoutDistortion) - << std::endl; + << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithoutDistortion) + << std::endl; std::cout << "Depth intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl; + << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl; std::cout << "Infrared intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_INFRARED, vpCameraParameters::perspectiveProjWithoutDistortion) - << std::endl; + << rs.getCameraParameters(RS2_STREAM_INFRARED, vpCameraParameters::perspectiveProjWithoutDistortion) + << std::endl; std::cout << "Infrared intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_INFRARED, vpCameraParameters::perspectiveProjWithDistortion) - << std::endl; + << rs.getCameraParameters(RS2_STREAM_INFRARED, vpCameraParameters::perspectiveProjWithDistortion) + << std::endl; std::cout << "depth_M_color:\n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl; std::cout << "color_M_infrared:\n" << rs.getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl; @@ -382,7 +388,7 @@ int main(int argc, char *argv[]) viewer_colvector_thread.join(); #endif std::cout << "Acquisition1 - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; config.disable_all_streams(); config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 60); @@ -412,23 +418,23 @@ int main(int argc, char *argv[]) std::cout << "\n" << std::endl; std::cout << "Color intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithoutDistortion) - << std::endl; + << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithoutDistortion) + << std::endl; std::cout << "Color intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl; + << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl; std::cout << "Depth intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithoutDistortion) - << std::endl; + << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithoutDistortion) + << std::endl; std::cout << "Depth intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl; + << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl; std::cout << "Infrared intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_INFRARED, vpCameraParameters::perspectiveProjWithoutDistortion) - << std::endl; + << rs.getCameraParameters(RS2_STREAM_INFRARED, vpCameraParameters::perspectiveProjWithoutDistortion) + << std::endl; std::cout << "Infrared intrinsics:\n" - << rs.getCameraParameters(RS2_STREAM_INFRARED, vpCameraParameters::perspectiveProjWithDistortion) - << std::endl; + << rs.getCameraParameters(RS2_STREAM_INFRARED, vpCameraParameters::perspectiveProjWithDistortion) + << std::endl; std::cout << "depth_M_color:\n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl; std::cout << "color_M_infrared:\n" << rs.getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl; @@ -445,7 +451,8 @@ int main(int argc, char *argv[]) if (pcl_color) { rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud_color, (unsigned char *)infrared.bitmap); - } else { + } + else { rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud, (unsigned char *)infrared.bitmap); } @@ -487,7 +494,7 @@ int main(int argc, char *argv[]) d2.close(depth_color); d3.close(infrared); std::cout << "Acquisition2 - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; #if VISP_HAVE_OPENCV_VERSION >= 0x030000 rs.close(); @@ -531,7 +538,7 @@ int main(int argc, char *argv[]) } std::cout << "Acquisition3 - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; #endif #ifdef VISP_HAVE_PCL @@ -580,7 +587,7 @@ int main(int argc, char *argv[]) viewer_colvector_thread2.join(); std::cout << "Acquisition4 - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; #endif return EXIT_SUCCESS; @@ -592,11 +599,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE2) std::cout << "Install librealsense2 to make this test work." << std::endl; #endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) " - "to make this test work" - << std::endl; -#endif #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) std::cout << "X11 or GDI are needed." << std::endl; #endif diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp index dff61c40f4..895035d488 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp @@ -46,7 +46,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() @@ -111,9 +111,11 @@ int main() std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -127,10 +129,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #elif !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) std::cout << "You don't have X11 or GDI display capabilities" << std::endl; #elif !(RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp index 2bbdd914af..666d03f38c 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp @@ -47,7 +47,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) #include @@ -61,7 +61,7 @@ int main() double ts; vpImagePoint frame_origin; std::list > - frame_origins; // Frame origin's history for trajectory visualization + frame_origins; // Frame origin's history for trajectory visualization unsigned int display_scale = 2; try { @@ -156,9 +156,11 @@ int main() std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -172,10 +174,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #elif !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) std::cout << "You don't have X11 or GDI display capabilities" << std::endl; #elif !(RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry_async.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry_async.cpp index 7a6f8cfb0a..dea908efda 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry_async.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry_async.cpp @@ -47,7 +47,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) #include @@ -61,7 +61,7 @@ int main() unsigned int confidence; vpImagePoint frame_origin; std::list > - frame_origins; // Frame origin's history for trajectory visualization. + frame_origins; // Frame origin's history for trajectory visualization. unsigned int display_scale = 2; try { @@ -118,8 +118,9 @@ int main() odo_acc[5] = static_cast(pose_data.angular_acceleration.z); confidence = pose_data.tracker_confidence; - } else { - // Stream that bypass synchronization (such as IMU, Pose, ...) will produce single frames. + } + else { + // Stream that bypass synchronization (such as IMU, Pose, ...) will produce single frames. rs2_pose pose_data = frame.as().get_pose_data(); vpTranslationVector ctw(static_cast(pose_data.translation.x), static_cast(pose_data.translation.y), @@ -152,9 +153,9 @@ int main() vpHomogeneousMatrix cextMc = cextMw * cMw.inverse(); vpMeterPixelConversion::convertPoint(cam, cextMc[0][3] / cextMc[2][3], cextMc[1][3] / cextMc[2][3], frame_origin); frame_origins.push_back(std::make_pair(confidence, frame_origin)); - }; + }; - // Open vpRealSense2 object according to configuration and with the callback to be called. + // Open vpRealSense2 object according to configuration and with the callback to be called. g.open(config, callback); I_left.resize(g.getIntrinsics(RS2_STREAM_FISHEYE, 1).height, g.getIntrinsics(RS2_STREAM_FISHEYE, 1).width); @@ -225,9 +226,11 @@ int main() vpDisplay::flush(I_right); vpDisplay::flush(I_pose); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -241,10 +244,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #elif !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) std::cout << "You don't have X11 or GDI display capabilities" << std::endl; #elif !(RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp index a0345aa320..c55622c7da 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp @@ -46,7 +46,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() @@ -72,14 +72,16 @@ int main() rs.getIMUData(&imu_acc, &imu_vel, NULL); std::cout << "Gyro vel: x = " << std::setw(12) << imu_vel[0] << " y = " << std::setw(12) << imu_vel[1] - << " z = " << std::setw(12) << imu_vel[2]; + << " z = " << std::setw(12) << imu_vel[2]; std::cout << " Accel: x = " << std::setw(12) << imu_acc[0] << " y = " << std::setw(12) << imu_acc[1] - << " z = " << std::setw(12) << imu_acc[2]; + << " z = " << std::setw(12) << imu_acc[2]; std::cout << std::endl; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -93,10 +95,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #elif !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) std::cout << "You don't have X11 or GDI display capabilities" << std::endl; #elif !(RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp index c29afcce28..cf38353a98 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp @@ -46,7 +46,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() @@ -58,7 +58,7 @@ int main() vpImagePoint origin; vpImagePoint frame_origin; std::list > - frame_origins; // Frame origin's history for trajectory visualization + frame_origins; // Frame origin's history for trajectory visualization try { vpRealSense2 rs; @@ -132,9 +132,11 @@ int main() std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -148,10 +150,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #elif !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) std::cout << "You don't have X11 or GDI display capabilities" << std::endl; #elif !(RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp index 728f1f68e8..516a700a2f 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp @@ -48,7 +48,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ +#if defined(VISP_HAVE_REALSENSE2) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() @@ -72,7 +72,7 @@ int main() config.enable_stream(RS2_STREAM_FISHEYE, 2, RS2_FORMAT_Y8); rs.open(config); cam_left = - rs.getCameraParameters(RS2_STREAM_FISHEYE, vpCameraParameters::ProjWithKannalaBrandtDistortion, cam_index); + rs.getCameraParameters(RS2_STREAM_FISHEYE, vpCameraParameters::ProjWithKannalaBrandtDistortion, cam_index); vpImage I((unsigned int)rs.getIntrinsics(RS2_STREAM_FISHEYE).height, (unsigned int)rs.getIntrinsics(RS2_STREAM_FISHEYE).width); @@ -124,9 +124,11 @@ int main() std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -140,10 +142,6 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -#elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl; - std::cout << "Tip:" << std::endl; - std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl; #elif !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) std::cout << "You don't have X11 or GDI display capabilities" << std::endl; #elif !(RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) diff --git a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp b/modules/sensor/test/rgb-depth/testRealSense_R200.cpp index dba605f4f3..571de313f4 100644 --- a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense_R200.cpp @@ -46,8 +46,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include @@ -68,7 +67,7 @@ bool cancelled = false, update_pointcloud = false; class ViewerWorker { public: - explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {} + explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { } void run() { @@ -98,7 +97,8 @@ class ViewerWorker if (local_update) { if (m_colorMode) { local_pointcloud_color = pointcloud_color->makeShared(); - } else { + } + else { local_pointcloud = pointcloud->makeShared(); } } @@ -113,15 +113,18 @@ class ViewerWorker viewer->addPointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "RGB sample cloud"); - } else { + } + else { viewer->addPointCloud(local_pointcloud, "sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); } init = false; - } else { + } + else { if (m_colorMode) { viewer->updatePointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - } else { + } + else { viewer->updatePointCloud(local_pointcloud, "sample cloud"); } } @@ -234,7 +237,8 @@ void test_R200(vpRealSense &rs, const std::map &enables, case rs::stream::depth: if (depth_color_visualization) { dd.init(I_depth_color, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } else { + } + else { dd.init(I_depth, (int)I_color.getWidth() + 80, 0, "Depth frame"); } break; @@ -289,17 +293,20 @@ void test_R200(vpRealSense &rs, const std::map &enables, rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color, (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); - } else { + } + else { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud, (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); } - } else { + } + else { if (pcl_color) { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color, (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); - } else { + } + else { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud, (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); @@ -311,12 +318,14 @@ void test_R200(vpRealSense &rs, const std::map &enables, update_pointcloud = true; #endif - } else { + } + else { if (direct_infrared_conversion) { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); - } else { + } + else { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, rs::stream::infrared, infrared2_stream); @@ -327,14 +336,16 @@ void test_R200(vpRealSense &rs, const std::map &enables, if (depth_color_visualization) { vpImageConvert::createDepthHistogram(depth, I_depth_color); - } else { + } + else { vpImageConvert::createDepthHistogram(depth, I_depth); } vpDisplay::display(I_color); if (depth_color_visualization) { vpDisplay::display(I_depth_color); - } else { + } + else { vpDisplay::display(I_depth); } vpDisplay::display(I_infrared); @@ -343,7 +354,8 @@ void test_R200(vpRealSense &rs, const std::map &enables, vpDisplay::flush(I_color); if (depth_color_visualization) { vpDisplay::flush(I_depth_color); - } else { + } + else { vpDisplay::flush(I_depth); } vpDisplay::flush(I_infrared); @@ -373,7 +385,7 @@ void test_R200(vpRealSense &rs, const std::map &enables, } std::cout << title << " - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; rs.close(); } @@ -394,7 +406,7 @@ int main(int argc, char *argv[]) std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl; std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *)rs.getHandler(), nullptr) - << std::endl; + << std::endl; std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; rs.close(); @@ -549,12 +561,15 @@ int main(int argc, char *argv[]) false, rs::stream::color, rs::stream::depth, rs::stream::infrared2, true, (argc > 1 ? (bool)(atoi(argv[1]) > 0) : false)); #endif - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const rs::error &e) { + } + catch (const rs::error &e) { std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() - << "): " << e.what() << std::endl; - } catch (const std::exception &e) { + << "): " << e.what() << std::endl; + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -566,10 +581,6 @@ int main() { #if !defined(VISP_HAVE_REALSENSE) std::cout << "This deprecated example is only working with librealsense 1.x " << std::endl; -#elif !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) " - "to make this test working" - << std::endl; #elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) std::cout << "X11 or GDI are needed!" << std::endl; #endif diff --git a/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp index 40e095bcd2..3a91cc5ed9 100644 --- a/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp @@ -46,8 +46,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include @@ -68,7 +67,7 @@ bool cancelled = false, update_pointcloud = false; class ViewerWorker { public: - explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {} + explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { } void run() { @@ -98,7 +97,8 @@ class ViewerWorker if (local_update) { if (m_colorMode) { local_pointcloud_color = pointcloud_color->makeShared(); - } else { + } + else { local_pointcloud = pointcloud->makeShared(); } } @@ -113,15 +113,18 @@ class ViewerWorker viewer->addPointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "RGB sample cloud"); - } else { + } + else { viewer->addPointCloud(local_pointcloud, "sample cloud"); viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); } init = false; - } else { + } + else { if (m_colorMode) { viewer->updatePointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - } else { + } + else { viewer->updatePointCloud(local_pointcloud, "sample cloud"); } } @@ -220,7 +223,8 @@ void test_SR300(vpRealSense &rs, const std::map &enables, case rs::stream::depth: if (depth_color_visualization) { dd.init(I_depth_color, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } else { + } + else { dd.init(I_depth, (int)I_color.getWidth() + 80, 0, "Depth frame"); } break; @@ -265,15 +269,18 @@ void test_SR300(vpRealSense &rs, const std::map &enables, if (pcl_color) { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color, (unsigned char *)I_infrared.bitmap, NULL, color_stream, depth_stream); - } else { + } + else { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud, (unsigned char *)I_infrared.bitmap, NULL, color_stream, depth_stream); } - } else { + } + else { if (pcl_color) { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color, (unsigned char *)infrared.bitmap, NULL, color_stream, depth_stream); - } else { + } + else { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud, (unsigned char *)infrared.bitmap, NULL, color_stream, depth_stream); } @@ -283,11 +290,13 @@ void test_SR300(vpRealSense &rs, const std::map &enables, update_pointcloud = true; #endif - } else { + } + else { if (direct_infrared_conversion) { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, (unsigned char *)I_infrared.bitmap, NULL, color_stream, depth_stream); - } else { + } + else { rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, (unsigned char *)infrared.bitmap, NULL, color_stream, depth_stream); vpImageConvert::convert(infrared, I_infrared); @@ -296,14 +305,16 @@ void test_SR300(vpRealSense &rs, const std::map &enables, if (depth_color_visualization) { vpImageConvert::createDepthHistogram(depth, I_depth_color); - } else { + } + else { vpImageConvert::createDepthHistogram(depth, I_depth); } vpDisplay::display(I_color); if (depth_color_visualization) { vpDisplay::display(I_depth_color); - } else { + } + else { vpDisplay::display(I_depth); } vpDisplay::display(I_infrared); @@ -311,7 +322,8 @@ void test_SR300(vpRealSense &rs, const std::map &enables, vpDisplay::flush(I_color); if (depth_color_visualization) { vpDisplay::flush(I_depth_color); - } else { + } + else { vpDisplay::flush(I_depth); } vpDisplay::flush(I_infrared); @@ -340,7 +352,7 @@ void test_SR300(vpRealSense &rs, const std::map &enables, } std::cout << title << " - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; + << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; rs.close(); } @@ -361,7 +373,7 @@ int main(int argc, char *argv[]) std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl; std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *)rs.getHandler(), nullptr) - << std::endl; + << std::endl; std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; rs.close(); @@ -481,12 +493,15 @@ int main(int argc, char *argv[]) break; } } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "RealSense error " << e.what() << std::endl; - } catch (const rs::error &e) { + } + catch (const rs::error &e) { std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() - << "): " << e.what() << std::endl; - } catch (const std::exception &e) { + << "): " << e.what() << std::endl; + } + catch (const std::exception &e) { std::cerr << e.what() << std::endl; } @@ -499,11 +514,6 @@ int main() #if !defined(VISP_HAVE_REALSENSE) std::cout << "Install librealsense to make this test work." << std::endl; #endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) " - "to make this test work." - << std::endl; -#endif #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) std::cout << "X11 or GDI are needed." << std::endl; #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h index 564268e4aa..7b6b694538 100755 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h @@ -79,7 +79,7 @@ template class vpMbtTukeyEstimator #include #define USE_TRANSFORM 1 -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && USE_TRANSFORM +#if USE_TRANSFORM #define HAVE_TRANSFORM 1 #include #endif @@ -116,7 +116,8 @@ namespace #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_14) auto AbsDiff = [](const auto &a, const auto &b) { return std::fabs(a - b); }; #else -template struct AbsDiff : public std::binary_function { +template struct AbsDiff : public std::binary_function +{ T operator()(const T a, const T b) const { return std::fabs(a - b); } }; #endif @@ -351,7 +352,8 @@ template void vpMbtTukeyEstimator::psiTukey(const T sig, std::ve if (xi > 1.) { weights[i] = 0; - } else { + } + else { xi = 1 - xi; xi *= xi; weights[i] = xi; @@ -450,7 +452,8 @@ template void vpMbtTukeyEstimator::psiTukey(const T sig, std::vecto if (xi > 1.) { weights[i] = 0; - } else { + } + else { xi = 1 - xi; xi *= xi; weights[i] = xi; diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp index 9e1a4fb43c..07f25e06cd 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp @@ -47,7 +47,7 @@ // https://stackoverflow.com/a/40765925 #if !defined(__FMA__) && defined(__AVX2__) - #define __FMA__ 1 +#define __FMA__ 1 #endif #if defined _WIN32 && defined(_M_ARM64) @@ -81,18 +81,16 @@ #endif #if !USE_OPENCV_HAL && (USE_SSE || USE_NEON) -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include -#endif namespace { #if USE_SSE -inline void v_load_deinterleave(const uint64_t *ptr, __m128i& a, __m128i& b, __m128i& c) +inline void v_load_deinterleave(const uint64_t *ptr, __m128i &a, __m128i &b, __m128i &c) { - __m128i t0 = _mm_loadu_si128((const __m128i*)ptr); // a0, b0 - __m128i t1 = _mm_loadu_si128((const __m128i*)(ptr + 2)); // c0, a1 - __m128i t2 = _mm_loadu_si128((const __m128i*)(ptr + 4)); // b1, c1 + __m128i t0 = _mm_loadu_si128((const __m128i *)ptr); // a0, b0 + __m128i t1 = _mm_loadu_si128((const __m128i *)(ptr + 2)); // c0, a1 + __m128i t2 = _mm_loadu_si128((const __m128i *)(ptr + 4)); // b1, c1 t1 = _mm_shuffle_epi32(t1, 0x4e); // a1, c0 @@ -101,37 +99,37 @@ inline void v_load_deinterleave(const uint64_t *ptr, __m128i& a, __m128i& b, __m c = _mm_unpackhi_epi64(t1, t2); } -inline void v_load_deinterleave(const double* ptr, __m128d& a0, __m128d& b0, __m128d& c0) +inline void v_load_deinterleave(const double *ptr, __m128d &a0, __m128d &b0, __m128d &c0) { __m128i a1, b1, c1; - v_load_deinterleave((const uint64_t*)ptr, a1, b1, c1); + v_load_deinterleave((const uint64_t *)ptr, a1, b1, c1); a0 = _mm_castsi128_pd(a1); b0 = _mm_castsi128_pd(b1); c0 = _mm_castsi128_pd(c1); } -inline __m128d v_combine_low(const __m128d& a, const __m128d& b) +inline __m128d v_combine_low(const __m128d &a, const __m128d &b) { __m128i a1 = _mm_castpd_si128(a), b1 = _mm_castpd_si128(b); return _mm_castsi128_pd(_mm_unpacklo_epi64(a1, b1)); } -inline __m128d v_combine_high(const __m128d& a, const __m128d& b) +inline __m128d v_combine_high(const __m128d &a, const __m128d &b) { __m128i a1 = _mm_castpd_si128(a), b1 = _mm_castpd_si128(b); return _mm_castsi128_pd(_mm_unpackhi_epi64(a1, b1)); } -inline __m128d v_fma(const __m128d& a, const __m128d& b, const __m128d& c) +inline __m128d v_fma(const __m128d &a, const __m128d &b, const __m128d &c) { #if __FMA__ - return _mm_fmadd_pd(a, b, c); + return _mm_fmadd_pd(a, b, c); #else - return _mm_add_pd(_mm_mul_pd(a, b), c); + return _mm_add_pd(_mm_mul_pd(a, b), c); #endif } #else -inline void v_load_deinterleave(const double* ptr, float64x2_t& a0, float64x2_t& b0, float64x2_t& c0) +inline void v_load_deinterleave(const double *ptr, float64x2_t &a0, float64x2_t &b0, float64x2_t &c0) { float64x2x3_t v = vld3q_f64(ptr); a0 = v.val[0]; @@ -139,17 +137,17 @@ inline void v_load_deinterleave(const double* ptr, float64x2_t& a0, float64x2_t& c0 = v.val[2]; } -inline float64x2_t v_combine_low(const float64x2_t& a, const float64x2_t& b) +inline float64x2_t v_combine_low(const float64x2_t &a, const float64x2_t &b) { return vcombine_f64(vget_low_f64(a), vget_low_f64(b)); } -inline float64x2_t v_combine_high(const float64x2_t& a, const float64x2_t& b) +inline float64x2_t v_combine_high(const float64x2_t &a, const float64x2_t &b) { return vcombine_f64(vget_high_f64(a), vget_high_f64(b)); } -inline float64x2_t v_fma(const float64x2_t& a, const float64x2_t& b, const float64x2_t& c) +inline float64x2_t v_fma(const float64x2_t &a, const float64x2_t &b, const float64x2_t &c) { return vfmaq_f64(c, a, b); } @@ -159,12 +157,11 @@ inline float64x2_t v_fma(const float64x2_t& a, const float64x2_t& b, const float vpMbtFaceDepthDense::vpMbtFaceDepthDense() : m_cam(), m_clippingFlag(vpPolygon3D::NO_CLIPPING), m_distFarClip(100), m_distNearClip(0.001), m_hiddenFace(NULL), - m_planeObject(), m_polygon(NULL), m_useScanLine(false), - m_depthDenseFilteringMethod(DEPTH_OCCUPANCY_RATIO_FILTERING), m_depthDenseFilteringMaxDist(3.0), - m_depthDenseFilteringMinDist(0.8), m_depthDenseFilteringOccupancyRatio(0.3), m_isTrackedDepthDenseFace(true), - m_isVisible(false), m_listOfFaceLines(), m_planeCamera(), m_pointCloudFace(), m_polygonLines() -{ -} + m_planeObject(), m_polygon(NULL), m_useScanLine(false), + m_depthDenseFilteringMethod(DEPTH_OCCUPANCY_RATIO_FILTERING), m_depthDenseFilteringMaxDist(3.0), + m_depthDenseFilteringMinDist(0.8), m_depthDenseFilteringOccupancyRatio(0.3), m_isTrackedDepthDenseFace(true), + m_isVisible(false), m_listOfFaceLines(), m_planeCamera(), m_pointCloudFace(), m_polygonLines() +{ } vpMbtFaceDepthDense::~vpMbtFaceDepthDense() { @@ -312,7 +309,7 @@ bool vpMbtFaceDepthDense::computeDesiredFeatures(const vpHomogeneousMatrix &cMo, if ((m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() && j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs()[i][j] == m_polygon->getIndex()) - : polygon_2d.isInside(vpImagePoint(i, j)))) { + : polygon_2d.isInside(vpImagePoint(i, j)))) { totalTheoreticalPoints++; if (vpMeTracker::inMask(mask, i, j) && pcl::isFinite((*point_cloud)(j, i)) && (*point_cloud)(j, i).z > 0) { @@ -398,7 +395,7 @@ bool vpMbtFaceDepthDense::computeDesiredFeatures(const vpHomogeneousMatrix &cMo, if ((m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() && j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs()[i][j] == m_polygon->getIndex()) - : polygon_2d.isInside(vpImagePoint(i, j)))) { + : polygon_2d.isInside(vpImagePoint(i, j)))) { totalTheoreticalPoints++; if (vpMeTracker::inMask(mask, i, j) && point_cloud[i * width + j][2] > 0) { @@ -440,7 +437,8 @@ void vpMbtFaceDepthDense::computeVisibilityDisplay() int index = *itindex; if (index == -1) { isvisible = true; - } else { + } + else { if (line->hiddenface->isVisible((unsigned int)index)) { isvisible = true; } @@ -453,7 +451,8 @@ void vpMbtFaceDepthDense::computeVisibilityDisplay() if (isvisible) { line->setVisible(true); - } else { + } + else { line->setVisible(false); } } @@ -642,7 +641,8 @@ void vpMbtFaceDepthDense::computeInteractionMatrixAndResidu(const vpHomogeneousM error[(unsigned int)(cpt / 3)] = D + (normal.t() * pt); } #endif - } else { + } + else { vpColVector normal(3); normal[0] = nx; normal[1] = ny; @@ -739,19 +739,21 @@ void vpMbtFaceDepthDense::computeROI(const vpHomogeneousMatrix &cMo, unsigned in if (linesLst.empty()) { distanceToFace = std::numeric_limits::max(); - } else { + } + else { faceCentroid.set_X(faceCentroid.get_X() / (2 * linesLst.size())); faceCentroid.set_Y(faceCentroid.get_Y() / (2 * linesLst.size())); faceCentroid.set_Z(faceCentroid.get_Z() / (2 * linesLst.size())); distanceToFace = - sqrt(faceCentroid.get_X() * faceCentroid.get_X() + faceCentroid.get_Y() * faceCentroid.get_Y() + - faceCentroid.get_Z() * faceCentroid.get_Z()); + sqrt(faceCentroid.get_X() * faceCentroid.get_X() + faceCentroid.get_Y() * faceCentroid.get_Y() + + faceCentroid.get_Z() * faceCentroid.get_Z()); } } } - } else { - // Get polygon clipped + } + else { + // Get polygon clipped m_polygon->getRoiClipped(m_cam, roiPts, cMo); // Get 3D polygon clipped @@ -760,7 +762,8 @@ void vpMbtFaceDepthDense::computeROI(const vpHomogeneousMatrix &cMo, unsigned in if (polygonsClipped.empty()) { distanceToFace = std::numeric_limits::max(); - } else { + } + else { vpPoint faceCentroid; for (size_t i = 0; i < polygonsClipped.size(); i++) { @@ -788,7 +791,7 @@ void vpMbtFaceDepthDense::display(const vpImage &I, const vpHomog bool displayFullModel) { std::vector > models = - getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); + getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); for (size_t i = 0; i < models.size(); i++) { vpImagePoint ip1(models[i][1], models[i][2]); @@ -802,7 +805,7 @@ void vpMbtFaceDepthDense::display(const vpImage &I, const vpHomogeneousM bool displayFullModel) { std::vector > models = - getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); + getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); for (size_t i = 0; i < models.size(); i++) { vpImagePoint ip1(models[i][1], models[i][2]); @@ -814,14 +817,12 @@ void vpMbtFaceDepthDense::display(const vpImage &I, const vpHomogeneousM void vpMbtFaceDepthDense::displayFeature(const vpImage & /*I*/, const vpHomogeneousMatrix & /*cMo*/, const vpCameraParameters & /*cam*/, const double /*scale*/, const unsigned int /*thickness*/) -{ -} +{ } void vpMbtFaceDepthDense::displayFeature(const vpImage & /*I*/, const vpHomogeneousMatrix & /*cMo*/, const vpCameraParameters & /*cam*/, const double /*scale*/, const unsigned int /*thickness*/) -{ -} +{ } /*! Return a list of line parameters to display the primitive at a given pose and camera parameters. @@ -848,7 +849,7 @@ std::vector > vpMbtFaceDepthDense::getModelForDisplay(unsign ++it) { vpMbtDistanceLine *line = *it; std::vector > lineModels = - line->getModelForDisplay(width, height, cMo, cam, displayFullModel); + line->getModelForDisplay(width, height, cMo, cam, displayFullModel); models.insert(models.end(), lineModels.begin(), lineModels.end()); } } diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp index 7dda21c822..d2c7390ac7 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp @@ -57,14 +57,13 @@ vpMbtFaceDepthNormal::vpMbtFaceDepthNormal() : m_cam(), m_clippingFlag(vpPolygon3D::NO_CLIPPING), m_distFarClip(100), m_distNearClip(0.001), m_hiddenFace(NULL), - m_planeObject(), m_polygon(NULL), m_useScanLine(false), m_faceActivated(false), - m_faceCentroidMethod(GEOMETRIC_CENTROID), m_faceDesiredCentroid(), m_faceDesiredNormal(), - m_featureEstimationMethod(ROBUST_FEATURE_ESTIMATION), m_isTrackedDepthNormalFace(true), m_isVisible(false), - m_listOfFaceLines(), m_planeCamera(), - m_pclPlaneEstimationMethod(2), // SAC_MSAC, see pcl/sample_consensus/method_types.h - m_pclPlaneEstimationRansacMaxIter(200), m_pclPlaneEstimationRansacThreshold(0.001), m_polygonLines() -{ -} + m_planeObject(), m_polygon(NULL), m_useScanLine(false), m_faceActivated(false), + m_faceCentroidMethod(GEOMETRIC_CENTROID), m_faceDesiredCentroid(), m_faceDesiredNormal(), + m_featureEstimationMethod(ROBUST_FEATURE_ESTIMATION), m_isTrackedDepthNormalFace(true), m_isVisible(false), + m_listOfFaceLines(), m_planeCamera(), + m_pclPlaneEstimationMethod(2), // SAC_MSAC, see pcl/sample_consensus/method_types.h + m_pclPlaneEstimationRansacMaxIter(200), m_pclPlaneEstimationRansacThreshold(0.001), m_polygonLines() +{ } vpMbtFaceDepthNormal::~vpMbtFaceDepthNormal() { @@ -202,9 +201,11 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo if (m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { point_cloud_face_custom.reserve((size_t)(3 * bb.getWidth() * bb.getHeight())); point_cloud_face_vec.reserve((size_t)(3 * bb.getWidth() * bb.getHeight())); - } else if (m_featureEstimationMethod == ROBUST_SVD_PLANE_ESTIMATION) { + } + else if (m_featureEstimationMethod == ROBUST_SVD_PLANE_ESTIMATION) { point_cloud_face_vec.reserve((size_t)(3 * bb.getWidth() * bb.getHeight())); - } else if (m_featureEstimationMethod == PCL_PLANE_ESTIMATION) { + } + else if (m_featureEstimationMethod == PCL_PLANE_ESTIMATION) { point_cloud_face->reserve((size_t)(bb.getWidth() * bb.getHeight())); } @@ -223,12 +224,13 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo (m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() && j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs()[i][j] == m_polygon->getIndex()) - : polygon_2d.isInside(vpImagePoint(i, j)))) { + : polygon_2d.isInside(vpImagePoint(i, j)))) { if (m_featureEstimationMethod == PCL_PLANE_ESTIMATION) { point_cloud_face->push_back((*point_cloud)(j, i)); - } else if (m_featureEstimationMethod == ROBUST_SVD_PLANE_ESTIMATION || - m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { + } + else if (m_featureEstimationMethod == ROBUST_SVD_PLANE_ESTIMATION || + m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { point_cloud_face_vec.push_back((*point_cloud)(j, i).x); point_cloud_face_vec.push_back((*point_cloud)(j, i).y); point_cloud_face_vec.push_back((*point_cloud)(j, i).z); @@ -244,7 +246,8 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo prev_x = x; prev_y = y; prev_z = (*point_cloud)(j, i).z; - } else { + } + else { push = false; point_cloud_face_custom.push_back(prev_x); point_cloud_face_custom.push_back(x); @@ -256,7 +259,8 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo point_cloud_face_custom.push_back((*point_cloud)(j, i).z); } #endif - } else { + } + else { point_cloud_face_custom.push_back(x); point_cloud_face_custom.push_back(y); point_cloud_face_custom.push_back((*point_cloud)(j, i).z); @@ -290,12 +294,15 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo if (!computeDesiredFeaturesPCL(point_cloud_face, desired_features, desired_normal, centroid_point)) { return false; } - } else if (m_featureEstimationMethod == ROBUST_SVD_PLANE_ESTIMATION) { + } + else if (m_featureEstimationMethod == ROBUST_SVD_PLANE_ESTIMATION) { computeDesiredFeaturesSVD(point_cloud_face_vec, cMo, desired_features, desired_normal, centroid_point); - } else if (m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { + } + else if (m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { computeDesiredFeaturesRobustFeatures(point_cloud_face_custom, point_cloud_face_vec, cMo, desired_features, desired_normal, centroid_point); - } else { + } + else { throw vpException(vpException::badValue, "Unknown feature estimation method!"); } @@ -376,8 +383,8 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo (m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() && j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs()[i][j] == m_polygon->getIndex()) - : polygon_2d.isInside(vpImagePoint(i, j)))) { - // Add point + : polygon_2d.isInside(vpImagePoint(i, j)))) { +// Add point point_cloud_face.push_back(point_cloud[i * width + j][0]); point_cloud_face.push_back(point_cloud[i * width + j][1]); point_cloud_face.push_back(point_cloud[i * width + j][2]); @@ -393,7 +400,8 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo prev_x = x; prev_y = y; prev_z = point_cloud[i * width + j][2]; - } else { + } + else { push = false; point_cloud_face_custom.push_back(prev_x); point_cloud_face_custom.push_back(x); @@ -405,7 +413,8 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo point_cloud_face_custom.push_back(point_cloud[i * width + j][2]); } #endif - } else { + } + else { point_cloud_face_custom.push_back(x); point_cloud_face_custom.push_back(y); point_cloud_face_custom.push_back(point_cloud[i * width + j][2]); @@ -445,16 +454,19 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo } computeDesiredFeaturesPCL(point_cloud_face_pcl, desired_features, desired_normal, centroid_point); - } else -#endif - if (m_featureEstimationMethod == ROBUST_SVD_PLANE_ESTIMATION) { - computeDesiredFeaturesSVD(point_cloud_face, cMo, desired_features, desired_normal, centroid_point); - } else if (m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { - computeDesiredFeaturesRobustFeatures(point_cloud_face_custom, point_cloud_face, cMo, desired_features, - desired_normal, centroid_point); - } else { - throw vpException(vpException::badValue, "Unknown feature estimation method!"); } + else +#endif + if (m_featureEstimationMethod == ROBUST_SVD_PLANE_ESTIMATION) { + computeDesiredFeaturesSVD(point_cloud_face, cMo, desired_features, desired_normal, centroid_point); + } + else if (m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { + computeDesiredFeaturesRobustFeatures(point_cloud_face_custom, point_cloud_face, cMo, desired_features, + desired_normal, centroid_point); + } + else { + throw vpException(vpException::badValue, "Unknown feature estimation method!"); + } computeDesiredNormalAndCentroid(cMo, desired_normal, centroid_point); @@ -514,7 +526,8 @@ bool vpMbtFaceDepthNormal::computeDesiredFeaturesPCL(const pcl::PointCloud &po for (size_t i = 0; i < points.size() - 1; i++) { // projection onto xy plane c_x1 += (points[i].get_X() + points[i + 1].get_X()) * - (points[i].get_X() * points[i + 1].get_Y() - points[i + 1].get_X() * points[i].get_Y()); + (points[i].get_X() * points[i + 1].get_Y() - points[i + 1].get_X() * points[i].get_Y()); c_y += (points[i].get_Y() + points[i + 1].get_Y()) * - (points[i].get_X() * points[i + 1].get_Y() - points[i + 1].get_X() * points[i].get_Y()); + (points[i].get_X() * points[i + 1].get_Y() - points[i + 1].get_X() * points[i].get_Y()); A1 += points[i].get_X() * points[i + 1].get_Y() - points[i + 1].get_X() * points[i].get_Y(); // projection onto xz plane c_x2 += (points[i].get_X() + points[i + 1].get_X()) * - (points[i].get_X() * points[i + 1].get_Z() - points[i + 1].get_X() * points[i].get_Z()); + (points[i].get_X() * points[i + 1].get_Z() - points[i + 1].get_X() * points[i].get_Z()); c_z += (points[i].get_Z() + points[i + 1].get_Z()) * - (points[i].get_X() * points[i + 1].get_Z() - points[i + 1].get_X() * points[i].get_Z()); + (points[i].get_X() * points[i + 1].get_Z() - points[i + 1].get_X() * points[i].get_Z()); A2 += points[i].get_X() * points[i + 1].get_Z() - points[i + 1].get_X() * points[i].get_Z(); } @@ -639,7 +653,8 @@ bool vpMbtFaceDepthNormal::computePolygonCentroid(const std::vector &po if (A1 > A2) { centroid.set_X(c_x1); - } else { + } + else { centroid.set_X(c_x2); } @@ -704,8 +719,9 @@ void vpMbtFaceDepthNormal::computeROI(const vpHomogeneousMatrix &cMo, unsigned i } } } - } else { - // Get polygon clipped + } + else { + // Get polygon clipped m_polygon->getRoiClipped(m_cam, roiPts, cMo); #if DEBUG_DISPLAY_DEPTH_NORMAL @@ -730,7 +746,8 @@ void vpMbtFaceDepthNormal::computeVisibilityDisplay() int index = *itindex; if (index == -1) { isvisible = true; - } else { + } + else { if (line->hiddenface->isVisible((unsigned int)index)) { isvisible = true; } @@ -743,7 +760,8 @@ void vpMbtFaceDepthNormal::computeVisibilityDisplay() if (isvisible) { line->setVisible(true); - } else { + } + else { line->setVisible(false); } } @@ -775,7 +793,8 @@ void vpMbtFaceDepthNormal::computeNormalVisibility(double nx, double ny, double e4[1] = -centroid.get_Y(); e4[2] = -centroid.get_Z(); e4.normalize(); - } else { + } + else { double centroid_x = 0.0; double centroid_y = 0.0; double centroid_z = 0.0; @@ -804,7 +823,8 @@ void vpMbtFaceDepthNormal::computeNormalVisibility(double nx, double ny, double double angle = acos(vpColVector::dotProd(e4, faceNormal)); if (angle < M_PI_2) { correct_normal = faceNormal; - } else { + } + else { correct_normal[0] = -faceNormal[0]; correct_normal[1] = -faceNormal[1]; correct_normal[2] = -faceNormal[2]; @@ -830,7 +850,8 @@ void vpMbtFaceDepthNormal::computeNormalVisibility(float nx, float ny, float nz, double angle = acos(vpColVector::dotProd(e4, faceNormal)); if (angle < M_PI_2) { face_normal = pcl::PointXYZ(faceNormal[0], faceNormal[1], faceNormal[2]); - } else { + } + else { face_normal = pcl::PointXYZ(-faceNormal[0], -faceNormal[1], -faceNormal[2]); } } @@ -906,7 +927,7 @@ void vpMbtFaceDepthNormal::display(const vpImage &I, const vpHomo bool displayFullModel) { std::vector > models = - getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); + getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); for (size_t i = 0; i < models.size(); i++) { vpImagePoint ip1(models[i][1], models[i][2]); @@ -920,7 +941,7 @@ void vpMbtFaceDepthNormal::display(const vpImage &I, const vpHomogeneous bool displayFullModel) { std::vector > models = - getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); + getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); for (size_t i = 0; i < models.size(); i++) { vpImagePoint ip1(models[i][1], models[i][2]); @@ -1093,7 +1114,7 @@ void vpMbtFaceDepthNormal::estimateFeatures(const std::vector &point_clo const __m128d vinvZi = _mm_div_pd(vones, vZi); const __m128d tmp = - _mm_add_pd(_mm_add_pd(_mm_mul_pd(vA, vxi), _mm_mul_pd(vB, vyi)), _mm_sub_pd(vC, vinvZi)); + _mm_add_pd(_mm_add_pd(_mm_mul_pd(vA, vxi), _mm_mul_pd(vB, vyi)), _mm_sub_pd(vC, vinvZi)); _mm_storeu_pd(ptr_residues, tmp); } } @@ -1260,7 +1281,8 @@ void vpMbtFaceDepthNormal::estimateFeatures(const std::vector &point_clo iter++; } // while ( std::fabs(error - prev_error) > 1e-6 && (iter < max_iter) ) #endif - } else { + } + else { while (std::fabs(error - prev_error) > 1e-6 && (iter < max_iter)) { if (iter == 0) { // Transform the plane equation for the current pose @@ -1372,8 +1394,9 @@ void vpMbtFaceDepthNormal::estimatePlaneEquationSVD(const std::vector &p for (unsigned int iter = 0; iter < max_iter && std::fabs(error - prev_error) > 1e-6; iter++) { if (iter != 0) { tukey.MEstimator(residues, weights, 1e-4); - } else { - // Transform the plane equation for the current pose + } + else { + // Transform the plane equation for the current pose m_planeCamera = m_planeObject; m_planeCamera.changeFrame(cMo); @@ -1386,7 +1409,7 @@ void vpMbtFaceDepthNormal::estimatePlaneEquationSVD(const std::vector &p for (size_t i = 0; i < point_cloud_face.size() / 3; i++) { residues[i] = std::fabs(A * point_cloud_face[3 * i] + B * point_cloud_face[3 * i + 1] + C * point_cloud_face[3 * i + 2] + D) / - sqrt(A * A + B * B + C * C); + sqrt(A * A + B * B + C * C); } tukey.MEstimator(residues, weights, 1e-4); @@ -1448,7 +1471,7 @@ void vpMbtFaceDepthNormal::estimatePlaneEquationSVD(const std::vector &p for (size_t i = 0; i < point_cloud_face.size() / 3; i++) { residues[i] = std::fabs(A * point_cloud_face[3 * i] + B * point_cloud_face[3 * i + 1] + C * point_cloud_face[3 * i + 2] + D) / - sqrt(A * A + B * B + C * C); + sqrt(A * A + B * B + C * C); error += weights[i] * residues[i]; } error /= total_w; @@ -1516,18 +1539,10 @@ vpMbtFaceDepthNormal::getFeaturesForDisplay(const vpHomogeneousMatrix &cMo, cons vpMeterPixelConversion::convertPoint(cam, pt_extremity.get_x(), pt_extremity.get_y(), im_extremity); { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {2, // desired normal + std::vector params = { 2, // desired normal im_centroid.get_i(), im_centroid.get_j(), im_extremity.get_i(), - im_extremity.get_j()}; -#else - std::vector params; - params.push_back(2); // desired normal - params.push_back(im_centroid.get_i()); - params.push_back(im_centroid.get_j()); - params.push_back(im_extremity.get_i()); - params.push_back(im_extremity.get_j()); -#endif + im_extremity.get_j() }; + features.push_back(params); } @@ -1554,18 +1569,10 @@ vpMbtFaceDepthNormal::getFeaturesForDisplay(const vpHomogeneousMatrix &cMo, cons vpMeterPixelConversion::convertPoint(cam, pt_extremity.get_x(), pt_extremity.get_y(), im_extremity); { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {3, // normal at current pose + std::vector params = { 3, // normal at current pose im_centroid.get_i(), im_centroid.get_j(), im_extremity.get_i(), - im_extremity.get_j()}; -#else - std::vector params; - params.push_back(3); // normal at current pose - params.push_back(im_centroid.get_i()); - params.push_back(im_centroid.get_j()); - params.push_back(im_extremity.get_i()); - params.push_back(im_extremity.get_j()); -#endif + im_extremity.get_j() }; + features.push_back(params); } } @@ -1598,7 +1605,7 @@ std::vector > vpMbtFaceDepthNormal::getModelForDisplay(unsig ++it) { vpMbtDistanceLine *line = *it; std::vector > lineModels = - line->getModelForDisplay(width, height, cMo, cam, displayFullModel); + line->getModelForDisplay(width, height, cMo, cam, displayFullModel); models.insert(models.end(), lineModels.begin(), lineModels.end()); } } diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp index bd24b7b2be..e85a72d168 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp @@ -57,10 +57,9 @@ */ vpMbtDistanceCircle::vpMbtDistanceCircle() : name(), index(0), cam(), me(NULL), wmean(1), featureEllipse(), isTrackedCircle(true), meEllipse(NULL), circle(NULL), - radius(0.), p1(NULL), p2(NULL), p3(NULL), L(), error(), nbFeature(0), Reinit(false), hiddenface(NULL), - index_polygon(-1), isvisible(false) -{ -} + radius(0.), p1(NULL), p2(NULL), p3(NULL), L(), error(), nbFeature(0), Reinit(false), hiddenface(NULL), + index_polygon(-1), isvisible(false) +{ } /*! Basic destructor useful to deallocate the memory. @@ -151,7 +150,8 @@ bool vpMbtDistanceCircle::initMovingEdge(const vpImage &I, const try { circle->projection(); - } catch (...) { + } + catch (...) { std::cout << "Problem when projecting circle\n"; return false; } @@ -169,8 +169,9 @@ bool vpMbtDistanceCircle::initMovingEdge(const vpImage &I, const double n20_p, n11_p, n02_p; vpMeterPixelConversion::convertEllipse(cam, *circle, ic, n20_p, n11_p, n02_p); meEllipse->initTracking(I, ic, n20_p, n11_p, n02_p, doNotTrack); - } catch (...) { - // vpTRACE("the circle can't be initialized"); + } + catch (...) { + // vpTRACE("the circle can't be initialized"); return false; } } @@ -188,8 +189,9 @@ void vpMbtDistanceCircle::trackMovingEdge(const vpImage &I, const if (isvisible) { try { meEllipse->track(I); - } catch (...) { - // std::cout << "Track meEllipse failed" << std::endl; + } + catch (...) { + // std::cout << "Track meEllipse failed" << std::endl; meEllipse->reset(); Reinit = true; } @@ -215,7 +217,8 @@ void vpMbtDistanceCircle::updateMovingEdge(const vpImage &I, cons try { circle->projection(); - } catch (...) { + } + catch (...) { std::cout << "Problem when projecting circle\n"; } @@ -225,7 +228,8 @@ void vpMbtDistanceCircle::updateMovingEdge(const vpImage &I, cons double n20_p, n11_p, n02_p; vpMeterPixelConversion::convertEllipse(cam, *circle, ic, n20_p, n11_p, n02_p); meEllipse->updateParameters(I, ic, n20_p, n11_p, n02_p); - } catch (...) { + } + catch (...) { Reinit = true; } nbFeature = (unsigned int)meEllipse->getMeList().size(); @@ -317,16 +321,9 @@ std::vector > vpMbtDistanceCircle::getFeaturesForDisplay() for (std::list::const_iterator it = meEllipse->getMeList().begin(); it != meEllipse->getMeList().end(); ++it) { vpMeSite p_me = *it; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {0, // ME - p_me.get_ifloat(), p_me.get_jfloat(), static_cast(p_me.getState())}; -#else - std::vector params; - params.push_back(0); // ME - params.push_back(p_me.get_ifloat()); - params.push_back(p_me.get_jfloat()); - params.push_back(static_cast(p_me.getState())); -#endif + std::vector params = { 0, // ME + p_me.get_ifloat(), p_me.get_jfloat(), static_cast(p_me.getState()) }; + features.push_back(params); } } @@ -356,7 +353,8 @@ std::vector vpMbtDistanceCircle::getModelForDisplay(const vpHomogeneousM try { circle->projection(); - } catch (...) { + } + catch (...) { std::cout << "Cannot project the circle"; } @@ -412,7 +410,8 @@ void vpMbtDistanceCircle::initInteractionMatrixError() nbFeature = (unsigned int)meEllipse->getMeList().size(); L.resize(nbFeature, 6); error.resize(nbFeature); - } else + } + else nbFeature = 0; } @@ -427,7 +426,8 @@ void vpMbtDistanceCircle::computeInteractionMatrixError(const vpHomogeneousMatri circle->changeFrame(cMo); try { circle->projection(); - } catch (...) { + } + catch (...) { std::cout << "Problem projection circle\n"; } @@ -461,8 +461,8 @@ void vpMbtDistanceCircle::computeInteractionMatrixError(const vpHomogeneousMatri L[j][k] = H[0] * H1[0][k] + H[1] * H1[1][k] + H[2] * H1[2][k] + H[3] * H1[3][k] + H[4] * H1[4][k]; error[j] = n02 * vpMath::sqr(x) + n20 * vpMath::sqr(y) - 2 * n11 * x * y + 2 * (n11 * yg - n02 * xg) * x + - 2 * (n11 * xg - n20 * yg) * y + n02 * vpMath::sqr(xg) + n20 * vpMath::sqr(yg) - 2 * n11 * xg * yg + - 4.0 * vpMath::sqr(n11) - 4.0 * n20 * n02; + 2 * (n11 * xg - n20 * yg) * y + n02 * vpMath::sqr(xg) + n20 * vpMath::sqr(yg) - 2 * n11 * xg * yg + + 4.0 * vpMath::sqr(n11) - 4.0 * n20 * n02; j++; } } diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp index 1a0d03810b..9ba91189f4 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp @@ -61,11 +61,10 @@ */ vpMbtDistanceCylinder::vpMbtDistanceCylinder() : name(), index(0), cam(), me(NULL), wmean1(1), wmean2(1), featureline1(), featureline2(), isTrackedCylinder(true), - meline1(NULL), meline2(NULL), cercle1(NULL), cercle2(NULL), radius(0), p1(NULL), p2(NULL), L(), error(), - nbFeature(0), nbFeaturel1(0), nbFeaturel2(0), Reinit(false), c(NULL), hiddenface(NULL), index_polygon(-1), - isvisible(false) -{ -} + meline1(NULL), meline2(NULL), cercle1(NULL), cercle2(NULL), radius(0), p1(NULL), p2(NULL), L(), error(), + nbFeature(0), nbFeaturel1(0), nbFeaturel2(0), Reinit(false), c(NULL), hiddenface(NULL), index_polygon(-1), + isvisible(false) +{ } /*! Basic destructor useful to deallocate the memory. @@ -192,14 +191,16 @@ bool vpMbtDistanceCylinder::initMovingEdge(const vpImage &I, cons p2->projection(); try { cercle1->projection(); - } catch (...) { - // std::cout<<"Problem when projecting circle 1\n"; + } + catch (...) { + // std::cout<<"Problem when projecting circle 1\n"; return false; } try { cercle2->projection(); - } catch (...) { - // std::cout<<"Problem when projecting circle 2\n"; + } + catch (...) { + // std::cout<<"Problem when projecting circle 2\n"; return false; } c->projection(); @@ -242,14 +243,16 @@ bool vpMbtDistanceCylinder::initMovingEdge(const vpImage &I, cons if (ip11.get_j() < ip12.get_j()) { meline1->jmin = (int)ip11.get_j() - marge; meline1->jmax = (int)ip12.get_j() + marge; - } else { + } + else { meline1->jmin = (int)ip12.get_j() - marge; meline1->jmax = (int)ip11.get_j() + marge; } if (ip11.get_i() < ip12.get_i()) { meline1->imin = (int)ip11.get_i() - marge; meline1->imax = (int)ip12.get_i() + marge; - } else { + } + else { meline1->imin = (int)ip12.get_i() - marge; meline1->imax = (int)ip11.get_i() + marge; } @@ -257,14 +260,16 @@ bool vpMbtDistanceCylinder::initMovingEdge(const vpImage &I, cons if (ip21.get_j() < ip22.get_j()) { meline2->jmin = (int)ip21.get_j() - marge; meline2->jmax = (int)ip22.get_j() + marge; - } else { + } + else { meline2->jmin = (int)ip22.get_j() - marge; meline2->jmax = (int)ip21.get_j() + marge; } if (ip21.get_i() < ip22.get_i()) { meline2->imin = (int)ip21.get_i() - marge; meline2->imax = (int)ip22.get_i() + marge; - } else { + } + else { meline2->imin = (int)ip22.get_i() - marge; meline2->imax = (int)ip21.get_i() + marge; } @@ -296,14 +301,16 @@ bool vpMbtDistanceCylinder::initMovingEdge(const vpImage &I, cons try { meline1->initTracking(I, ip11, ip12, rho1, theta1, doNotTrack); - } catch (...) { - // vpTRACE("the line can't be initialized"); + } + catch (...) { + // vpTRACE("the line can't be initialized"); return false; } try { meline2->initTracking(I, ip21, ip22, rho2, theta2, doNotTrack); - } catch (...) { - // vpTRACE("the line can't be initialized"); + } + catch (...) { + // vpTRACE("the line can't be initialized"); return false; } } @@ -321,15 +328,17 @@ void vpMbtDistanceCylinder::trackMovingEdge(const vpImage &I, con if (isvisible) { try { meline1->track(I); - } catch (...) { - // std::cout << "Track meline1 failed" << std::endl; + } + catch (...) { + // std::cout << "Track meline1 failed" << std::endl; meline1->reset(); Reinit = true; } try { meline2->track(I); - } catch (...) { - // std::cout << "Track meline2 failed" << std::endl; + } + catch (...) { + // std::cout << "Track meline2 failed" << std::endl; meline2->reset(); Reinit = true; } @@ -361,12 +370,14 @@ void vpMbtDistanceCylinder::updateMovingEdge(const vpImage &I, co p2->projection(); try { cercle1->projection(); - } catch (...) { + } + catch (...) { std::cout << "Probleme projection cercle 1\n"; } try { cercle2->projection(); - } catch (...) { + } + catch (...) { std::cout << "Probleme projection cercle 2\n"; } c->projection(); @@ -400,14 +411,16 @@ void vpMbtDistanceCylinder::updateMovingEdge(const vpImage &I, co if (ip11.get_j() < ip12.get_j()) { meline1->jmin = (int)ip11.get_j() - marge; meline1->jmax = (int)ip12.get_j() + marge; - } else { + } + else { meline1->jmin = (int)ip12.get_j() - marge; meline1->jmax = (int)ip11.get_j() + marge; } if (ip11.get_i() < ip12.get_i()) { meline1->imin = (int)ip11.get_i() - marge; meline1->imax = (int)ip12.get_i() + marge; - } else { + } + else { meline1->imin = (int)ip12.get_i() - marge; meline1->imax = (int)ip11.get_i() + marge; } @@ -415,14 +428,16 @@ void vpMbtDistanceCylinder::updateMovingEdge(const vpImage &I, co if (ip21.get_j() < ip22.get_j()) { meline2->jmin = (int)ip21.get_j() - marge; meline2->jmax = (int)ip22.get_j() + marge; - } else { + } + else { meline2->jmin = (int)ip22.get_j() - marge; meline2->jmax = (int)ip21.get_j() + marge; } if (ip21.get_i() < ip22.get_i()) { meline2->imin = (int)ip21.get_i() - marge; meline2->imax = (int)ip22.get_i() + marge; - } else { + } + else { meline2->imin = (int)ip22.get_i() - marge; meline2->imax = (int)ip21.get_i() + marge; } @@ -455,13 +470,15 @@ void vpMbtDistanceCylinder::updateMovingEdge(const vpImage &I, co try { // meline1->updateParameters(I,rho1,theta1); meline1->updateParameters(I, ip11, ip12, rho1, theta1); - } catch (...) { + } + catch (...) { Reinit = true; } try { // meline2->updateParameters(I,rho2,theta2); meline2->updateParameters(I, ip21, ip22, rho2, theta2); - } catch (...) { + } + catch (...) { Reinit = true; } @@ -515,7 +532,7 @@ void vpMbtDistanceCylinder::display(const vpImage &I, const vpHom bool displayFullModel) { std::vector > models = - getModelForDisplay(I.getWidth(), I.getHeight(), cMo, camera, displayFullModel); + getModelForDisplay(I.getWidth(), I.getHeight(), cMo, camera, displayFullModel); for (size_t i = 0; i < models.size(); i++) { vpImagePoint ip1(models[i][1], models[i][2]); @@ -540,7 +557,7 @@ void vpMbtDistanceCylinder::display(const vpImage &I, const vpHomogeneou bool displayFullModel) { std::vector > models = - getModelForDisplay(I.getWidth(), I.getHeight(), cMo, camera, displayFullModel); + getModelForDisplay(I.getWidth(), I.getHeight(), cMo, camera, displayFullModel); for (size_t i = 0; i < models.size(); i++) { vpImagePoint ip1(models[i][1], models[i][2]); @@ -562,16 +579,9 @@ std::vector > vpMbtDistanceCylinder::getFeaturesForDisplay() for (std::list::const_iterator it = meline1->getMeList().begin(); it != meline1->getMeList().end(); ++it) { vpMeSite p_me = *it; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {0, // ME - p_me.get_ifloat(), p_me.get_jfloat(), static_cast(p_me.getState())}; -#else - std::vector params; - params.push_back(0); // ME - params.push_back(p_me.get_ifloat()); - params.push_back(p_me.get_jfloat()); - params.push_back(static_cast(p_me.getState())); -#endif + std::vector params = { 0, // ME + p_me.get_ifloat(), p_me.get_jfloat(), static_cast(p_me.getState()) }; + features.push_back(params); } } @@ -580,16 +590,9 @@ std::vector > vpMbtDistanceCylinder::getFeaturesForDisplay() for (std::list::const_iterator it = meline2->getMeList().begin(); it != meline2->getMeList().end(); ++it) { vpMeSite p_me = *it; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {0, // ME - p_me.get_ifloat(), p_me.get_jfloat(), static_cast(p_me.getState())}; -#else - std::vector params; - params.push_back(0); // ME - params.push_back(p_me.get_ifloat()); - params.push_back(p_me.get_jfloat()); - params.push_back(static_cast(p_me.getState())); -#endif + std::vector params = { 0, // ME + p_me.get_ifloat(), p_me.get_jfloat(), static_cast(p_me.getState()) }; + features.push_back(params); } } @@ -626,12 +629,14 @@ std::vector > vpMbtDistanceCylinder::getModelForDisplay(unsi p2->projection(); try { cercle1->projection(); - } catch (...) { + } + catch (...) { std::cout << "Problem projection circle 1"; } try { cercle2->projection(); - } catch (...) { + } + catch (...) { std::cout << "Problem projection circle 2"; } c->projection(); @@ -659,24 +664,9 @@ std::vector > vpMbtDistanceCylinder::getModelForDisplay(unsi ip21.set_ij(i21, j21); ip22.set_ij(i22, j22); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params1 = {0, ip11.get_i(), ip11.get_j(), ip12.get_i(), ip12.get_j()}; - - std::vector params2 = {0, ip21.get_i(), ip21.get_j(), ip22.get_i(), ip22.get_j()}; -#else - std::vector params1, params2; - params1.push_back(0); - params1.push_back(ip11.get_i()); - params1.push_back(ip11.get_j()); - params1.push_back(ip12.get_i()); - params1.push_back(ip12.get_j()); - - params2.push_back(0); - params2.push_back(ip11.get_i()); - params2.push_back(ip11.get_j()); - params2.push_back(ip12.get_i()); - params2.push_back(ip12.get_j()); -#endif + std::vector params1 = { 0, ip11.get_i(), ip11.get_j(), ip12.get_i(), ip12.get_j() }; + + std::vector params2 = { 0, ip21.get_i(), ip21.get_j(), ip22.get_i(), ip22.get_j() }; models.push_back(params1); models.push_back(params2); @@ -730,7 +720,8 @@ void vpMbtDistanceCylinder::initInteractionMatrixError() nbFeature = nbFeaturel1 + nbFeaturel2; L.resize(nbFeature, 6); error.resize(nbFeature); - } else { + } + else { nbFeature = 0; nbFeaturel1 = 0; nbFeaturel2 = 0; @@ -752,12 +743,14 @@ void vpMbtDistanceCylinder::computeInteractionMatrixError(const vpHomogeneousMat cercle1->changeFrame(cMo); try { cercle1->projection(); - } catch (...) { + } + catch (...) { std::cout << "Problem projection circle 1\n"; } try { cercle2->projection(); - } catch (...) { + } + catch (...) { std::cout << "Problem projection circle 2\n"; } diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp index 80083734bc..92651b06e4 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp @@ -56,10 +56,9 @@ void buildLine(vpPoint &P1, vpPoint &P2, vpPoint &P3, vpPoint &P4, vpLine &L); */ vpMbtDistanceLine::vpMbtDistanceLine() : name(), index(0), cam(), me(NULL), isTrackedLine(true), isTrackedLineWithVisibility(true), wmean(1), featureline(), - poly(), useScanLine(false), meline(), line(NULL), p1(NULL), p2(NULL), L(), error(), nbFeature(), nbFeatureTotal(0), - Reinit(false), hiddenface(NULL), Lindex_polygon(), Lindex_polygon_tracked(), isvisible(false) -{ -} + poly(), useScanLine(false), meline(), line(NULL), p1(NULL), p2(NULL), L(), error(), nbFeature(), nbFeatureTotal(0), + Reinit(false), hiddenface(NULL), Lindex_polygon(), Lindex_polygon_tracked(), isvisible(false) +{ } /*! Basic destructor useful to deallocate the memory. @@ -199,7 +198,8 @@ void vpMbtDistanceLine::buildFrom(vpPoint &_p1, vpPoint &_p2, vpUniRand &rand_ge vpPoint P3(V3[0], V3[1], V3[2]); vpPoint P4(V4[0], V4[1], V4[2]); buildLine(*p1, *p2, P3, P4, *line); - } else { + } + else { vpPoint P3(V1[0], V1[1], V1[2]); vpPoint P4(V2[0], V2[1], V2[2]); buildLine(*p1, *p2, P3, P4, *line); @@ -328,7 +328,8 @@ bool vpMbtDistanceLine::initMovingEdge(const vpImage &I, const vp if (useScanLine) { hiddenface->computeScanLineQuery(poly.polyClipped[0].first, poly.polyClipped[1].first, linesLst); - } else { + } + else { linesLst.push_back(std::make_pair(poly.polyClipped[0].first, poly.polyClipped[1].first)); } @@ -339,7 +340,8 @@ bool vpMbtDistanceLine::initMovingEdge(const vpImage &I, const vp line->changeFrame(cMo); try { line->projection(); - } catch (...) { + } + catch (...) { isvisible = false; return false; } @@ -378,14 +380,16 @@ bool vpMbtDistanceLine::initMovingEdge(const vpImage &I, const vp if (ip1.get_j() < ip2.get_j()) { melinePt->jmin = (int)ip1.get_j() - marge; melinePt->jmax = (int)ip2.get_j() + marge; - } else { + } + else { melinePt->jmin = (int)ip2.get_j() - marge; melinePt->jmax = (int)ip1.get_j() + marge; } if (ip1.get_i() < ip2.get_i()) { melinePt->imin = (int)ip1.get_i() - marge; melinePt->imax = (int)ip2.get_i() + marge; - } else { + } + else { melinePt->imin = (int)ip2.get_i() - marge; melinePt->imax = (int)ip1.get_i() + marge; } @@ -395,13 +399,15 @@ bool vpMbtDistanceLine::initMovingEdge(const vpImage &I, const vp meline.push_back(melinePt); nbFeature.push_back((unsigned int)melinePt->getMeList().size()); nbFeatureTotal += nbFeature.back(); - } catch (...) { + } + catch (...) { delete melinePt; isvisible = false; return false; } } - } else { + } + else { isvisible = false; } } @@ -425,7 +431,8 @@ void vpMbtDistanceLine::trackMovingEdge(const vpImage &I) nbFeature.push_back((unsigned int)meline[i]->getMeList().size()); nbFeatureTotal += (unsigned int)meline[i]->getMeList().size(); } - } catch (...) { + } + catch (...) { for (size_t i = 0; i < meline.size(); i++) { if (meline[i] != NULL) delete meline[i]; @@ -463,7 +470,8 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const if (useScanLine) { hiddenface->computeScanLineQuery(poly.polyClipped[0].first, poly.polyClipped[1].first, linesLst); - } else { + } + else { linesLst.push_back(std::make_pair(poly.polyClipped[0].first, poly.polyClipped[1].first)); } @@ -478,11 +486,13 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const nbFeatureTotal = 0; isvisible = false; Reinit = true; - } else { + } + else { line->changeFrame(cMo); try { line->projection(); - } catch (...) { + } + catch (...) { for (size_t j = 0; j < meline.size(); j++) { if (meline[j] != NULL) delete meline[j]; @@ -525,14 +535,16 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const if (ip1.get_j() < ip2.get_j()) { meline[i]->jmin = (int)ip1.get_j() - marge; meline[i]->jmax = (int)ip2.get_j() + marge; - } else { + } + else { meline[i]->jmin = (int)ip2.get_j() - marge; meline[i]->jmax = (int)ip1.get_j() + marge; } if (ip1.get_i() < ip2.get_i()) { meline[i]->imin = (int)ip1.get_i() - marge; meline[i]->imax = (int)ip2.get_i() + marge; - } else { + } + else { meline[i]->imin = (int)ip2.get_i() - marge; meline[i]->imax = (int)ip1.get_i() + marge; } @@ -541,7 +553,8 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const nbFeature[i] = (unsigned int)meline[i]->getMeList().size(); nbFeatureTotal += nbFeature[i]; } - } catch (...) { + } + catch (...) { for (size_t j = 0; j < meline.size(); j++) { if (meline[j] != NULL) delete meline[j]; @@ -554,7 +567,8 @@ void vpMbtDistanceLine::updateMovingEdge(const vpImage &I, const Reinit = true; } } - } else { + } + else { for (size_t i = 0; i < meline.size(); i++) { if (meline[i] != NULL) delete meline[i]; @@ -612,7 +626,7 @@ void vpMbtDistanceLine::display(const vpImage &I, const vpHomogen bool displayFullModel) { std::vector > models = - getModelForDisplay(I.getWidth(), I.getHeight(), cMo, camera, displayFullModel); + getModelForDisplay(I.getWidth(), I.getHeight(), cMo, camera, displayFullModel); for (size_t i = 0; i < models.size(); i++) { vpImagePoint ip1(models[i][1], models[i][2]); @@ -637,7 +651,7 @@ void vpMbtDistanceLine::display(const vpImage &I, const vpHomogeneousMat bool displayFullModel) { std::vector > models = - getModelForDisplay(I.getWidth(), I.getHeight(), cMo, camera, displayFullModel); + getModelForDisplay(I.getWidth(), I.getHeight(), cMo, camera, displayFullModel); for (size_t i = 0; i < models.size(); i++) { vpImagePoint ip1(models[i][1], models[i][2]); @@ -691,16 +705,9 @@ std::vector > vpMbtDistanceLine::getFeaturesForDisplay() if (me_l != NULL) { for (std::list::const_iterator it = me_l->getMeList().begin(); it != me_l->getMeList().end(); ++it) { vpMeSite p_me_l = *it; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {0, // ME - p_me_l.get_ifloat(), p_me_l.get_jfloat(), static_cast(p_me_l.getState())}; -#else - std::vector params; - params.push_back(0); // ME - params.push_back(p_me_l.get_ifloat()); - params.push_back(p_me_l.get_jfloat()); - params.push_back(static_cast(p_me_l.getState())); -#endif + std::vector params = { 0, // ME + p_me_l.get_ifloat(), p_me_l.get_jfloat(), static_cast(p_me_l.getState()) }; + features.push_back(params); } } @@ -749,7 +756,8 @@ std::vector > vpMbtDistanceLine::getModelForDisplay(unsigned std::vector > linesLst; if (useScanLine && !displayFullModel) { hiddenface->computeScanLineQuery(poly.polyClipped[0].first, poly.polyClipped[1].first, linesLst, true); - } else { + } + else { linesLst.push_back(std::make_pair(poly.polyClipped[0].first, poly.polyClipped[1].first)); } @@ -760,17 +768,9 @@ std::vector > vpMbtDistanceLine::getModelForDisplay(unsigned vpMeterPixelConversion::convertPoint(camera, linesLst[i].first.get_x(), linesLst[i].first.get_y(), ip1); vpMeterPixelConversion::convertPoint(camera, linesLst[i].second.get_x(), linesLst[i].second.get_y(), ip2); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {0, // 0 for line parameters - ip1.get_i(), ip1.get_j(), ip2.get_i(), ip2.get_j()}; -#else - std::vector params; - params.push_back(0); // 0 for line parameters - params.push_back(ip1.get_i()); - params.push_back(ip1.get_j()); - params.push_back(ip2.get_i()); - params.push_back(ip2.get_j()); -#endif + std::vector params = { 0, // 0 for line parameters + ip1.get_i(), ip1.get_j(), ip2.get_i(), ip2.get_j() }; + models.push_back(params); } } @@ -787,7 +787,8 @@ void vpMbtDistanceLine::initInteractionMatrixError() if (isvisible) { L.resize(nbFeatureTotal, 6); error.resize(nbFeatureTotal); - } else { + } + else { for (size_t i = 0; i < meline.size(); i++) { nbFeature[i] = 0; // To be consistent with nbFeature[i] = 0 @@ -850,9 +851,10 @@ void vpMbtDistanceLine::computeInteractionMatrixError(const vpHomogeneousMatrix j++; } } - } catch (...) { - // Handle potential exception: due to a degenerate case: the image of the straight line is a point! - // Set the corresponding interaction matrix part to zero + } + catch (...) { + // Handle potential exception: due to a degenerate case: the image of the straight line is a point! + // Set the corresponding interaction matrix part to zero unsigned int j = 0; for (size_t i = 0; i < meline.size(); i++) { for (std::list::const_iterator it = meline[i]->getMeList().begin(); @@ -894,8 +896,8 @@ bool vpMbtDistanceLine::closeToImageBorder(const vpImage &I, cons return true; } - if (((unsigned int)i_ > (I.getHeight() - threshold)) || (unsigned int)i_ < threshold || - ((unsigned int)j_ > (I.getWidth() - threshold)) || (unsigned int)j_ < threshold) { + if (((unsigned int)i_ >(I.getHeight() - threshold)) || (unsigned int)i_ < threshold || + ((unsigned int)j_ >(I.getWidth() - threshold)) || (unsigned int)j_ < threshold) { return true; } } diff --git a/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp b/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp index adc7cd4038..68ae531fc1 100644 --- a/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp +++ b/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp @@ -53,16 +53,15 @@ */ vpMbtDistanceKltCylinder::vpMbtDistanceKltCylinder() : c0Mo(), p1Ext(), p2Ext(), cylinder(), circle1(), circle2(), initPoints(), initPoints3D(), curPoints(), - curPointsInd(), nbPointsCur(0), nbPointsInit(0), minNbPoint(4), enoughPoints(false), cam(), - isTrackedKltCylinder(true), listIndicesCylinderBBox(), hiddenface(NULL), useScanLine(false) -{ -} + curPointsInd(), nbPointsCur(0), nbPointsInit(0), minNbPoint(4), enoughPoints(false), cam(), + isTrackedKltCylinder(true), listIndicesCylinderBBox(), hiddenface(NULL), useScanLine(false) +{ } /*! Basic destructor. */ -vpMbtDistanceKltCylinder::~vpMbtDistanceKltCylinder() {} +vpMbtDistanceKltCylinder::~vpMbtDistanceKltCylinder() { } void vpMbtDistanceKltCylinder::buildFrom(const vpPoint &p1, const vpPoint &p2, const double &r) { @@ -130,7 +129,8 @@ void vpMbtDistanceKltCylinder::init(const vpKltOpencv &_tracker, const vpHomogen break; } } - } else { + } + else { std::vector roi; for (unsigned int kc = 0; kc < listIndicesCylinderBBox.size(); kc++) { hiddenface->getPolygon()[(size_t)listIndicesCylinderBBox[kc]]->getRoiClipped(cam, roi); @@ -243,7 +243,8 @@ void vpMbtDistanceKltCylinder::removeOutliers(const vpColVector &_w, const doubl tmp[iter->first] = vpImagePoint(iter->second.get_i(), iter->second.get_j()); tmp2[iter->first] = curPointsInd[iter->first]; nbPointsCur++; - } else { + } + else { nbSupp++; initPoints.erase(iter->first); } @@ -321,7 +322,8 @@ void vpMbtDistanceKltCylinder::computeInteractionMatrixAndResidu(const vpHomogen _R[2 * index_] = (x0_transform - x_cur); _R[2 * index_ + 1] = (y0_transform - y_cur); index_++; - } else { + } + else { double invZ = 1.0 / Z; _J[2 * index_][0] = -invZ; @@ -424,7 +426,8 @@ void vpMbtDistanceKltCylinder::updateMask( for (size_t i = 0; i < solution[index_max].size(); i++) { roi_offset.push_back(vpImagePoint((double)(solution[index_max][i].Y), (double)(solution[index_max][i].X))); } - } else { + } + else { roi_offset = roi; } @@ -472,7 +475,8 @@ void vpMbtDistanceKltCylinder::updateMask( vpPolygon::isInside(roi, i_d - shiftBorder_d, j_d - shiftBorder_d)) { mask.at(i, j) = nb; } - } else { + } + else { if (vpPolygon::isInside(roi, i, j)) { mask.at(i, j) = nb; } @@ -579,18 +583,9 @@ std::vector > vpMbtDistanceKltCylinder::getFeaturesForDispla iP2.set_i(vpMath::round(iP.get_i() + 7)); iP2.set_j(vpMath::round(iP.get_j() + 7)); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {1, // KLT - iP.get_i(), iP.get_j(), iP2.get_i(), iP2.get_j(), static_cast(id)}; -#else - std::vector params; - params.push_back(1); // KLT - params.push_back(iP.get_i()); - params.push_back(iP.get_j()); - params.push_back(iP2.get_i()); - params.push_back(iP2.get_j()); - params.push_back(static_cast(id)); -#endif + std::vector params = { 1, // KLT + iP.get_i(), iP.get_j(), iP2.get_i(), iP2.get_j(), static_cast(id) }; + features.push_back(params); } @@ -619,12 +614,14 @@ std::vector > vpMbtDistanceKltCylinder::getModelForDisplay(c try { circle1.projection(); - } catch (...) { + } + catch (...) { std::cout << "Problem projection circle 1"; } try { circle2.projection(); - } catch (...) { + } + catch (...) { std::cout << "Problem projection circle 2"; } @@ -653,27 +650,13 @@ std::vector > vpMbtDistanceKltCylinder::getModelForDisplay(c ip21.set_ij(i21, j21); ip22.set_ij(i22, j22); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params1 = {0, // line parameters - ip11.get_i(), ip11.get_j(), ip12.get_i(), ip12.get_j()}; + std::vector params1 = { 0, // line parameters + ip11.get_i(), ip11.get_j(), ip12.get_i(), ip12.get_j() }; models.push_back(params1); - std::vector params2 = {0, // line parameters - ip21.get_i(), ip21.get_j(), ip22.get_i(), ip22.get_j()}; -#else - std::vector params1, params2; - params1.push_back(0); // line parameters - params1.push_back(ip11.get_i()); - params1.push_back(ip11.get_j()); - params1.push_back(ip12.get_i()); - params1.push_back(ip12.get_j()); - - params2.push_back(0); // line parameters - params2.push_back(ip21.get_i()); - params2.push_back(ip21.get_j()); - params2.push_back(ip22.get_i()); - params2.push_back(ip22.get_j()); -#endif + std::vector params2 = { 0, // line parameters + ip21.get_i(), ip21.get_j(), ip22.get_i(), ip22.get_j() }; + models.push_back(params1); models.push_back(params2); } @@ -701,5 +684,5 @@ double vpMbtDistanceKltCylinder::computeZ(const double &x, const double &y) #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: // libvisp_mbt.a(vpMbtDistanceKltCylinder.cpp.o) has no symbols -void dummy_vpMbtDistanceKltCylinder(){}; +void dummy_vpMbtDistanceKltCylinder() { }; #endif diff --git a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp index 56bef81a4e..9c67083b1a 100644 --- a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp +++ b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp @@ -53,17 +53,16 @@ */ vpMbtDistanceKltPoints::vpMbtDistanceKltPoints() : H(), N(), N_cur(), invd0(1.), cRc0_0n(), initPoints(std::map()), - curPoints(std::map()), curPointsInd(std::map()), nbPointsCur(0), nbPointsInit(0), - minNbPoint(4), enoughPoints(false), dt(1.), d0(1.), cam(), isTrackedKltPoints(true), polygon(NULL), - hiddenface(NULL), useScanLine(false) -{ -} + curPoints(std::map()), curPointsInd(std::map()), nbPointsCur(0), nbPointsInit(0), + minNbPoint(4), enoughPoints(false), dt(1.), d0(1.), cam(), isTrackedKltPoints(true), polygon(NULL), + hiddenface(NULL), useScanLine(false) +{ } /*! Basic destructor. */ -vpMbtDistanceKltPoints::~vpMbtDistanceKltPoints() {} +vpMbtDistanceKltPoints::~vpMbtDistanceKltPoints() { } /*! Initialise the face to track. All the points in the map, representing all @@ -100,7 +99,8 @@ void vpMbtDistanceKltPoints::init(const vpKltOpencv &_tracker, const vpImagegetMbScanLineRenderer().getPrimitiveIDs()[(unsigned int)y_tmp][(unsigned int)x_tmp] == polygon->getIndex()) add = true; - } else if (vpPolygon::isInside(roi, y_tmp, x_tmp)) { + } + else if (vpPolygon::isInside(roi, y_tmp, x_tmp)) { add = true; } } @@ -205,7 +205,7 @@ void vpMbtDistanceKltPoints::computeInteractionMatrixAndResidu(vpColVector &_R, vpPixelMeterConversion::convertPoint(cam, iP0, x0, y0); double x0_transform, - y0_transform; // equivalent x and y in the first image (reference) + y0_transform; // equivalent x and y in the first image (reference) computeP_mu_t(x0, y0, x0_transform, y0_transform, H); double invZ = compute_1_over_Z(x_cur, y_cur); @@ -400,7 +400,8 @@ void vpMbtDistanceKltPoints::updateMask( for (size_t i = 0; i < solution[index_max].size(); i++) { roi_offset.push_back(vpImagePoint((double)(solution[index_max][i].Y), (double)(solution[index_max][i].X))); } - } else { + } + else { roi_offset = roi; } @@ -447,7 +448,8 @@ void vpMbtDistanceKltPoints::updateMask( vpPolygon::isInside(roi, i_d - shiftBorder_d, j_d - shiftBorder_d)) { mask.at(i, j) = nb; } - } else { + } + else { if (vpPolygon::isInside(roi, i, j)) { mask.at(i, j) = nb; } @@ -480,7 +482,8 @@ void vpMbtDistanceKltPoints::removeOutliers(const vpColVector &_w, const double tmp[iter->first] = vpImagePoint(iter->second.get_i(), iter->second.get_j()); tmp2[iter->first] = curPointsInd[iter->first]; nbPointsCur++; - } else { + } + else { nbSupp++; initPoints.erase(iter->first); } @@ -593,19 +596,8 @@ std::vector > vpMbtDistanceKltPoints::getFeaturesForDisplay( vpImagePoint iP2; iP2.set_i(vpMath::round(iP.get_i() + 7)); iP2.set_j(vpMath::round(iP.get_j() + 7)); - -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {1, // KLT - iP.get_i(), iP.get_j(), iP2.get_i(), iP2.get_j(), static_cast(id)}; -#else - std::vector params; - params.push_back(1); // KLT - params.push_back(iP.get_i()); - params.push_back(iP.get_j()); - params.push_back(iP2.get_i()); - params.push_back(iP2.get_j()); - params.push_back(static_cast(id)); -#endif + std::vector params = { 1, // KLT + iP.get_i(), iP.get_j(), iP2.get_i(), iP2.get_j(), static_cast(id) }; features.push_back(params); } @@ -650,18 +642,8 @@ std::vector > vpMbtDistanceKltPoints::getModelForDisplay(con linesLst[i].second.project(); vpMeterPixelConversion::convertPoint(camera, linesLst[i].first.get_x(), linesLst[i].first.get_y(), ip1); vpMeterPixelConversion::convertPoint(camera, linesLst[i].second.get_x(), linesLst[i].second.get_y(), ip2); - -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::vector params = {0, // 0 for line parameters - ip1.get_i(), ip1.get_j(), ip2.get_i(), ip2.get_j()}; -#else - std::vector params; - params.push_back(0); // 0 for line parameters - params.push_back(ip1.get_i()); - params.push_back(ip1.get_j()); - params.push_back(ip2.get_i()); - params.push_back(ip2.get_j()); -#endif + std::vector params = { 0, // 0 for line parameters + ip1.get_i(), ip1.get_j(), ip2.get_i(), ip2.get_j() }; models.push_back(params); } } @@ -674,5 +656,5 @@ std::vector > vpMbtDistanceKltPoints::getModelForDisplay(con #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_mbt.a(vpMbtDistanceKltPoints.cpp.o) // has no symbols -void dummy_vpMbtDistanceKltPoints(){}; +void dummy_vpMbtDistanceKltPoints() { }; #endif diff --git a/modules/tracker/mbt/src/vpMbGenericTracker.cpp b/modules/tracker/mbt/src/vpMbGenericTracker.cpp index 71b8ee65b0..d4b851ccef 100644 --- a/modules/tracker/mbt/src/vpMbGenericTracker.cpp +++ b/modules/tracker/mbt/src/vpMbGenericTracker.cpp @@ -7105,7 +7105,7 @@ void vpMbGenericTracker::TrackerWrapper::testTracking() } void vpMbGenericTracker::TrackerWrapper::track(const vpImage & -#if defined(VISP_HAVE_PCL) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PCL) I #endif ) @@ -7119,7 +7119,7 @@ void vpMbGenericTracker::TrackerWrapper::track(const vpImage & return; } -#if defined(VISP_HAVE_PCL) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PCL) track(&I, nullptr); #endif } diff --git a/modules/tracker/mbt/src/vpMbTracker.cpp b/modules/tracker/mbt/src/vpMbTracker.cpp index 0aa00ffc5f..b4beb1e3a6 100644 --- a/modules/tracker/mbt/src/vpMbTracker.cpp +++ b/modules/tracker/mbt/src/vpMbTracker.cpp @@ -90,22 +90,19 @@ #include #endif -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include -#endif #ifndef DOXYGEN_SHOULD_SKIP_THIS namespace { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::mutex g_mutex_cout; -#endif +std::mutex g_mutex_cout; /*! Structure to store info about segment in CAO model files. */ -struct SegmentInfo { - SegmentInfo() : extremities(), name(), useLod(false), minLineLengthThresh(0.) {} +struct SegmentInfo +{ + SegmentInfo() : extremities(), name(), useLod(false), minLineLengthThresh(0.) { } std::vector extremities; std::string name; @@ -117,11 +114,11 @@ struct SegmentInfo { Structure to store info about a polygon face represented by a vpPolygon and by a list of vpPoint representing the corners of the polygon face in 3D. */ -struct PolygonFaceInfo { +struct PolygonFaceInfo +{ PolygonFaceInfo(double dist, const vpPolygon &poly, const std::vector &corners) : distanceToCamera(dist), polygon(poly), faceCorners(corners) - { - } + { } bool operator<(const PolygonFaceInfo &pfi) const { return distanceToCamera < pfi.distanceToCamera; } @@ -154,16 +151,19 @@ std::istream &safeGetline(std::istream &is, std::string &t) int c = sb->sbumpc(); if (c == '\n') { return is; - } else if (c == '\r') { + } + else if (c == '\r') { if (sb->sgetc() == '\n') sb->sbumpc(); return is; - } else if (c == std::streambuf::traits_type::eof()) { - // Also handle the case when the last line has no line ending + } + else if (c == std::streambuf::traits_type::eof()) { + // Also handle the case when the last line has no line ending if (t.empty()) is.setstate(std::ios::eofbit); return is; - } else { // default case + } + else { // default case t += (char)c; } } @@ -178,18 +178,18 @@ std::istream &safeGetline(std::istream &is, std::string &t) */ vpMbTracker::vpMbTracker() : m_cam(), m_cMo(), oJo(6, 6), m_isoJoIdentity(true), modelFileName(), modelInitialised(false), poseSavingFilename(), - computeCovariance(false), covarianceMatrix(), computeProjError(false), projectionError(90.0), - displayFeatures(false), m_optimizationMethod(vpMbTracker::GAUSS_NEWTON_OPT), faces(), angleAppears(vpMath::rad(89)), - angleDisappears(vpMath::rad(89)), distNearClip(0.001), distFarClip(100), clippingFlag(vpPolygon3D::NO_CLIPPING), - useOgre(false), ogreShowConfigDialog(false), useScanLine(false), nbPoints(0), nbLines(0), nbPolygonLines(0), - nbPolygonPoints(0), nbCylinders(0), nbCircles(0), useLodGeneral(false), applyLodSettingInConfig(false), - minLineLengthThresholdGeneral(50.0), minPolygonAreaThresholdGeneral(2500.0), mapOfParameterNames(), - m_computeInteraction(true), m_lambda(1.0), m_maxIter(30), m_stopCriteriaEpsilon(1e-8), m_initialMu(0.01), - m_projectionErrorLines(), m_projectionErrorCylinders(), m_projectionErrorCircles(), m_projectionErrorFaces(), - m_projectionErrorOgreShowConfigDialog(false), m_projectionErrorMe(), m_projectionErrorKernelSize(2), m_SobelX(5, 5), - m_SobelY(5, 5), m_projectionErrorDisplay(false), m_projectionErrorDisplayLength(20), - m_projectionErrorDisplayThickness(1), m_projectionErrorCam(), m_mask(NULL), m_I(), m_sodb_init_called(false), - m_rand() + computeCovariance(false), covarianceMatrix(), computeProjError(false), projectionError(90.0), + displayFeatures(false), m_optimizationMethod(vpMbTracker::GAUSS_NEWTON_OPT), faces(), angleAppears(vpMath::rad(89)), + angleDisappears(vpMath::rad(89)), distNearClip(0.001), distFarClip(100), clippingFlag(vpPolygon3D::NO_CLIPPING), + useOgre(false), ogreShowConfigDialog(false), useScanLine(false), nbPoints(0), nbLines(0), nbPolygonLines(0), + nbPolygonPoints(0), nbCylinders(0), nbCircles(0), useLodGeneral(false), applyLodSettingInConfig(false), + minLineLengthThresholdGeneral(50.0), minPolygonAreaThresholdGeneral(2500.0), mapOfParameterNames(), + m_computeInteraction(true), m_lambda(1.0), m_maxIter(30), m_stopCriteriaEpsilon(1e-8), m_initialMu(0.01), + m_projectionErrorLines(), m_projectionErrorCylinders(), m_projectionErrorCircles(), m_projectionErrorFaces(), + m_projectionErrorOgreShowConfigDialog(false), m_projectionErrorMe(), m_projectionErrorKernelSize(2), m_SobelX(5, 5), + m_SobelY(5, 5), m_projectionErrorDisplay(false), m_projectionErrorDisplayLength(20), + m_projectionErrorDisplayThickness(1), m_projectionErrorCam(), m_mask(NULL), m_I(), m_sodb_init_called(false), + m_rand() { oJo.eye(); // Map used to parse additional information in CAO model files, @@ -261,14 +261,16 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage finitpos.open(str_pose.c_str(), std::ios::in); ss << str_pose; - } else { + } + else { finitpos.open(poseSavingFilename.c_str(), std::ios::in); ss << poseSavingFilename; } if (finitpos.fail()) { std::cout << "Cannot read " << ss.str() << std::endl << "cMo set to identity" << std::endl; last_cMo.eye(); - } else { + } + else { for (unsigned int i = 0; i < 6; i += 1) { finitpos >> init_pos[i]; } @@ -283,7 +285,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage display(*I, last_cMo, m_cam, vpColor::green, 1, true); vpDisplay::displayFrame(*I, last_cMo, m_cam, 0.05, vpColor::green); vpDisplay::flush(*I); - } else { + } + else { vpDisplay::display(*I_color); display(*I_color, last_cMo, m_cam, vpColor::green, 1, true); vpDisplay::displayFrame(*I_color, last_cMo, m_cam, 0.05, vpColor::green); @@ -300,7 +303,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage while (!vpDisplay::getClick(*I, ip, button)) { } - } else { + } + else { vpDisplay::displayText(*I_color, 15, 10, "left click to validate, right click to modify initial pose", vpColor::red); @@ -313,13 +317,15 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (!finitpos.fail() && button == vpMouseButton::button1) { m_cMo = last_cMo; - } else { + } + else { vpDisplay *d_help = NULL; if (I) { vpDisplay::display(*I); vpDisplay::flush(*I); - } else { + } + else { vpDisplay::display(*I_color); vpDisplay::flush(*I_color); } @@ -337,17 +343,14 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage // X Y Z if (pos != std::string::npos) { ss << initFile; - } else { + } + else { ss << initFile; ss << ".init"; } std::cout << "Load 3D points from: " << ss.str() << std::endl; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) finit.open(ss.str()); -#else - finit.open(ss.str().c_str()); -#endif if (finit.fail()) { std::cout << "Cannot read " << ss.str() << std::endl; throw vpException(vpException::ioError, "Cannot open model-based tracker init file %s", ss.str().c_str()); @@ -357,7 +360,7 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage // Display window creation and initialisation try { if (displayHelp) { - const std::string imgExtVec[] = {".ppm", ".pgm", ".jpg", ".jpeg", ".png"}; + const std::string imgExtVec[] = { ".ppm", ".pgm", ".jpg", ".jpeg", ".png" }; std::string dispF; bool foundHelpImg = false; if (pos != std::string::npos) { @@ -365,7 +368,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage dispF = initFile.substr(0, pos) + imgExtVec[i]; foundHelpImg = vpIoTools::checkFilename(dispF); } - } else { + } + else { for (size_t i = 0; i < 5 && !foundHelpImg; i++) { dispF = initFile + imgExtVec[i]; foundHelpImg = vpIoTools::checkFilename(dispF); @@ -394,7 +398,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage #endif } } - } catch (...) { + } + catch (...) { if (d_help != NULL) { delete d_help; d_help = NULL; @@ -428,7 +433,7 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage vpColVector pt_3d_tf = T * pt_3d; std::cout << "Point " << i + 1 << " with 3D coordinates: " << pt_3d_tf[0] << " " << pt_3d_tf[1] << " " - << pt_3d_tf[2] << std::endl; + << pt_3d_tf[2] << std::endl; P[i].setWorldCoordinates(pt_3d_tf[0], pt_3d_tf[1], pt_3d_tf[2]); // (X,Y,Z) } @@ -448,7 +453,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage vpDisplay::displayCross(*I, mem_ip[k], 10, vpColor::green, 2); } vpDisplay::flush(*I); - } else { + } + else { vpDisplay::display(*I_color); vpDisplay::displayText(*I_color, 15, 10, text.str(), vpColor::red); for (unsigned int k = 0; k < mem_ip.size(); k++) { @@ -463,7 +469,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage vpDisplay::getClick(*I, ip); mem_ip.push_back(ip); vpDisplay::flush(*I); - } else { + } + else { vpDisplay::getClick(*I_color, ip); mem_ip.push_back(ip); vpDisplay::flush(*I_color); @@ -479,7 +486,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (I) { vpDisplay::flush(*I); vpDisplay::display(*I); - } else { + } + else { vpDisplay::flush(*I_color); vpDisplay::display(*I_color); } @@ -498,12 +506,14 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (button == vpMouseButton::button1) { isWellInit = true; - } else { + } + else { pose.clearPoint(); vpDisplay::display(*I); vpDisplay::flush(*I); } - } else { + } + else { display(*I_color, m_cMo, m_cam, vpColor::green, 1, true); vpDisplay::displayText(*I_color, 15, 10, "left click to validate, right click to re initialize object", vpColor::red); @@ -516,7 +526,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (button == vpMouseButton::button1) { isWellInit = true; - } else { + } + else { pose.clearPoint(); vpDisplay::display(*I_color); vpDisplay::flush(*I_color); @@ -630,7 +641,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (I) { vpDisplay::display(*I); vpDisplay::flush(*I); - } else { + } + else { vpDisplay::display(*I_color); vpDisplay::flush(*I_color); } @@ -661,14 +673,16 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (I) { d_help->init(Iref, I->display->getWindowXPosition() + (int)I->getWidth() + 80, I->display->getWindowYPosition(), "Where to initialize..."); - } else { + } + else { d_help->init(Iref, I_color->display->getWindowXPosition() + (int)I_color->getWidth() + 80, I_color->display->getWindowYPosition(), "Where to initialize..."); } vpDisplay::display(Iref); vpDisplay::flush(Iref); #endif - } catch (...) { + } + catch (...) { if (d_help != NULL) { delete d_help; d_help = NULL; @@ -689,7 +703,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage vpDisplay::getClick(*I, ip); vpDisplay::displayCross(*I, ip, 5, vpColor::green); vpDisplay::flush(*I); - } else { + } + else { vpDisplay::getClick(*I_color, ip); vpDisplay::displayCross(*I_color, ip, 5, vpColor::green); vpDisplay::flush(*I_color); @@ -702,14 +717,16 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (I) { vpDisplay::displayPoint(*I, ip, vpColor::green); // display target point - } else { + } + else { vpDisplay::displayPoint(*I_color, ip, vpColor::green); // display target point } pose.addPoint(P[i]); // and added to the pose computation point list } if (I) { vpDisplay::flush(*I); - } else { + } + else { vpDisplay::flush(*I_color); } @@ -727,12 +744,14 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (button == vpMouseButton::button1) { isWellInit = true; - } else { + } + else { pose.clearPoint(); vpDisplay::display(*I); vpDisplay::flush(*I); } - } else { + } + else { display(*I_color, m_cMo, m_cam, vpColor::green, 1, true); vpDisplay::displayText(*I_color, 15, 10, "left click to validate, right click to re initialize object", vpColor::red); @@ -745,7 +764,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (button == vpMouseButton::button1) { isWellInit = true; - } else { + } + else { pose.clearPoint(); vpDisplay::display(*I_color); vpDisplay::flush(*I_color); @@ -755,7 +775,8 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage if (I) { vpDisplay::displayFrame(*I, m_cMo, m_cam, 0.05, vpColor::red); - } else { + } + else { vpDisplay::displayFrame(*I_color, m_cMo, m_cam, 0.05, vpColor::red); } @@ -818,7 +839,8 @@ void vpMbTracker::initFromPoints(const vpImage *const I, const vp if (pos == initFile.size() - ext.size() && pos != 0) { ss << initFile; - } else { + } + else { ss << initFile; ss << ".init"; } @@ -929,7 +951,8 @@ void vpMbTracker::initFromPoints(const vpImage *const I, const vp if (I) { init(*I); - } else { + } + else { vpImageConvert::convert(*I_color, m_I); init(m_I); } @@ -1018,7 +1041,8 @@ void vpMbTracker::initFromPoints(const vpImage *const I, const vp if (I) { init(*I); - } else { + } + else { vpImageConvert::convert(*I_color, m_I); init(m_I); } @@ -1064,7 +1088,8 @@ void vpMbTracker::initFromPose(const vpImage *const I, const vpIm if (pos == initFile.size() - ext.size() && pos != 0) { ss << initFile; - } else { + } + else { ss << initFile; ss << ".pos"; } @@ -1083,7 +1108,8 @@ void vpMbTracker::initFromPose(const vpImage *const I, const vpIm if (I) { init(*I); - } else { + } + else { vpImageConvert::convert(*I_color, m_I); init(m_I); } @@ -1438,13 +1464,16 @@ void vpMbTracker::loadModel(const std::string &modelFile, bool verbose, const vp nbCylinders = 0; nbCircles = 0; loadCAOModel(modelFile, vectorOfModelFilename, startIdFace, verbose, true, odTo); - } else if ((*(it - 1) == 'l' && *(it - 2) == 'r' && *(it - 3) == 'w' && *(it - 4) == '.') || - (*(it - 1) == 'L' && *(it - 2) == 'R' && *(it - 3) == 'W' && *(it - 4) == '.')) { + } + else if ((*(it - 1) == 'l' && *(it - 2) == 'r' && *(it - 3) == 'w' && *(it - 4) == '.') || + (*(it - 1) == 'L' && *(it - 2) == 'R' && *(it - 3) == 'W' && *(it - 4) == '.')) { loadVRMLModel(modelFile); - } else { + } + else { throw vpException(vpException::ioError, "Error: File %s doesn't contain a cao or wrl model", modelFile.c_str()); } - } else { + } + else { throw vpException(vpException::ioError, "Error: File %s doesn't exist", modelFile.c_str()); } @@ -1497,7 +1526,8 @@ void vpMbTracker::loadVRMLModel(const std::string &modelFile) sceneGraphVRML2 = tovrml2.getVRML2SceneGraph(); sceneGraphVRML2->ref(); sceneGraph->unref(); - } else { + } + else { sceneGraphVRML2 = SoDB::readAllVRML(&in); if (sceneGraphVRML2 == NULL) { /*return -1;*/ } @@ -1561,7 +1591,8 @@ std::map vpMbTracker::parseParameters(std::string &end if (pos != std::string::npos) { mapOfParams[it->first] = endLine.substr(0, pos); endLine = endLine.substr(pos + 1); - } else { + } + else { parseQuote = false; } } @@ -1662,9 +1693,10 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector> caoVersion; fileId.ignore(std::numeric_limits::max(), fileId.widen('\n')); // skip the rest of the line - } else { + } + else { std::cout << "in vpMbTracker::loadCAOModel() -> Bad parameter header " - "file : use V0, V1, ..."; + "file : use V0, V1, ..."; throw vpException(vpException::badValue, "in vpMbTracker::loadCAOModel() -> Bad parameter " "header file : use V0, V1, ..."); } @@ -1771,12 +1803,14 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) std::lock_guard lock(g_mutex_cout); -#endif std::cout << "> " << caoNbrPoint << " points" << std::endl; } @@ -1842,9 +1874,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) std::lock_guard lock(g_mutex_cout); -#endif std::cout << "> " << caoNbrLine << " lines" << std::endl; } @@ -1903,7 +1933,8 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector key(index1, index2); segmentTemporaryMap[key] = segmentInfo; - } else { + } + else { vpTRACE(" line %d has wrong coordinates.", k); } } @@ -1923,9 +1954,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) std::lock_guard lock(g_mutex_cout); -#endif std::cout << "> " << caoNbrPolygonLine << " polygon lines" << std::endl; } @@ -2012,9 +2041,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) std::lock_guard lock(g_mutex_cout); -#endif std::cout << "> " << caoNbrPolygonPoint << " polygon points" << std::endl; } @@ -2085,9 +2112,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) std::lock_guard lock(g_mutex_cout); -#endif std::cout << "> " << caoNbCylinder << " cylinders" << std::endl; } @@ -2142,7 +2167,8 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) std::lock_guard lock(g_mutex_cout); -#endif std::cout << "> " << caoNbCircle << " circles" << std::endl; } @@ -2217,7 +2241,8 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) std::lock_guard lock(g_mutex_cout); -#endif std::cout << "Global information for " << vpIoTools::getName(modelFile) << " :" << std::endl; std::cout << "Total nb of points : " << nbPoints << std::endl; std::cout << "Total nb of lines : " << nbLines << std::endl; @@ -2240,10 +2263,9 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) + } + else { std::lock_guard lock(g_mutex_cout); -#endif std::cout << "> " << nbPoints << " points" << std::endl; std::cout << "> " << nbLines << " lines" << std::endl; std::cout << "> " << nbPolygonLines << " polygon lines" << std::endl; @@ -2255,7 +2277,8 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vectorget(j); if (!strncmp(face_set->getName().getString(), "cyl", 3)) { extractCylinders(face_set, transform, idFace, name); - } else { + } + else { extractFaces(face_set, transform, idFace, name); } } @@ -2382,7 +2406,8 @@ void vpMbTracker::extractFaces(SoVRMLIndexedFaceSet *face_set, vpHomogeneousMatr initProjectionErrorFaceFromCorners(*(m_projectionErrorFaces.getPolygon().back())); corners.resize(0); } - } else { + } + else { coord = (SoVRMLCoordinate *)(face_set->coord.getValue()); int index = face_set->coordIndex[i]; pointTransformed[0] = coord->point[index].getValue()[0]; @@ -2445,7 +2470,8 @@ void vpMbTracker::extractCylinders(SoVRMLIndexedFaceSet *face_set, vpHomogeneous if (i < (int)corners_c1.size()) { corners_c1[(unsigned int)i] = pt; - } else { + } + else { corners_c2[(unsigned int)i - corners_c1.size()] = pt; } } @@ -2518,7 +2544,8 @@ void vpMbTracker::extractLines(SoVRMLIndexedLineSet *line_set, int &idFace, cons initProjectionErrorFaceFromCorners(*(m_projectionErrorFaces.getPolygon().back())); corners.resize(0); } - } else { + } + else { coord = (SoVRMLCoordinate *)(line_set->coord.getValue()); int index = line_set->coordIndex[i]; point[0] = coord->point[index].getValue()[0]; @@ -2593,7 +2620,8 @@ vpMbTracker::getPolygonFaces(bool orderPolygons, bool useVisibility, bool clipPo if (clipPolygon) { faces.getPolygon()[i]->getRoiClipped(m_cam, roiPts, m_cMo); - } else { + } + else { roiPts = faces.getPolygon()[i]->getRoi(m_cam, m_cMo); } @@ -2606,7 +2634,8 @@ vpMbTracker::getPolygonFaces(bool orderPolygons, bool useVisibility, bool clipPo std::vector polyPts; if (clipPolygon) { faces.getPolygon()[i]->getPolygonClipped(polyPts); - } else { + } + else { for (unsigned int j = 0; j < faces.getPolygon()[i]->nbpt; j++) { polyPts.push_back(faces.getPolygon()[i]->p[j]); } @@ -2650,7 +2679,8 @@ vpMbTracker::getPolygonFaces(bool orderPolygons, bool useVisibility, bool clipPo pairOfPolygonFaces.first = polygonsTmp; pairOfPolygonFaces.second = roisPtTmp; - } else { + } + else { pairOfPolygonFaces.first = polygonsTmp; pairOfPolygonFaces.second = roisPtTmp; } @@ -2673,8 +2703,8 @@ void vpMbTracker::setOgreVisibilityTest(const bool &v) #ifndef VISP_HAVE_OGRE useOgre = false; std::cout << "WARNING: ViSP doesn't have Ogre3D, basic visibility test " - "will be used. setOgreVisibilityTest() set to false." - << std::endl; + "will be used. setOgreVisibilityTest() set to false." + << std::endl; #endif } } @@ -2809,7 +2839,8 @@ void vpMbTracker::computeCovarianceMatrixVVS(const bool isoJoIdentity, const vpC // computation efficiency if (isoJoIdentity) { covarianceMatrix = vpMatrix::computeCovarianceMatrixVVS(cMoPrev, error, L_true, D); - } else { + } + else { covarianceMatrix = vpMatrix::computeCovarianceMatrixVVS(cMoPrev, error, LVJ_true, D); } } @@ -2890,7 +2921,8 @@ void vpMbTracker::computeVVSPoseEstimation(const bool isoJoIdentity, unsigned in v = -m_lambda * LTL.pseudoInverse(LTL.getRows() * std::numeric_limits::epsilon()) * LTR; break; } - } else { + } + else { vpVelocityTwistMatrix cVo; cVo.buildFrom(m_cMo); vpMatrix LVJ = (L * (cVo * oJo)); @@ -2953,7 +2985,7 @@ vpColVector vpMbTracker::getEstimatedDoF() const frame that are estimated by the tracker. When set to 1, all the 6 dof are estimated. - Below we give the correspondance between the index of the vector and the + Below we give the correspondence between the index of the vector and the considered dof: - v[0] = 1 if translation along X is estimated, 0 otherwise; - v[1] = 1 if translation along Y is estimated, 0 otherwise; @@ -2971,7 +3003,8 @@ void vpMbTracker::setEstimatedDoF(const vpColVector &v) // if(v[i] != 0){ if (std::fabs(v[i]) > std::numeric_limits::epsilon()) { oJo[i][i] = 1.0; - } else { + } + else { oJo[i][i] = 0.0; m_isoJoIdentity = false; } @@ -3326,7 +3359,7 @@ void vpMbTracker::addProjectionErrorCircle(const vpPoint &P1, const vpPoint &P2, if ((samePoint(*(ci->p1), P1) && samePoint(*(ci->p2), P2) && samePoint(*(ci->p3), P3)) || (samePoint(*(ci->p1), P1) && samePoint(*(ci->p2), P3) && samePoint(*(ci->p3), P2))) { already_here = - (std::fabs(ci->radius - r) < std::numeric_limits::epsilon() * vpMath::maximum(ci->radius, r)); + (std::fabs(ci->radius - r) < std::numeric_limits::epsilon() * vpMath::maximum(ci->radius, r)); } } @@ -3357,7 +3390,7 @@ void vpMbTracker::addProjectionErrorCylinder(const vpPoint &P1, const vpPoint &P if ((samePoint(*(cy->p1), P1) && samePoint(*(cy->p2), P2)) || (samePoint(*(cy->p1), P2) && samePoint(*(cy->p2), P1))) { already_here = - (std::fabs(cy->radius - r) < std::numeric_limits::epsilon() * vpMath::maximum(cy->radius, r)); + (std::fabs(cy->radius - r) < std::numeric_limits::epsilon() * vpMath::maximum(cy->radius, r)); } } @@ -3566,7 +3599,8 @@ void vpMbTracker::projectionErrorVisibleFace(unsigned int width, unsigned int he if (!useOgre) { m_projectionErrorFaces.setVisible(width, height, m_projectionErrorCam, _cMo, angleAppears, angleDisappears, changed); - } else { + } + else { #ifdef VISP_HAVE_OGRE m_projectionErrorFaces.setVisibleOgre(width, height, m_projectionErrorCam, _cMo, angleAppears, angleDisappears, changed); @@ -3648,7 +3682,8 @@ void vpMbTracker::projectionErrorInitMovingEdge(const vpImage &I, l->updateTracked(); if (l->meline.empty() && l->isTracked()) l->initMovingEdge(I, _cMo, doNotTrack, m_mask); - } else { + } + else { l->setVisible(false); for (size_t a = 0; a < l->meline.size(); a++) { if (l->meline[a] != NULL) @@ -3683,7 +3718,8 @@ void vpMbTracker::projectionErrorInitMovingEdge(const vpImage &I, if (cy->isTracked()) cy->initMovingEdge(I, _cMo, doNotTrack, m_mask); } - } else { + } + else { cy->setVisible(false); if (cy->meline1 != NULL) delete cy->meline1; @@ -3716,7 +3752,8 @@ void vpMbTracker::projectionErrorInitMovingEdge(const vpImage &I, if (ci->isTracked()) ci->initMovingEdge(I, _cMo, doNotTrack, m_mask); } - } else { + } + else { ci->setVisible(false); if (ci->meEllipse != NULL) delete ci->meEllipse; @@ -3738,7 +3775,8 @@ void vpMbTracker::loadConfigFile(const std::string &configFile, bool verbose) std::cout << " *********** Parsing XML for ME projection error ************ " << std::endl; } xmlp.parse(configFile); - } catch (...) { + } + catch (...) { throw vpException(vpException::ioError, "Cannot open XML file \"%s\"", configFile.c_str()); } diff --git a/modules/tracker/mbt/test/generic-with-dataset/perfGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/perfGenericTracker.cpp index 2b3e3f35bf..da5bb48cb8 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/perfGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/perfGenericTracker.cpp @@ -57,10 +57,8 @@ template bool read_data(const std::string &input_directory, int cpt, const vpCameraParameters &cam_depth, vpImage &I, vpImage &I_depth, std::vector &pointcloud, vpHomogeneousMatrix &cMo) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) static_assert(std::is_same::value || std::is_same::value, "Template function supports only unsigned char and vpRGBa images!"); -#endif #if VISP_HAVE_DATASET_VERSION >= 0x030600 std::string ext("png"); #else @@ -130,7 +128,7 @@ TEST_CASE("Benchmark generic tracker", "[benchmark]") vpMbGenericTracker tracker(tracker_type); const std::string input_directory = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "mbt-depth/Castle-simu"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "mbt-depth/Castle-simu"); const std::string configFileCam1 = input_directory + std::string("/Config/chateau.xml"); const std::string configFileCam2 = input_directory + std::string("/Config/chateau_depth.xml"); REQUIRE(vpIoTools::checkFilename(configFileCam1)); @@ -191,16 +189,16 @@ TEST_CASE("Benchmark generic tracker", "[benchmark]") { std::vector > mapOfTrackerTypes; mapOfTrackerTypes.push_back( - {{"Camera1", vpMbGenericTracker::EDGE_TRACKER}, {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER}}); + { {"Camera1", vpMbGenericTracker::EDGE_TRACKER}, {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER} }); mapOfTrackerTypes.push_back( - {{"Camera1", vpMbGenericTracker::EDGE_TRACKER}, {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER}}); + { {"Camera1", vpMbGenericTracker::EDGE_TRACKER}, {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER} }); #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) mapOfTrackerTypes.push_back( - {{"Camera1", vpMbGenericTracker::KLT_TRACKER}, {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER}}); - mapOfTrackerTypes.push_back({{"Camera1", vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER}, - {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER}}); - mapOfTrackerTypes.push_back({{"Camera1", vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER}, - {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER}}); + { {"Camera1", vpMbGenericTracker::KLT_TRACKER}, {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER} }); + mapOfTrackerTypes.push_back({ {"Camera1", vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER}, + {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER} }); + mapOfTrackerTypes.push_back({ {"Camera1", vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER}, + {"Camera2", vpMbGenericTracker::DEPTH_DENSE_TRACKER} }); #endif std::vector benchmarkNames = { @@ -289,7 +287,7 @@ TEST_CASE("Benchmark generic tracker", "[benchmark]") return cMo; }; #else - } + } #endif vpPoseVector pose_est(cMo); @@ -304,9 +302,9 @@ TEST_CASE("Benchmark generic tracker", "[benchmark]") const double max_rotation_error = 0.03; CHECK(sqrt(t_err.sumSquare()) < max_translation_error); CHECK(sqrt(tu_err.sumSquare()) < max_rotation_error); - } } - } // if (runBenchmark) + } +} // if (runBenchmark) } int main(int argc, char *argv[]) @@ -316,11 +314,11 @@ int main(int argc, char *argv[]) // Build a new parser on top of Catch's using namespace Catch::clara; auto cli = session.cli() // Get Catch's composite command line parser - | Opt(runBenchmark) // bind variable to a new option, with a hint string - ["--benchmark"] // the option names it will respond to - ("run benchmark comparing naive code with ViSP implementation"); // description string for the help output + | Opt(runBenchmark) // bind variable to a new option, with a hint string + ["--benchmark"] // the option names it will respond to + ("run benchmark comparing naive code with ViSP implementation"); // description string for the help output - // Now pass the new composite back to Catch so it uses that +// Now pass the new composite back to Catch so it uses that session.cli(cli); // Let Catch (using Clara) parse the command line diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp index 709128e746..2167f43c26 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp @@ -46,9 +46,7 @@ #if defined(VISP_HAVE_MODULE_MBT) && \ (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include -#endif #include #include @@ -187,10 +185,8 @@ template bool read_data(const std::string &input_directory, int cpt, const vpCameraParameters &cam_depth, vpImage &I, vpImage &I_depth, std::vector &pointcloud, vpHomogeneousMatrix &cMo) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) static_assert(std::is_same::value || std::is_same::value, "Template function supports only unsigned char and vpRGBa images!"); -#endif #if VISP_HAVE_DATASET_VERSION >= 0x030600 std::string ext("png"); #else @@ -258,10 +254,8 @@ template bool run(const std::string &input_directory, bool opt_click_allowed, bool opt_display, bool useScanline, int trackerType_image, int opt_lastFrame, bool use_depth, bool use_mask, bool save) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) static_assert(std::is_same::value || std::is_same::value, "Template function supports only unsigned char and vpRGBa images!"); -#endif // Initialise a display #if defined(VISP_HAVE_X11) vpDisplayX display1, display2; @@ -655,7 +649,7 @@ bool run(const std::string &input_directory, bool opt_click_allowed, bool opt_di } } // namespace -int main(int argc, const char *argv []) +int main(int argc, const char *argv[]) { try { std::string env_ipath; @@ -681,7 +675,7 @@ int main(int argc, const char *argv []) // Read the command line options if (!getOptions(argc, argv, opt_ipath, opt_click_allowed, opt_display, opt_save, useScanline, trackerType_image, - opt_lastFrame, use_depth, use_mask, use_color_image)) { + opt_lastFrame, use_depth, use_mask, use_color_image)) { return EXIT_FAILURE; } diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp index 6c5501226e..bcdbe470f0 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp @@ -43,12 +43,9 @@ #include #include -#if defined(VISP_HAVE_MODULE_MBT) && \ - (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) +#if defined(VISP_HAVE_MODULE_MBT) && (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include -#endif #include #include @@ -166,10 +163,8 @@ template bool read_data(const std::string &input_directory, int cpt, const vpCameraParameters &cam_depth, vpImage &I, vpImage &I_depth, std::vector &pointcloud, vpHomogeneousMatrix &cMo) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) static_assert(std::is_same::value || std::is_same::value, "Template function supports only unsigned char and vpRGBa images!"); -#endif #if VISP_HAVE_DATASET_VERSION >= 0x030600 std::string ext("png"); #else @@ -233,10 +228,8 @@ template bool run(vpImage &I, const std::string &input_directory, bool opt_click_allowed, bool opt_display, bool useScanline, int opt_lastFrame, bool use_mask) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) static_assert(std::is_same::value || std::is_same::value, "Template function supports only unsigned char and vpRGBa images!"); -#endif // Initialise a display #if defined(VISP_HAVE_X11) vpDisplayX display1, display2; @@ -258,29 +251,29 @@ bool run(vpImage &I, const std::string &input_directory, bool opt_click_al tracker.loadConfigFile(input_directory + "/Config/chateau_depth.xml"); #if 0 // Corresponding parameters manually set to have an example code - { - vpCameraParameters cam_depth; - cam_depth.initPersProjWithoutDistortion(700.0, 700.0, 320.0, 240.0); - tracker.setCameraParameters(cam_depth); - } - // Depth - tracker.setDepthNormalFeatureEstimationMethod(vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION); - tracker.setDepthNormalPclPlaneEstimationMethod(2); - tracker.setDepthNormalPclPlaneEstimationRansacMaxIter(200); - tracker.setDepthNormalPclPlaneEstimationRansacThreshold(0.001); - tracker.setDepthNormalSamplingStep(2, 2); + { + vpCameraParameters cam_depth; + cam_depth.initPersProjWithoutDistortion(700.0, 700.0, 320.0, 240.0); + tracker.setCameraParameters(cam_depth); + } + // Depth + tracker.setDepthNormalFeatureEstimationMethod(vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION); + tracker.setDepthNormalPclPlaneEstimationMethod(2); + tracker.setDepthNormalPclPlaneEstimationRansacMaxIter(200); + tracker.setDepthNormalPclPlaneEstimationRansacThreshold(0.001); + tracker.setDepthNormalSamplingStep(2, 2); - tracker.setDepthDenseSamplingStep(4, 4); + tracker.setDepthDenseSamplingStep(4, 4); #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) - tracker.setKltMaskBorder(5); + tracker.setKltMaskBorder(5); #endif - tracker.setAngleAppear(vpMath::rad(85.0)); - tracker.setAngleDisappear(vpMath::rad(89.0)); - tracker.setNearClippingDistance(0.01); - tracker.setFarClippingDistance(2.0); - tracker.setClipping(tracker.getClipping() | vpMbtPolygon::FOV_CLIPPING); + tracker.setAngleAppear(vpMath::rad(85.0)); + tracker.setAngleDisappear(vpMath::rad(89.0)); + tracker.setNearClippingDistance(0.01); + tracker.setFarClippingDistance(2.0); + tracker.setClipping(tracker.getClipping() | vpMbtPolygon::FOV_CLIPPING); #endif tracker.loadModel(input_directory + "/Models/chateau.cao"); vpHomogeneousMatrix T; @@ -391,7 +384,7 @@ bool run(vpImage &I, const std::string &input_directory, bool opt_click_al const double tu_thresh = useScanline ? 0.5 : 0.4; if (!use_mask && (t_err2 > t_thresh || tu_err2 > tu_thresh)) { // no accuracy test with mask std::cerr << "Pose estimated exceeds the threshold (t_thresh = " << t_thresh << ", tu_thresh = " << tu_thresh - << ")!" << std::endl; + << ")!" << std::endl; std::cout << "t_err: " << t_err2 << " ; tu_err: " << tu_err2 << std::endl; correct_accuracy = false; } @@ -430,8 +423,8 @@ bool run(vpImage &I, const std::string &input_directory, bool opt_click_al if (!time_vec.empty()) std::cout << "Computation time, Mean: " << vpMath::getMean(time_vec) - << " ms ; Median: " << vpMath::getMedian(time_vec) << " ms ; Std: " << vpMath::getStdev(time_vec) << " ms" - << std::endl; + << " ms ; Median: " << vpMath::getMedian(time_vec) << " ms ; Std: " << vpMath::getStdev(time_vec) << " ms" + << std::endl; if (!vec_err_t.empty()) std::cout << "Max translation error: " << *std::max_element(vec_err_t.begin(), vec_err_t.end()) << std::endl; @@ -479,15 +472,15 @@ int main(int argc, const char *argv[]) usage(argv[0], NULL); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; return EXIT_FAILURE; } std::string input_directory = - vpIoTools::createFilePath(!opt_ipath.empty() ? opt_ipath : env_ipath, "mbt-depth/Castle-simu"); + vpIoTools::createFilePath(!opt_ipath.empty() ? opt_ipath : env_ipath, "mbt-depth/Castle-simu"); if (!vpIoTools::checkDirectory(input_directory)) { std::cerr << "ViSP-images does not contain the folder: " << input_directory << "!" << std::endl; return EXIT_SUCCESS; @@ -496,11 +489,13 @@ int main(int argc, const char *argv[]) if (use_color_image) { vpImage I_color; return run(I_color, input_directory, opt_click_allowed, opt_display, useScanline, opt_lastFrame, use_mask); - } else { + } + else { vpImage I_gray; return run(I_gray, input_directory, opt_click_allowed, opt_display, useScanline, opt_lastFrame, use_mask); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/tracker/me/include/visp3/me/vpMe.h b/modules/tracker/me/include/visp3/me/vpMe.h index 5cb1b64151..a35e03254f 100644 --- a/modules/tracker/me/include/visp3/me/vpMe.h +++ b/modules/tracker/me/include/visp3/me/vpMe.h @@ -174,12 +174,10 @@ class VISP_EXPORT vpMe */ vpMe &operator=(const vpMe &me); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! * Move operator. */ vpMe &operator=(const vpMe &&me); -#endif /*! * Check sample step wrt min value. diff --git a/modules/tracker/me/include/visp3/me/vpMeEllipse.h b/modules/tracker/me/include/visp3/me/vpMeEllipse.h index cf60d79183..e71ffad56b 100644 --- a/modules/tracker/me/include/visp3/me/vpMeEllipse.h +++ b/modules/tracker/me/include/visp3/me/vpMeEllipse.h @@ -549,11 +549,7 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker * \exception vpTrackingException::initializationError : Moving edges not * initialized. */ -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) virtual void sample(const vpImage &I, bool doNotTrack = false) override; -#else - virtual void sample(const vpImage &I, bool doNotTrack = false); -#endif /*! * Compute the \f$ theta \f$ angle for each vpMeSite. diff --git a/modules/tracker/me/include/visp3/me/vpMeLine.h b/modules/tracker/me/include/visp3/me/vpMeLine.h index fa03bdc306..0ba0cb1cf6 100644 --- a/modules/tracker/me/include/visp3/me/vpMeLine.h +++ b/modules/tracker/me/include/visp3/me/vpMeLine.h @@ -213,11 +213,7 @@ class VISP_EXPORT vpMeLine : public vpMeTracker * \exception vpTrackingException::initializationError : Moving edges not * initialized. */ -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) virtual void sample(const vpImage &I, bool doNotTrack = false) override; -#else - virtual void sample(const vpImage &I, bool doNotTrack = false); -#endif /*! * Resample the line if the number of sample is less than 80% of the diff --git a/modules/tracker/me/src/moving-edges/vpMe.cpp b/modules/tracker/me/src/moving-edges/vpMe.cpp index 29cd610cb8..f58df242ab 100644 --- a/modules/tracker/me/src/moving-edges/vpMe.cpp +++ b/modules/tracker/me/src/moving-edges/vpMe.cpp @@ -405,7 +405,6 @@ vpMe &vpMe::operator=(const vpMe &me) return *this; } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMe &vpMe::operator=(const vpMe &&me) { if (m_mask != NULL) { @@ -430,7 +429,6 @@ vpMe &vpMe::operator=(const vpMe &&me) initMask(); return *this; } -#endif vpMe::~vpMe() { diff --git a/modules/tracker/me/test/testJsonMe.cpp b/modules/tracker/me/test/testJsonMe.cpp index 1874ae1a95..8d0ef208f5 100644 --- a/modules/tracker/me/test/testJsonMe.cpp +++ b/modules/tracker/me/test/testJsonMe.cpp @@ -39,7 +39,7 @@ #include -#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_CATCH2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_CATCH2) #include #include @@ -95,7 +95,7 @@ class RandomMeGenerator : public Catch::Generators::IGenerator vpMe current; public: - RandomMeGenerator() : m_rand(std::random_device{}()), m_dist(0.0, 1.0), m_int_dist(1, 10) + RandomMeGenerator() : m_rand(std::random_device {}()), m_dist(0.0, 1.0), m_int_dist(1, 10) { static_cast(next()); } @@ -150,11 +150,11 @@ SCENARIO("Serializing and deserializing a single vpMe", "[json]") const auto testInt = [&j, &me](const std::string &key, std::function setter, std::function getter) -> void { testOptionalProperty(j, { key }, me, setter, getter, [](int v) -> int { return v - 1; }); - }; + }; const auto testDouble = [&j, &me](const std::string &key, std::function setter, std::function getter) -> void { testOptionalProperty(j, { key }, me, setter, getter, [](double v) -> double { return v + 1.0; }); - }; + }; WHEN("Removing threshold") { testDouble("threshold", &vpMe::setThreshold, &vpMe::getThreshold); } WHEN("Removing mu1 and mu2") @@ -175,7 +175,7 @@ SCENARIO("Serializing and deserializing a single vpMe", "[json]") } } -int main(int argc, char *argv []) +int main(int argc, char *argv[]) { Catch::Session session; // There must be exactly one instance session.applyCommandLine(argc, argv); diff --git a/modules/vision/include/visp3/vision/vpPose.h b/modules/vision/include/visp3/vision/vpPose.h index c45a347f39..abd2644b59 100644 --- a/modules/vision/include/visp3/vision/vpPose.h +++ b/modules/vision/include/visp3/vision/vpPose.h @@ -52,9 +52,7 @@ #include #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include -#endif #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) && \ (!defined(_MSC_VER) || ((VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) && (_MSC_VER >= 1911))) @@ -617,7 +615,7 @@ class VISP_EXPORT vpPose * Match a vector p2D of 2D point (x,y) and a vector p3D of 3D points * (X,Y,Z) using the Ransac algorithm. * - * At least numberOfInlierToReachAConsensus of true correspondance are required + * At least numberOfInlierToReachAConsensus of true correspondence are required * to validate the pose * * The inliers are given in a vector of vpPoint listInliers. diff --git a/modules/vision/include/visp3/vision/vpPoseFeatures.h b/modules/vision/include/visp3/vision/vpPoseFeatures.h index 2f2ca927b4..5a70f55e9c 100644 --- a/modules/vision/include/visp3/vision/vpPoseFeatures.h +++ b/modules/vision/include/visp3/vision/vpPoseFeatures.h @@ -63,8 +63,6 @@ #include #include - -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #ifndef DOXYGEN_SHOULD_SKIP_THIS @@ -367,7 +365,6 @@ class vpPoseSpecificFeatureTemplateObject : public vpPoseSpecificFeature } }; #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS -#endif // (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! * \class vpPoseFeatures @@ -477,7 +474,6 @@ class VISP_EXPORT vpPoseFeatures */ void addFeatureSegment(vpPoint &, vpPoint &); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! * Add a specific feature for the pose computation. */ @@ -489,7 +485,6 @@ class VISP_EXPORT vpPoseFeatures */ template void addSpecificFeature(ObjType *obj, RetType(ObjType:: *fct_ptr)(ArgsFunc...), Args &&...args); -#endif /*! * Clear all the features @@ -616,11 +611,8 @@ class VISP_EXPORT vpPoseFeatures std::vector > m_featureLine_DuoLineInt_List; // vpFeatureSegment std::vector > m_featureSegment_DuoPoints_list; - -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) // Specific features std::vector m_featureSpecific_list; -#endif /*! * Get the error vector and L matrix from all the features. @@ -649,7 +641,6 @@ class VISP_EXPORT vpPoseFeatures void computePoseRobustVVS(vpHomogeneousMatrix &cMo); }; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! * Add a specific feature for the pose computation. * @@ -691,12 +682,10 @@ class VISP_EXPORT vpPoseFeatures * vpFeatureLine fl; * void (*ptr)(vpFeaturePoint&, const vpPoint&) = &vpFeatureBuilder::create; * - * #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) * pose.addSpecificFeature(ptr, fp, pts[0]); * pose.addSpecificFeature(&vp_createPoint, fp, pts[1]); * pose.addSpecificFeature(&vp_createTwoPoint, fp, pts[2], pts[3]); * pose.addSpecificFeature(&vp_createLine, fl, line); - * #endif * * //... Pose Computation * @@ -773,11 +762,9 @@ void vpPoseFeatures::addSpecificFeature(RetType(*fct_ptr)(ArgsFunc...), Args &&. * void (vp_createClass::*ptrClassLine)(vpFeatureLine &, const vpLine &) * = &vp_createClass::vp_createLine; * - * #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) * pose.addSpecificFeature(&cpClass, ptrClassPoint, fp, pts[0]); * pose.addSpecificFeature(&cpClass, ptrClassTwoPoint, fp, pts[1], pts[2]); * pose.addSpecificFeature(&cpClass, ptrClassLine, fl, line); - * #endif * * //... Pose Computation * @@ -799,7 +786,6 @@ void vpPoseFeatures::addSpecificFeature(ObjType *obj, RetType(ObjType:: *fct_ptr if (m_featureSpecific_list.size() > m_maxSize) m_maxSize = static_cast(m_featureSpecific_list.size()); } -#endif #endif //#ifdef VISP_HAVE_MODULE_VISUAL_FEATURES diff --git a/modules/vision/src/pose-estimation/vpPoseFeatures.cpp b/modules/vision/src/pose-estimation/vpPoseFeatures.cpp index 958bf2b998..2550ab73ba 100644 --- a/modules/vision/src/pose-estimation/vpPoseFeatures.cpp +++ b/modules/vision/src/pose-estimation/vpPoseFeatures.cpp @@ -81,11 +81,9 @@ void vpPoseFeatures::clear() delete m_featureSegment_DuoPoints_list[(unsigned int)i].desiredFeature; m_featureSegment_DuoPoints_list.clear(); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) for (int i = (int)m_featureSpecific_list.size() - 1; i >= 0; i--) delete m_featureSpecific_list[(unsigned int)i]; m_featureSpecific_list.clear(); -#endif m_maxSize = 0; m_totalSize = 0; @@ -305,14 +303,12 @@ void vpPoseFeatures::error_and_interaction(vpHomogeneousMatrix &cMo, vpColVector L.stack(fs.interaction()); } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) //--------------Specific Feature-------------- if (i < m_featureSpecific_list.size()) { m_featureSpecific_list[i]->createCurrent(cMo); err.stack(m_featureSpecific_list[i]->error()); L.stack(m_featureSpecific_list[i]->currentInteraction()); } -#endif } } diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index 2ff1b5a4c2..cd470e4ec4 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -49,9 +49,7 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include -#endif #define eps 1e-6 @@ -355,15 +353,10 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo throw(vpPoseException(vpPoseException::notInitializedError, "Not enough point to compute the pose")); } -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) unsigned int nbThreads = 1; bool executeParallelVersion = useParallelRansac; -#else - bool executeParallelVersion = false; -#endif if (executeParallelVersion) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) if (nbParallelRansacThreads <= 0) { // Get number of CPU threads nbThreads = std::thread::hardware_concurrency(); @@ -375,13 +368,11 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo else { nbThreads = nbParallelRansacThreads; } -#endif } bool foundSolution = false; if (executeParallelVersion) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) std::vector threadpool; std::vector ransacWorkers; @@ -422,7 +413,6 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo } foundSolution = successRansac; -#endif } else { // Sequential RANSAC diff --git a/modules/vision/test/pose/testFindMatch.cpp b/modules/vision/test/pose/testFindMatch.cpp index 4dbd410b7e..60bd02e72f 100644 --- a/modules/vision/test/pose/testFindMatch.cpp +++ b/modules/vision/test/pose/testFindMatch.cpp @@ -29,7 +29,7 @@ * * Description: * Compute the pose of a 3D object using the Dementhon method. Assuming that - * the correspondance between 2D points and 3D points is not done, we use + * the correspondence between 2D points and 3D points is not done, we use * the RANSAC algorithm to achieve this task */ diff --git a/modules/vision/test/pose/testPoseFeatures.cpp b/modules/vision/test/pose/testPoseFeatures.cpp index 56d6e32548..de359cc12d 100644 --- a/modules/vision/test/pose/testPoseFeatures.cpp +++ b/modules/vision/test/pose/testPoseFeatures.cpp @@ -52,13 +52,12 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) class vp_createPointClass { public: int value; - vp_createPointClass() : value(0) {} + vp_createPointClass() : value(0) { } int vp_createPoint(vpFeaturePoint &fp, const vpPoint &v) { @@ -72,7 +71,6 @@ void vp_createPoint(vpFeaturePoint &fp, const vpPoint &v) { vpFeatureBuilder::cr void vp_createLine(vpFeatureLine &fp, const vpLine &v) { vpFeatureBuilder::create(fp, v); } #endif -#endif int test_pose(bool use_robust) { @@ -153,7 +151,6 @@ int test_pose(bool use_robust) pose.addFeatureEllipse(circle); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpFeaturePoint fp; vpFeatureLine fl; vpFeatureSegment fs; @@ -163,7 +160,6 @@ int test_pose(bool use_robust) pose.addSpecificFeature(&cpClass, ptrClass, fp, pts[1]); pose.addSpecificFeature(&vp_createLine, fl, line); pose.addSpecificFeature(ptr, fs, pts[3], pts[4]); -#endif pose.setVerbose(true); pose.setLambda(0.6); @@ -191,7 +187,7 @@ int test_pose(bool use_robust) std::cout << "\nResulting covariance (Diag): " << std::endl; vpMatrix covariance = pose.getCovarianceMatrix(); std::cout << covariance[0][0] << " " << covariance[1][1] << " " << covariance[2][2] << " " << covariance[3][3] << " " - << covariance[4][4] << " " << covariance[5][5] << " " << std::endl; + << covariance[4][4] << " " << covariance[5][5] << " " << std::endl; int test_fail = 0; for (unsigned int i = 0; i < 6; i++) { @@ -215,7 +211,8 @@ int main() return EXIT_FAILURE; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/vision/test/pose/testPoseRansac.cpp b/modules/vision/test/pose/testPoseRansac.cpp index 8c7f8213c0..9dd4cc8330 100644 --- a/modules/vision/test/pose/testPoseRansac.cpp +++ b/modules/vision/test/pose/testPoseRansac.cpp @@ -29,7 +29,7 @@ * * Description: * Compute the pose of a 3D object using the Dementhon method. Assuming that - * the correspondance between 2D points and 3D points is not done, we use + * the correspondence between 2D points and 3D points is not done, we use * the RANSAC algorithm to achieve this task */ diff --git a/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp b/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp index 2f4663685a..af960a6ce1 100644 --- a/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp +++ b/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp @@ -9,7 +9,7 @@ int main() { -#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) { std::cout << "From OpenCV to ViSP conversion" << std::endl; //! [Create OpenCV matrix] @@ -27,7 +27,7 @@ int main() { std::cout << "From ViSP to OpenCV conversion" << std::endl; //! [Create ViSP matrix] - vpMatrix M(3, 4, {1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}); + vpMatrix M(3, 4, { 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12 }); std::cout << "M: \n" << M << std::endl; //! [Create ViSP matrix] 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 f8c9564782..e7e088ad36 100644 --- a/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp @@ -20,14 +20,16 @@ int main(int argc, char **argv) for (int i = 0; i < argc; i++) { if (std::string(argv[i]) == "--camera_index" && i + 1 < argc) { opt_camera_index = atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--square_width" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--square_width" && i + 1 < argc) { opt_square_width = atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + 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 ((2 * 10000) + (31 * 100) + 0)) (void)argc; (void)argv; diff --git a/tutorial/grabber/tutorial-grabber-1394.cpp b/tutorial/grabber/tutorial-grabber-1394.cpp index 76af5f9edc..fe7bfddf5c 100644 --- a/tutorial/grabber/tutorial-grabber-1394.cpp +++ b/tutorial/grabber/tutorial-grabber-1394.cpp @@ -8,57 +8,57 @@ void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--change-settings]" - << " [--seqname ]" - << " [--record ]" - << " [--no-display]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--change-settings]" + << " [--seqname ]" + << " [--record ]" + << " [--no-display]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --change-settings" << std::endl - << " Force camera settings to acquire 640x480 images in M0NO8 at 60 fps." << std::endl - << std::endl - << " --seqname " << std::endl - << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl - << " Default: empty." << std::endl - << std::endl - << " --record " << std::endl - << " Allowed values for mode are:" << std::endl - << " 0: record all the captures images (continuous mode)," << std::endl - << " 1: record only images selected by a user click (single shot mode)." << std::endl - << " Default mode: 0" << std::endl - << std::endl - << " --no-display" << std::endl - << " Disable displaying captured images." << std::endl - << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." - << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --change-settings" << std::endl + << " Force camera settings to acquire 640x480 images in M0NO8 at 60 fps." << std::endl + << std::endl + << " --seqname " << std::endl + << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl + << " Default: empty." << std::endl + << std::endl + << " --record " << std::endl + << " Allowed values for mode are:" << std::endl + << " 0: record all the captures images (continuous mode)," << std::endl + << " 1: record only images selected by a user click (single shot mode)." << std::endl + << " Default mode: 0" << std::endl + << std::endl + << " --no-display" << std::endl + << " Disable displaying captured images." << std::endl + << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." + << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to visualize images:" << std::endl - << " " << argv[0] << std::endl - << std::endl - << " Examples to record a sequence:" << std::endl - << " " << argv[0] << " --seqname I%04d.png" << std::endl - << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl - << std::endl - << " Examples to record single shot images:\n" - << " " << argv[0] << " --seqname I%04d.png --record 1\n" - << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl - << std::endl; + << " Example to visualize images:" << std::endl + << " " << argv[0] << std::endl + << std::endl + << " Examples to record a sequence:" << std::endl + << " " << argv[0] << " --seqname I%04d.png" << std::endl + << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl + << std::endl + << " Examples to record single shot images:\n" + << " " << argv[0] << " --seqname I%04d.png --record 1\n" + << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_DC1394) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_DC1394) try { std::string opt_seqname; int opt_record_mode = 0; @@ -68,18 +68,23 @@ int main(int argc, const char *argv[]) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--change-settings") { opt_change_settings = true; - } else if (std::string(argv[i]) == "--seqname") { + } + else if (std::string(argv[i]) == "--seqname") { opt_seqname = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--record") { + } + else if (std::string(argv[i]) == "--record") { opt_record_mode = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--no-display") { + } + else if (std::string(argv[i]) == "--no-display") { opt_display = false; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -94,7 +99,7 @@ int main(int argc, const char *argv[]) std::cout << "Display : " << (opt_display ? "enabled" : "disabled") << std::endl; std::string text_record_mode = - std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); + std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); if (!opt_seqname.empty()) { std::cout << text_record_mode << std::endl; @@ -112,8 +117,9 @@ int main(int argc, const char *argv[]) try { g.setVideoMode(vp1394TwoGrabber::vpVIDEO_MODE_640x480_MONO8); g.setFramerate(vp1394TwoGrabber::vpFRAMERATE_60); - } catch (...) { // If settings are not available just catch execption to - // continue with default settings + } + catch (...) { // If settings are not available just catch execption to + // continue with default settings std::cout << "Warning: cannot modify camera settings" << std::endl; } } @@ -164,7 +170,8 @@ int main(int argc, const char *argv[]) if (d) { delete d; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } #else @@ -173,8 +180,5 @@ int main(int argc, const char *argv[]) #ifndef VISP_HAVE_DC1394 std::cout << "Install libdc1394, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif } diff --git a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp index 5e685b52ef..d663548c24 100644 --- a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp +++ b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp @@ -9,61 +9,61 @@ void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--device ]" - << " [--type ]" - << " [--seqname ]" - << " [--record ]" - << " [--no-display]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--device ]" + << " [--type ]" + << " [--seqname ]" + << " [--record ]" + << " [--no-display]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --device " << std::endl - << " Camera device index in range [0...9]. Set 0 to dial with the first camera," << std::endl - << " and 1 to dial with the second camera attached to the computer." << std::endl - << " Default: 0." << std::endl - << std::endl - << " --type " << std::endl - << " Camera device type: GigE or USB" << std::endl - << " Default: GigE" << std::endl - << std::endl - << " --seqname " << std::endl - << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl - << " Default: empty." << std::endl - << std::endl - << " --record " << std::endl - << " Allowed values for mode are:" << std::endl - << " 0: record all the captures images (continuous mode)," << std::endl - << " 1: record only images selected by a user click (single shot mode)." << std::endl - << " Default mode: 0" << std::endl - << std::endl - << " --no-display" << std::endl - << " Disable displaying captured images." << std::endl - << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." - << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --device " << std::endl + << " Camera device index in range [0...9]. Set 0 to dial with the first camera," << std::endl + << " and 1 to dial with the second camera attached to the computer." << std::endl + << " Default: 0." << std::endl + << std::endl + << " --type " << std::endl + << " Camera device type: GigE or USB" << std::endl + << " Default: GigE" << std::endl + << std::endl + << " --seqname " << std::endl + << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl + << " Default: empty." << std::endl + << std::endl + << " --record " << std::endl + << " Allowed values for mode are:" << std::endl + << " 0: record all the captures images (continuous mode)," << std::endl + << " 1: record only images selected by a user click (single shot mode)." << std::endl + << " Default mode: 0" << std::endl + << std::endl + << " --no-display" << std::endl + << " Disable displaying captured images." << std::endl + << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." + << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to visualize images:" << std::endl - << " " << argv[0] << std::endl - << std::endl - << " Example to visualize images from a second camera GigE:" << std::endl - << " " << argv[0] << " --device 1 --type GigE" << std::endl - << std::endl - << " Examples to record a sequence:" << std::endl - << " " << argv[0] << " --seqname I%04d.png" << std::endl - << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl - << std::endl - << " Examples to record single shot images:\n" - << " " << argv[0] << " --seqname I%04d.png --record 1\n" - << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl - << std::endl; + << " Example to visualize images:" << std::endl + << " " << argv[0] << std::endl + << std::endl + << " Example to visualize images from a second camera GigE:" << std::endl + << " " << argv[0] << " --device 1 --type GigE" << std::endl + << std::endl + << " Examples to record a sequence:" << std::endl + << " " << argv[0] << " --seqname I%04d.png" << std::endl + << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl + << std::endl + << " Examples to record single shot images:\n" + << " " << argv[0] << " --seqname I%04d.png --record 1\n" + << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } /*! @@ -73,7 +73,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_PYLON) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PYLON) try { unsigned int opt_device = 0; std::string opt_type("GigE"); @@ -90,18 +90,23 @@ int main(int argc, const char *argv[]) if (std::string(argv[i]) == "--type") { opt_type = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--seqname") { + } + else if (std::string(argv[i]) == "--seqname") { opt_seqname = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--record") { + } + else if (std::string(argv[i]) == "--record") { opt_record_mode = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--no-display") { + } + else if (std::string(argv[i]) == "--no-display") { opt_display = false; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -116,7 +121,7 @@ int main(int argc, const char *argv[]) std::cout << "Display : " << (opt_display ? "enabled" : "disabled") << std::endl; std::string text_record_mode = - std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); + std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); if (!opt_seqname.empty()) { std::cout << text_record_mode << std::endl; @@ -131,10 +136,12 @@ int main(int argc, const char *argv[]) if (opt_type == "GigE" || opt_type == "gige") { g = factory.createPylonGrabber(vpPylonFactory::BASLER_GIGE); std::cout << "Opening Basler GigE camera: " << opt_device << std::endl; - } else if (opt_type == "USB" || opt_type == "usb") { + } + else if (opt_type == "USB" || opt_type == "usb") { g = factory.createPylonGrabber(vpPylonFactory::BASLER_USB); std::cout << "Opening Basler USB camera: " << opt_device << std::endl; - } else { + } + else { std::cout << "Error: only Basler GigE or USB cameras are supported." << std::endl; return EXIT_SUCCESS; } @@ -185,7 +192,8 @@ int main(int argc, const char *argv[]) if (d) { delete d; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } #else @@ -194,8 +202,5 @@ int main(int argc, const char *argv[]) #ifndef VISP_HAVE_PYLON std::cout << "Install Basler Pylon SDK, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif } diff --git a/tutorial/grabber/tutorial-grabber-bebop2.cpp b/tutorial/grabber/tutorial-grabber-bebop2.cpp index 627c9ce686..7d5af10bd6 100644 --- a/tutorial/grabber/tutorial-grabber-bebop2.cpp +++ b/tutorial/grabber/tutorial-grabber-bebop2.cpp @@ -11,59 +11,59 @@ void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--ip
]" - << " [--hd-resolution]" - << " [--seqname ]" - << " [--record ]" - << " [--no-display]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--ip
]" + << " [--hd-resolution]" + << " [--seqname ]" + << " [--record ]" + << " [--no-display]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --ip
" << std::endl - << " IP address of the drone to which you want to connect." << std::endl - << " Default: 192.168.42.1" << std::endl - << std::endl - << " --hd-resolution" << std::endl - << " Enables HD 720p images instead of default 480p." << std::endl - << " Caution : The camera settings are different depending on whether the resolution is 720p or 480p." - << std::endl - << std::endl - << " --seqname " << std::endl - << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl - << " Default: empty." << std::endl - << std::endl - << " --record " << std::endl - << " Allowed values for mode are:" << std::endl - << " 0: record all the captures images (continuous mode)," << std::endl - << " 1: record only images selected by a user click (single shot mode)." << std::endl - << " Default mode: 0" << std::endl - << std::endl - << " --no-display" << std::endl - << " Disable displaying captured images." << std::endl - << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." - << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --ip
" << std::endl + << " IP address of the drone to which you want to connect." << std::endl + << " Default: 192.168.42.1" << std::endl + << std::endl + << " --hd-resolution" << std::endl + << " Enables HD 720p images instead of default 480p." << std::endl + << " Caution : The camera settings are different depending on whether the resolution is 720p or 480p." + << std::endl + << std::endl + << " --seqname " << std::endl + << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl + << " Default: empty." << std::endl + << std::endl + << " --record " << std::endl + << " Allowed values for mode are:" << std::endl + << " 0: record all the captures images (continuous mode)," << std::endl + << " 1: record only images selected by a user click (single shot mode)." << std::endl + << " Default mode: 0" << std::endl + << std::endl + << " --no-display" << std::endl + << " Disable displaying captured images." << std::endl + << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." + << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to visualize images:" << std::endl - << " " << argv[0] << std::endl - << std::endl - << " Examples to record a sequence of 720p images from drone with ip different from default:" << std::endl - << " " << argv[0] << " --seqname I%04d.png --ip 192.168.42.3 --hd_resolution" << std::endl - << " " << argv[0] << " --seqname folder/I%04d.png --record 0 --ip 192.168.42.3 --hd-resolution" - << std::endl - << std::endl - << " Examples to record single shot images:" << std::endl - << " " << argv[0] << " --seqname I%04d.png --record 1" << std::endl - << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl - << std::endl; + << " Example to visualize images:" << std::endl + << " " << argv[0] << std::endl + << std::endl + << " Examples to record a sequence of 720p images from drone with ip different from default:" << std::endl + << " " << argv[0] << " --seqname I%04d.png --ip 192.168.42.3 --hd_resolution" << std::endl + << " " << argv[0] << " --seqname folder/I%04d.png --record 0 --ip 192.168.42.3 --hd-resolution" + << std::endl + << std::endl + << " Examples to record single shot images:" << std::endl + << " " << argv[0] << " --seqname I%04d.png --record 1" << std::endl + << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } @@ -72,7 +72,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char **argv) { -#if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_FFMPEG) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_FFMPEG) try { std::string opt_seqname; int opt_record_mode = 0; @@ -84,20 +84,26 @@ int main(int argc, const char **argv) if (std::string(argv[i]) == "--seqname") { opt_seqname = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--record") { + } + else if (std::string(argv[i]) == "--record") { opt_record_mode = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--ip" && i + 1 < argc) { ip_address = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--hd-resolution") { + } + else if (std::string(argv[i]) == "--hd-resolution") { image_res = 1; - } else if (std::string(argv[i]) == "--no-display") { + } + else if (std::string(argv[i]) == "--no-display") { opt_display = false; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -111,7 +117,7 @@ int main(int argc, const char **argv) std::cout << "Display : " << (opt_display ? "enabled" : "disabled") << std::endl; std::string text_record_mode = - std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); + std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); if (!opt_seqname.empty()) { std::cout << text_record_mode << std::endl; @@ -130,7 +136,8 @@ int main(int argc, const char **argv) drone.startStreaming(); drone.setExposure(1.5f); drone.getRGBaImage(I); - } else { + } + else { std::cout << "Error : failed to setup drone control" << std::endl; return EXIT_FAILURE; } @@ -178,7 +185,8 @@ int main(int argc, const char **argv) if (d) { delete d; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Caught an exception: " << e << std::endl; } #else @@ -190,9 +198,6 @@ int main(int argc, const char **argv) #ifndef VISP_HAVE_FFMPEG std::cout << "Install ffmpeg, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif // #if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_FFMPEG) } #else diff --git a/tutorial/grabber/tutorial-grabber-flycapture.cpp b/tutorial/grabber/tutorial-grabber-flycapture.cpp index 53791a6edf..d9b65ea13d 100644 --- a/tutorial/grabber/tutorial-grabber-flycapture.cpp +++ b/tutorial/grabber/tutorial-grabber-flycapture.cpp @@ -9,58 +9,58 @@ void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--change-settings]" - << " [--seqname ]" - << " [--record ]" - << " [--no-display]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--change-settings]" + << " [--seqname ]" + << " [--record ]" + << " [--no-display]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --change-settings" << std::endl - << " Force camera settings to auto shutter, auto gain and 640x480 MONO8 image" << std::endl - << " acquisition at 60 fps." << std::endl - << std::endl - << " --seqname " << std::endl - << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl - << " Default: empty." << std::endl - << std::endl - << " --record " << std::endl - << " Allowed values for mode are:" << std::endl - << " 0: record all the captures images (continuous mode)," << std::endl - << " 1: record only images selected by a user click (single shot mode)." << std::endl - << " Default mode: 0" << std::endl - << std::endl - << " --no-display" << std::endl - << " Disable displaying captured images." << std::endl - << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." - << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --change-settings" << std::endl + << " Force camera settings to auto shutter, auto gain and 640x480 MONO8 image" << std::endl + << " acquisition at 60 fps." << std::endl + << std::endl + << " --seqname " << std::endl + << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl + << " Default: empty." << std::endl + << std::endl + << " --record " << std::endl + << " Allowed values for mode are:" << std::endl + << " 0: record all the captures images (continuous mode)," << std::endl + << " 1: record only images selected by a user click (single shot mode)." << std::endl + << " Default mode: 0" << std::endl + << std::endl + << " --no-display" << std::endl + << " Disable displaying captured images." << std::endl + << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." + << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to visualize images:" << std::endl - << " " << argv[0] << std::endl - << std::endl - << " Examples to record a sequence:" << std::endl - << " " << argv[0] << " --seqname I%04d.png" << std::endl - << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl - << std::endl - << " Examples to record single shot images:\n" - << " " << argv[0] << " --seqname I%04d.png --record 1\n" - << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl - << std::endl; + << " Example to visualize images:" << std::endl + << " " << argv[0] << std::endl + << std::endl + << " Examples to record a sequence:" << std::endl + << " " << argv[0] << " --seqname I%04d.png" << std::endl + << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl + << std::endl + << " Examples to record single shot images:\n" + << " " << argv[0] << " --seqname I%04d.png --record 1\n" + << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_FLYCAPTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_FLYCAPTURE) try { std::string opt_seqname; int opt_record_mode = 0; @@ -70,18 +70,23 @@ int main(int argc, const char *argv[]) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--change-settings") { opt_change_settings = true; - } else if (std::string(argv[i]) == "--seqname") { + } + else if (std::string(argv[i]) == "--seqname") { opt_seqname = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--record") { + } + else if (std::string(argv[i]) == "--record") { opt_record_mode = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--no-display") { + } + else if (std::string(argv[i]) == "--no-display") { opt_display = false; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -96,7 +101,7 @@ int main(int argc, const char *argv[]) std::cout << "Display : " << (opt_display ? "enabled" : "disabled") << std::endl; std::string text_record_mode = - std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); + std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); if (!opt_seqname.empty()) { std::cout << text_record_mode << std::endl; @@ -114,8 +119,9 @@ int main(int argc, const char *argv[]) g.setShutter(true); // Turn auto shutter on g.setGain(true); // Turn auto gain on g.setVideoModeAndFrameRate(FlyCapture2::VIDEOMODE_640x480Y8, FlyCapture2::FRAMERATE_60); - } catch (...) { // If settings are not available just catch execption to - // continue with default settings + } + catch (...) { // If settings are not available just catch execption to + // continue with default settings std::cout << "Warning: cannot modify camera settings" << std::endl; } } @@ -170,7 +176,8 @@ int main(int argc, const char *argv[]) if (d) { delete d; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; } #else @@ -179,8 +186,5 @@ int main(int argc, const char *argv[]) #ifndef VISP_HAVE_FLYCAPTURE std::cout << "Install Flycapture SDK, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif } diff --git a/tutorial/grabber/tutorial-grabber-ids-ueye.cpp b/tutorial/grabber/tutorial-grabber-ids-ueye.cpp index d032fdded0..7c12ec12c2 100644 --- a/tutorial/grabber/tutorial-grabber-ids-ueye.cpp +++ b/tutorial/grabber/tutorial-grabber-ids-ueye.cpp @@ -11,92 +11,92 @@ void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--device ]" - << " [--config-file ]" - << " [--fps ]" - << " [--gain ]" - << " [--shutter ]" - << " [--subsample ]" - << " [--white-balance ]" - << " [--color-mode ]" - << " [--seqname ]" - << " [--record ]" - << " [--no-display]" - << " [--verbose] [-v]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--device ]" + << " [--config-file ]" + << " [--fps ]" + << " [--gain ]" + << " [--shutter ]" + << " [--subsample ]" + << " [--white-balance ]" + << " [--color-mode ]" + << " [--seqname ]" + << " [--record ]" + << " [--no-display]" + << " [--verbose] [-v]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --device " << std::endl - << " Camera device index. Set 0 to dial with the first camera," << std::endl - << " and 1 to dial with the second camera attached to the computer." << std::endl - << " Default: 0" << std::endl - << std::endl - << " --config-file " << std::endl - << " Camera config file." << std::endl - << " Default: empty." << std::endl - << std::endl - << " --fps " << std::endl - << " \"Auto\" or a frames per second value." << std::endl - << " Default: current setting." << std::endl - << std::endl - << " --gain " << std::endl - << " \"Auto\" or manual gain with a value in 0 - 100." << std::endl - << " Default: current setting." << std::endl - << std::endl - << " --shutter " << std::endl - << " \"Auto\" or manual shutter." << std::endl - << " Default: current setting." << std::endl - << std::endl - << " --subsample " << std::endl - << " Subsample factor to reduce image size alog rows and columns." << std::endl - << " Default: 1." << std::endl - << std::endl - << " --white-balance " << std::endl - << " Possible values are 0 (disabled) or 1 (enabled)." << std::endl - << " Default: current setting." << std::endl - << std::endl - << " --color-mode " << std::endl - << " Possible modes are: mono8, rgb24, rgb32, bayer8." << std::endl - << " Default: current setting." << std::endl - << std::endl - << " --seqname " << std::endl - << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl - << " Default: empty." << std::endl - << std::endl - << " --record " << std::endl - << " Allowed values for mode are:" << std::endl - << " 0: record all the captures images (continuous mode)," << std::endl - << " 1: record only images selected by a user click (single shot mode)." << std::endl - << " Default mode: 0" << std::endl - << std::endl - << " --no-display" << std::endl - << " Disable displaying captured images." << std::endl - << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." - << std::endl - << std::endl - << " --verbose, -v" << std::endl - << " Enable extra printings." << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --device " << std::endl + << " Camera device index. Set 0 to dial with the first camera," << std::endl + << " and 1 to dial with the second camera attached to the computer." << std::endl + << " Default: 0" << std::endl + << std::endl + << " --config-file " << std::endl + << " Camera config file." << std::endl + << " Default: empty." << std::endl + << std::endl + << " --fps " << std::endl + << " \"Auto\" or a frames per second value." << std::endl + << " Default: current setting." << std::endl + << std::endl + << " --gain " << std::endl + << " \"Auto\" or manual gain with a value in 0 - 100." << std::endl + << " Default: current setting." << std::endl + << std::endl + << " --shutter " << std::endl + << " \"Auto\" or manual shutter." << std::endl + << " Default: current setting." << std::endl + << std::endl + << " --subsample " << std::endl + << " Subsample factor to reduce image size alog rows and columns." << std::endl + << " Default: 1." << std::endl + << std::endl + << " --white-balance " << std::endl + << " Possible values are 0 (disabled) or 1 (enabled)." << std::endl + << " Default: current setting." << std::endl + << std::endl + << " --color-mode " << std::endl + << " Possible modes are: mono8, rgb24, rgb32, bayer8." << std::endl + << " Default: current setting." << std::endl + << std::endl + << " --seqname " << std::endl + << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl + << " Default: empty." << std::endl + << std::endl + << " --record " << std::endl + << " Allowed values for mode are:" << std::endl + << " 0: record all the captures images (continuous mode)," << std::endl + << " 1: record only images selected by a user click (single shot mode)." << std::endl + << " Default mode: 0" << std::endl + << std::endl + << " --no-display" << std::endl + << " Disable displaying captured images." << std::endl + << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." + << std::endl + << std::endl + << " --verbose, -v" << std::endl + << " Enable extra printings." << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to visualize images:" << std::endl - << " " << argv[0] << std::endl - << std::endl - << " Examples to record a sequence of images:" << std::endl - << " " << argv[0] << " --seqname I%04d.png" << std::endl - << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl - << std::endl - << " Examples to record single shot images:\n" - << " " << argv[0] << " --seqname I%04d.png --record 1\n" - << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl - << std::endl; + << " Example to visualize images:" << std::endl + << " " << argv[0] << std::endl + << std::endl + << " Examples to record a sequence of images:" << std::endl + << " " << argv[0] << " --seqname I%04d.png" << std::endl + << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl + << std::endl + << " Examples to record single shot images:\n" + << " " << argv[0] << " --seqname I%04d.png --record 1\n" + << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } @@ -107,7 +107,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_UEYE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UEYE) try { unsigned int opt_device = 0; std::string opt_seqname; @@ -126,39 +126,51 @@ int main(int argc, const char *argv[]) if (std::string(argv[i]) == "--device") { opt_device = static_cast(std::atoi(argv[i + 1])); i++; - } else if (std::string(argv[i]) == "--config-file") { + } + else if (std::string(argv[i]) == "--config-file") { opt_config_file = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--fps") { + } + else if (std::string(argv[i]) == "--fps") { opt_fps = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--gain") { + } + else if (std::string(argv[i]) == "--gain") { opt_gain = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--shutter") { + } + else if (std::string(argv[i]) == "--shutter") { opt_shutter = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--subsample") { + } + else if (std::string(argv[i]) == "--subsample") { opt_subsample = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--white-balance") { + } + else if (std::string(argv[i]) == "--white-balance") { opt_white_balance = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--color-mode") { + } + else if (std::string(argv[i]) == "--color-mode") { opt_color_mode = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--seqname") { + } + else if (std::string(argv[i]) == "--seqname") { opt_seqname = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--record") { + } + else if (std::string(argv[i]) == "--record") { opt_record_mode = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { + } + else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { opt_verbose = true; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -191,7 +203,7 @@ int main(int argc, const char *argv[]) std::cout << "Found " << cam_ids.size() << " cameras :" << std::endl; for (unsigned int i = 0; i < cam_ids.size(); i++) { std::cout << (opt_device == i ? " * Camera " : " Camera ") << i << " - ID: " << cam_ids[i] - << " Model: " << cam_models[i] << " S/N: " << cam_serials[i] << std::endl; + << " Model: " << cam_models[i] << " S/N: " << cam_serials[i] << std::endl; } //! [List camera info] @@ -203,9 +215,9 @@ int main(int argc, const char *argv[]) //! [Active camera info] std::cout << "Active camera is Model " << g.getActiveCameraModel() - << " with S/N: " << g.getActiveCameraSerialNumber() << std::endl; + << " with S/N: " << g.getActiveCameraSerialNumber() << std::endl; - //! [Open connection] +//! [Open connection] g.open(I); //! [Open connection] @@ -229,19 +241,21 @@ int main(int argc, const char *argv[]) if (!opt_gain.empty()) { if (opt_gain == "auto") { std::cout << "Auto gain : " << (g.setGain(true) ? "enabled" : "N/A") << std::endl; - } else { + } + else { std::cout << "Manual gain : " - << (g.setGain(false, std::atoi(opt_gain.c_str())) ? (std::string(opt_gain) + " %") : "N/A") - << std::endl; + << (g.setGain(false, std::atoi(opt_gain.c_str())) ? (std::string(opt_gain) + " %") : "N/A") + << std::endl; } } if (!opt_shutter.empty()) { if (opt_shutter == "auto") { std::cout << "Auto shutter : " << (g.setExposure(true) ? "enabled" : "N/A") << std::endl; - } else { + } + else { std::cout << "Manual shutter : " - << (g.setExposure(false, std::atof(opt_shutter.c_str())) ? (std::string(opt_shutter) + " ms") : "N/A") - << std::endl; + << (g.setExposure(false, std::atof(opt_shutter.c_str())) ? (std::string(opt_shutter) + " ms") : "N/A") + << std::endl; } } @@ -261,10 +275,11 @@ int main(int argc, const char *argv[]) if (!opt_fps.empty()) { if (opt_fps == "auto") { std::cout << "Auto framerate : " << (g.setFrameRate(true) ? "enabled" : "N/A") << std::endl; - } else { + } + else { std::cout << "Manual framerate : " - << (g.setFrameRate(false, std::atof(opt_fps.c_str())) ? (std::string(opt_fps) + " Hz") : "N/A") - << std::endl; + << (g.setFrameRate(false, std::atof(opt_fps.c_str())) ? (std::string(opt_fps) + " Hz") : "N/A") + << std::endl; } } @@ -272,7 +287,7 @@ int main(int argc, const char *argv[]) std::cout << "Display : " << (opt_display ? "enabled" : "disabled") << std::endl; std::string text_record_mode = - std::string("Record mode : ") + (opt_record_mode ? std::string("single") : std::string("continuous")); + std::string("Record mode : ") + (opt_record_mode ? std::string("single") : std::string("continuous")); if (!opt_seqname.empty()) { std::cout << text_record_mode << std::endl; @@ -344,7 +359,8 @@ int main(int argc, const char *argv[]) if (d) { delete d; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } #else @@ -353,8 +369,5 @@ int main(int argc, const char *argv[]) #ifndef VISP_HAVE_UEYE std::cout << "Install IDS uEye SDK, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif } diff --git a/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp b/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp index 3d09ec70f3..7df532fc8f 100644 --- a/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp +++ b/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp @@ -12,28 +12,30 @@ int main(int argc, char **argv) { -#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) && \ - (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) std::vector > type_serial_nb; std::vector cam_found; for (int i = 0; i < argc; i++) { if (std::string(argv[i]) == "--T265") { type_serial_nb.push_back(std::make_pair("T265", std::string(argv[i + 1]))); - } else if (std::string(argv[i]) == "--D435") { + } + else if (std::string(argv[i]) == "--D435") { type_serial_nb.push_back(std::make_pair("D435", std::string(argv[i + 1]))); - } else if (std::string(argv[i]) == "--SR300") { + } + else if (std::string(argv[i]) == "--SR300") { type_serial_nb.push_back(std::make_pair("SR300", std::string(argv[i + 1]))); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] - << " [--T265 ] [--D435 ] [--SR300 ]\n" - << "\nExample to use 2 T265 cameras:\n" - << " " << argv[0] << " --T265 11622110511 --T265 11622110433 \n" - << "\nExample to use 1 T265 and 1 D435 cameras:\n" - << " " << argv[0] << " --T265 11622110511 --D435 752112077408 \n" - << "\nExample to use 2 T265 and 1 D435 cameras:\n" - << " " << argv[0] << " --T265 11622110511 --T265 11622110433 --D435 752112070408 \n" - << std::endl; + << " [--T265 ] [--D435 ] [--SR300 ]\n" + << "\nExample to use 2 T265 cameras:\n" + << " " << argv[0] << " --T265 11622110511 --T265 11622110433 \n" + << "\nExample to use 1 T265 and 1 D435 cameras:\n" + << " " << argv[0] << " --T265 11622110511 --D435 752112077408 \n" + << "\nExample to use 2 T265 and 1 D435 cameras:\n" + << " " << argv[0] << " --T265 11622110511 --T265 11622110433 --D435 752112070408 \n" + << std::endl; return EXIT_SUCCESS; } } @@ -64,7 +66,8 @@ int main(int argc, char **argv) if (!cam_found.back()) { std::cout << "Device with ID: " << type_serial_nb[i].second << " not found." << std::endl; } - } else { // D435 or SR300 + } + else { // D435 or SR300 D435_cfg.enable_device(type_serial_nb[i].second); D435_cfg.disable_stream(RS2_STREAM_DEPTH); D435_cfg.disable_stream(RS2_STREAM_INFRARED); @@ -121,11 +124,8 @@ int main(int argc, char **argv) #endif #if !(RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) std::cout << "librealsense is detected but its version is too old. Install librealsense version > 2.31.0, configure " - "and build ViSP again to use this example" - << std::endl; -#endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; + "and build ViSP again to use this example" + << std::endl; #endif #endif return EXIT_SUCCESS; diff --git a/tutorial/grabber/tutorial-grabber-opencv.cpp b/tutorial/grabber/tutorial-grabber-opencv.cpp index 7c1f2b6579..7978d6e770 100644 --- a/tutorial/grabber/tutorial-grabber-opencv.cpp +++ b/tutorial/grabber/tutorial-grabber-opencv.cpp @@ -10,7 +10,7 @@ #define USE_COLOR // Comment to acquire gray level images -void usage(const char *argv [], int error) +void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl << " " << argv[0] << " [--device ]" @@ -69,7 +69,7 @@ void usage(const char *argv [], int error) // usage: binary -h // device name: 0 is the default to dial with the first camera, // 1 to dial with a second camera attached to the computer -int main(int argc, const char *argv []) +int main(int argc, const char *argv[]) { int opt_device = 0; std::string opt_seqname; @@ -118,7 +118,7 @@ int main(int argc, const char *argv []) std::cout << "Record name: " << opt_seqname << std::endl; } -#if defined(HAVE_OPENCV_VIDEOIO) && defined(HAVE_OPENCV_HIGHGUI) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(HAVE_OPENCV_VIDEOIO) && defined(HAVE_OPENCV_HIGHGUI) try { cv::VideoCapture cap(opt_device); // open the default camera if (!cap.isOpened()) { // check if we succeeded @@ -186,8 +186,5 @@ int main(int argc, const char *argv []) #if !defined(HAVE_OPENCV_VIDEOIO) std::cout << "Install OpenCV videoio module, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif } diff --git a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp index 4d3fb8ce2a..a592372027 100644 --- a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp @@ -9,45 +9,45 @@ void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--fps <6|15|30|60>]" - << " [--record ]" - << " [--no-display]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--fps <6|15|30|60>]" + << " [--record ]" + << " [--no-display]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --fps <6|15|30|60>" << std::endl - << " Frames per second." << std::endl - << " Default: 30." << std::endl - << std::endl - << " --record " << std::endl - << " Allowed values for mode are:" << std::endl - << " 0: record all the captures images (continuous mode)," << std::endl - << " 1: record only images selected by a user click (single shot mode)." << std::endl - << " Default mode: 0" << std::endl - << std::endl - << " --no-display" << std::endl - << " Disable displaying captured images." << std::endl - << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." - << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --fps <6|15|30|60>" << std::endl + << " Frames per second." << std::endl + << " Default: 30." << std::endl + << std::endl + << " --record " << std::endl + << " Allowed values for mode are:" << std::endl + << " 0: record all the captures images (continuous mode)," << std::endl + << " 1: record only images selected by a user click (single shot mode)." << std::endl + << " Default mode: 0" << std::endl + << std::endl + << " --no-display" << std::endl + << " Disable displaying captured images." << std::endl + << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." + << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to visualize images:" << std::endl - << " " << argv[0] << std::endl - << std::endl - << " Example to record a sequence of images:" << std::endl - << " " << argv[0] << " --record 0" << std::endl - << std::endl - << " Example to record single shot images:\n" - << " " << argv[0] << " --record 1" << std::endl - << std::endl; + << " Example to visualize images:" << std::endl + << " " << argv[0] << std::endl + << std::endl + << " Example to record a sequence of images:" << std::endl + << " " << argv[0] << " --record 0" << std::endl + << std::endl + << " Example to record single shot images:\n" + << " " << argv[0] << " --record 1" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } @@ -56,8 +56,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) && \ - (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) try { std::string opt_seqname_left = "left-%04d.png", opt_seqname_right = "right-%04d.png"; int opt_record_mode = 0; @@ -68,15 +67,19 @@ int main(int argc, const char *argv[]) if (std::string(argv[i]) == "--fps") { opt_fps = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--record") { + } + else if (std::string(argv[i]) == "--record") { opt_record_mode = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--no-display") { + } + else if (std::string(argv[i]) == "--no-display") { opt_display = false; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -90,7 +93,7 @@ int main(int argc, const char *argv[]) std::cout << "Display : " << (opt_display ? "enabled" : "disabled") << std::endl; std::string text_record_mode = - std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); + std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); std::cout << text_record_mode << std::endl; std::cout << "Left record name: " << opt_seqname_left << std::endl; @@ -164,7 +167,8 @@ int main(int argc, const char *argv[]) if (display_right) { delete display_right; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } #else @@ -173,8 +177,5 @@ int main(int argc, const char *argv[]) #if !(defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0))) std::cout << "Install librealsense version > 2.31.0, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif } diff --git a/tutorial/grabber/tutorial-grabber-realsense.cpp b/tutorial/grabber/tutorial-grabber-realsense.cpp index e22e621be7..6c39b2a632 100644 --- a/tutorial/grabber/tutorial-grabber-realsense.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense.cpp @@ -10,63 +10,63 @@ void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--fps <6|15|30|60>]" - << " [--width ]" - << " [--height ]" - << " [--seqname ]" - << " [--record ]" - << " [--no-display]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--fps <6|15|30|60>]" + << " [--width ]" + << " [--height ]" + << " [--seqname ]" + << " [--record ]" + << " [--no-display]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --fps <6|15|30|60>" << std::endl - << " Frames per second." << std::endl - << " Default: 30." << std::endl - << std::endl - << " --width " << std::endl - << " Default: 640." << std::endl - << std::endl - << " --height " << std::endl - << " Default: 480." << std::endl - << std::endl - << " --seqname " << std::endl - << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl - << " Default: empty." << std::endl - << std::endl - << " --record " << std::endl - << " Allowed values for mode are:" << std::endl - << " 0: record all the captures images (continuous mode)," << std::endl - << " 1: record only images selected by a user click (single shot mode)." << std::endl - << " Default mode: 0" << std::endl - << std::endl - << " --no-display" << std::endl - << " Disable displaying captured images." << std::endl - << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." - << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --fps <6|15|30|60>" << std::endl + << " Frames per second." << std::endl + << " Default: 30." << std::endl + << std::endl + << " --width " << std::endl + << " Default: 640." << std::endl + << std::endl + << " --height " << std::endl + << " Default: 480." << std::endl + << std::endl + << " --seqname " << std::endl + << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl + << " Default: empty." << std::endl + << std::endl + << " --record " << std::endl + << " Allowed values for mode are:" << std::endl + << " 0: record all the captures images (continuous mode)," << std::endl + << " 1: record only images selected by a user click (single shot mode)." << std::endl + << " Default mode: 0" << std::endl + << std::endl + << " --no-display" << std::endl + << " Disable displaying captured images." << std::endl + << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." + << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to visualize images:" << std::endl - << " " << argv[0] << std::endl - << std::endl - << " Examples to record a sequence of successive images in 640x480 resolution:" << std::endl - << " " << argv[0] << " --seqname I%04d.png" << std::endl - << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl - << std::endl - << " Examples to record single shot 640x480 images:\n" - << " " << argv[0] << " --seqname I%04d.png --record 1\n" - << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl - << std::endl - << " Examples to record single shot 1280x720 images:\n" - << " " << argv[0] << " --seqname I%04d.png --record 1 --width 1280 --height 720" << std::endl - << std::endl; + << " Example to visualize images:" << std::endl + << " " << argv[0] << std::endl + << std::endl + << " Examples to record a sequence of successive images in 640x480 resolution:" << std::endl + << " " << argv[0] << " --seqname I%04d.png" << std::endl + << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl + << std::endl + << " Examples to record single shot 640x480 images:\n" + << " " << argv[0] << " --seqname I%04d.png --record 1\n" + << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl + << std::endl + << " Examples to record single shot 1280x720 images:\n" + << " " << argv[0] << " --seqname I%04d.png --record 1 --width 1280 --height 720" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } @@ -75,7 +75,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) try { std::string opt_seqname; int opt_record_mode = 0; @@ -88,24 +88,31 @@ int main(int argc, const char *argv[]) if (std::string(argv[i]) == "--fps") { opt_fps = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--seqname") { + } + else if (std::string(argv[i]) == "--seqname") { opt_seqname = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--width") { + } + else if (std::string(argv[i]) == "--width") { opt_width = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--height") { + } + else if (std::string(argv[i]) == "--height") { opt_height = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--record") { + } + else if (std::string(argv[i]) == "--record") { opt_record_mode = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--no-display") { + } + else if (std::string(argv[i]) == "--no-display") { opt_display = false; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -124,7 +131,7 @@ int main(int argc, const char *argv[]) std::cout << "Display : " << (opt_display ? "enabled" : "disabled") << std::endl; std::string text_record_mode = - std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); + std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); if (!opt_seqname.empty()) { std::cout << text_record_mode << std::endl; @@ -191,7 +198,8 @@ int main(int argc, const char *argv[]) if (d) { delete d; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } #else @@ -200,8 +208,5 @@ int main(int argc, const char *argv[]) #if !(defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2)) std::cout << "Install librealsense version > 2.31.0, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif } diff --git a/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp b/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp index 22805544c2..0108f2002a 100644 --- a/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp +++ b/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp @@ -12,8 +12,7 @@ */ int main(int argc, char **argv) { -#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && \ - (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_OCCIPITAL_STRUCTURE) // Both cameras can stream color and depth in 640x480 resolution. unsigned int width = 640, height = 480; @@ -80,8 +79,5 @@ int main(int argc, char **argv) #if !(defined(VISP_HAVE_REALSENSE2)) std::cout << "Install librealsense, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif } diff --git a/tutorial/grabber/tutorial-grabber-structure-core.cpp b/tutorial/grabber/tutorial-grabber-structure-core.cpp index cf1f1a2100..b668684ce8 100644 --- a/tutorial/grabber/tutorial-grabber-structure-core.cpp +++ b/tutorial/grabber/tutorial-grabber-structure-core.cpp @@ -9,61 +9,61 @@ void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--depth-fps <6|15|30|60>]" - << " [--depth-fps <6|15|30|60>]" - << " [--sxga]" - << " [--no-frame-sync]" - << " [--record ]" - << " [--no-display]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--depth-fps <6|15|30|60>]" + << " [--depth-fps <6|15|30|60>]" + << " [--sxga]" + << " [--no-frame-sync]" + << " [--record ]" + << " [--no-display]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --visible-fps <6|15|30|60>" << std::endl - << " Visible camera (gray or color) frames per second." << std::endl - << " Default: 30." << std::endl - << std::endl - << " --depth-fps <6|15|30|60>" << std::endl - << " Depth camera frames per second." << std::endl - << " Default: 30." << std::endl - << std::endl - << " --sxga" << std::endl - << " If available, output 1280x960 high resolution depth array." << std::endl - << std::endl - << " --no-frame-sync" << std::endl - << " If available, disable frame synchronization." << std::endl - << std::endl - << " --record " << std::endl - << " Allowed values for mode are:" << std::endl - << " 0: record all the captures images (continuous mode)," << std::endl - << " 1: record only images selected by a user click (single shot mode)." << std::endl - << " Default mode: 0" << std::endl - << std::endl - << " --no-display" << std::endl - << " Disable displaying captured images." << std::endl - << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." - << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --visible-fps <6|15|30|60>" << std::endl + << " Visible camera (gray or color) frames per second." << std::endl + << " Default: 30." << std::endl + << std::endl + << " --depth-fps <6|15|30|60>" << std::endl + << " Depth camera frames per second." << std::endl + << " Default: 30." << std::endl + << std::endl + << " --sxga" << std::endl + << " If available, output 1280x960 high resolution depth array." << std::endl + << std::endl + << " --no-frame-sync" << std::endl + << " If available, disable frame synchronization." << std::endl + << std::endl + << " --record " << std::endl + << " Allowed values for mode are:" << std::endl + << " 0: record all the captures images (continuous mode)," << std::endl + << " 1: record only images selected by a user click (single shot mode)." << std::endl + << " Default mode: 0" << std::endl + << std::endl + << " --no-display" << std::endl + << " Disable displaying captured images." << std::endl + << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." + << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to visualize images:" << std::endl - << " " << argv[0] << std::endl - << std::endl - << " Example to record a sequence of images:" << std::endl - << " " << argv[0] << " --record 0" << std::endl - << std::endl - << " Example to record a sequence of images at different frame rates:" << std::endl - << " " << argv[0] << " --record 0 --depth-fps 15 --visible-fps 10 --no-frame-sync" << std::endl - << std::endl - << " Example to record single shot images:\n" - << " " << argv[0] << " --record 1" << std::endl - << std::endl; + << " Example to visualize images:" << std::endl + << " " << argv[0] << std::endl + << std::endl + << " Example to record a sequence of images:" << std::endl + << " " << argv[0] << " --record 0" << std::endl + << std::endl + << " Example to record a sequence of images at different frame rates:" << std::endl + << " " << argv[0] << " --record 0 --depth-fps 15 --visible-fps 10 --no-frame-sync" << std::endl + << std::endl + << " Example to record single shot images:\n" + << " " << argv[0] << " --record 1" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } @@ -72,7 +72,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) try { std::string opt_seqname_visible = "visible-%04d.png", opt_seqname_depth = "depth-%04d.png"; int opt_record_mode = 0; @@ -85,22 +85,29 @@ int main(int argc, const char *argv[]) if (std::string(argv[i]) == "--depth-fps") { opt_depth_fps = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--visible-fps") { + } + else if (std::string(argv[i]) == "--visible-fps") { opt_visible_fps = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--sxga") { + } + else if (std::string(argv[i]) == "--sxga") { opt_sxga = true; - } else if (std::string(argv[i]) == "--no-frame-sync") { + } + else if (std::string(argv[i]) == "--no-frame-sync") { opt_frame_sync = false; - } else if (std::string(argv[i]) == "--record") { + } + else if (std::string(argv[i]) == "--record") { opt_record_mode = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--no-display") { + } + else if (std::string(argv[i]) == "--no-display") { opt_display = false; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -115,7 +122,7 @@ int main(int argc, const char *argv[]) std::cout << "Display : " << (opt_display ? "enabled" : "disabled") << std::endl; std::string text_record_mode = - std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); + std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); std::cout << text_record_mode << std::endl; std::cout << "Visible record name: " << opt_seqname_visible << std::endl; @@ -213,7 +220,8 @@ int main(int argc, const char *argv[]) delete display_depth; } } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } #else @@ -222,8 +230,5 @@ int main(int argc, const char *argv[]) #if !(defined(VISP_HAVE_OCCIPITAL_STRUCTURE)) std::cout << "Install libStructure, configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif #endif } diff --git a/tutorial/grabber/tutorial-grabber-v4l2.cpp b/tutorial/grabber/tutorial-grabber-v4l2.cpp index 3cf839d98a..245f04a2fb 100644 --- a/tutorial/grabber/tutorial-grabber-v4l2.cpp +++ b/tutorial/grabber/tutorial-grabber-v4l2.cpp @@ -10,61 +10,61 @@ void usage(const char *argv[], int error) { std::cout << "SYNOPSIS" << std::endl - << " " << argv[0] << " [--device ]" - << " [--scale ]" - << " [--seqname ]" - << " [--record ]" - << " [--no-display]" - << " [--help] [-h]" << std::endl - << std::endl; + << " " << argv[0] << " [--device ]" + << " [--scale ]" + << " [--seqname ]" + << " [--record ]" + << " [--no-display]" + << " [--help] [-h]" << std::endl + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --device " << std::endl - << " Camera device index. Set 0 to dial with the first camera," << std::endl - << " and 1 to dial with the second camera attached to the computer." << std::endl - << " Default: 0 to consider /dev/video0 device." << std::endl - << std::endl - << " --scale " << std::endl - << " Subsampling factor applied to the images captured by the device." << std::endl - << " Default: 1" << std::endl - << std::endl - << " --seqname " << std::endl - << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl - << " Default: empty." << std::endl - << std::endl - << " --record " << std::endl - << " Allowed values for mode are:" << std::endl - << " 0: record all the captures images (continuous mode)," << std::endl - << " 1: record only images selected by a user click (single shot mode)." << std::endl - << " Default mode: 0" << std::endl - << std::endl - << " --no-display" << std::endl - << " Disable displaying captured images." << std::endl - << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." - << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --device " << std::endl + << " Camera device index. Set 0 to dial with the first camera," << std::endl + << " and 1 to dial with the second camera attached to the computer." << std::endl + << " Default: 0 to consider /dev/video0 device." << std::endl + << std::endl + << " --scale " << std::endl + << " Subsampling factor applied to the images captured by the device." << std::endl + << " Default: 1" << std::endl + << std::endl + << " --seqname " << std::endl + << " Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl + << " Default: empty." << std::endl + << std::endl + << " --record " << std::endl + << " Allowed values for mode are:" << std::endl + << " 0: record all the captures images (continuous mode)," << std::endl + << " 1: record only images selected by a user click (single shot mode)." << std::endl + << " Default mode: 0" << std::endl + << std::endl + << " --no-display" << std::endl + << " Disable displaying captured images." << std::endl + << " When used and sequence name specified, record mode is internally set to 1 (continuous mode)." + << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "USAGE" << std::endl - << " Example to visualize images:" << std::endl - << " " << argv[0] << std::endl - << std::endl - << " Example to visualize images from a second camera:" << std::endl - << " " << argv[0] << " --device 1" << std::endl - << std::endl - << " Examples to record a sequence:" << std::endl - << " " << argv[0] << " --seqname I%04d.png" << std::endl - << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl - << std::endl - << " Examples to record single shot images:\n" - << " " << argv[0] << " --seqname I%04d.png --record 1\n" - << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl - << std::endl; + << " Example to visualize images:" << std::endl + << " " << argv[0] << std::endl + << std::endl + << " Example to visualize images from a second camera:" << std::endl + << " " << argv[0] << " --device 1" << std::endl + << std::endl + << " Examples to record a sequence:" << std::endl + << " " << argv[0] << " --seqname I%04d.png" << std::endl + << " " << argv[0] << " --seqname folder/I%04d.png --record 0" << std::endl + << std::endl + << " Examples to record single shot images:\n" + << " " << argv[0] << " --seqname I%04d.png --record 1\n" + << " " << argv[0] << " --seqname folder/I%04d.png --record 1" << std::endl + << std::endl; if (error) { std::cout << "Error" << std::endl - << " " - << "Unsupported parameter " << argv[error] << std::endl; + << " " + << "Unsupported parameter " << argv[error] << std::endl; } } @@ -76,7 +76,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_V4L2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_V4L2) try { int opt_device = 0; unsigned int opt_scale = 1; // Default value is 2 in the constructor. Turn @@ -89,21 +89,27 @@ int main(int argc, const char *argv[]) if (std::string(argv[i]) == "--device") { opt_device = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--scale") { + } + else if (std::string(argv[i]) == "--scale") { opt_scale = (unsigned int)atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--seqname") { + } + else if (std::string(argv[i]) == "--seqname") { opt_seqname = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--record") { + } + else if (std::string(argv[i]) == "--record") { opt_record_mode = std::atoi(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--no-display") { + } + else if (std::string(argv[i]) == "--no-display") { opt_display = false; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { usage(argv, 0); return EXIT_SUCCESS; - } else { + } + else { usage(argv, i); return EXIT_FAILURE; } @@ -117,7 +123,7 @@ int main(int argc, const char *argv[]) std::cout << "Display : " << (opt_display ? "enabled" : "disabled") << std::endl; std::string text_record_mode = - std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); + std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous")); if (!opt_seqname.empty()) { std::cout << text_record_mode << std::endl; @@ -184,7 +190,8 @@ int main(int argc, const char *argv[]) if (d) { delete d; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } #else @@ -193,8 +200,6 @@ int main(int argc, const char *argv[]) #ifndef VISP_HAVE_V4L2 std::cout << "Install Video 4 Linux 2 (v4l2), configure and build ViSP again to use this example" << std::endl; #endif -#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) - std::cout << "This tutorial should be built with c++11 support" << std::endl; -#endif + #endif } diff --git a/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.cpp b/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.cpp index c7837498dd..5d1749565b 100644 --- a/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.cpp +++ b/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.cpp @@ -1,7 +1,7 @@ //! \example ClassUsingPclViewer.cpp #include "ClassUsingPclViewer.h" -#if defined(VISP_HAVE_PCL) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PCL) // PCL #include diff --git a/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.h b/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.h index cbfa0543d9..45a541348e 100644 --- a/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.h +++ b/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.h @@ -4,7 +4,7 @@ //! \example ClassUsingPclViewer.h #include -#if defined(VISP_HAVE_PCL) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PCL) #include #include diff --git a/tutorial/gui/pcl-visualizer/tutorial-pcl-viewer.cpp b/tutorial/gui/pcl-visualizer/tutorial-pcl-viewer.cpp index 0c016f1561..c2ddc12c67 100644 --- a/tutorial/gui/pcl-visualizer/tutorial-pcl-viewer.cpp +++ b/tutorial/gui/pcl-visualizer/tutorial-pcl-viewer.cpp @@ -4,7 +4,7 @@ // System include #include -#if defined(VISP_HAVE_PCL) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PCL) // ViSP include #include @@ -91,7 +91,7 @@ std::string getAvailableDisplayMode(const std::string &prefix = "< ", const std: } //! [Enum for mode choice] -int main(int argc, char *argv []) +int main(int argc, char *argv[]) { //! [Default arguments values] const double def_addedNoise = 0.; // Standard deviation of the noise added to the points. diff --git a/tutorial/image/drawingHelpers.h b/tutorial/image/drawingHelpers.h index ad3b4e57aa..e612b20237 100644 --- a/tutorial/image/drawingHelpers.h +++ b/tutorial/image/drawingHelpers.h @@ -37,67 +37,67 @@ namespace drawingHelpers { - #if defined(VISP_HAVE_X11) - extern vpDisplayX d; - #elif defined(HAVE_OPENCV_HIGHGUI) - extern vpDisplayOpenCV d; - #elif defined(VISP_HAVE_GTK) - extern vpDisplayGTK d; - #elif defined(VISP_HAVE_GDI) - extern vpDisplayGDI d; - #elif defined(VISP_HAVE_D3D9) - extern vpDisplayD3D d; - #endif +#if defined(VISP_HAVE_X11) +extern vpDisplayX d; +#elif defined(HAVE_OPENCV_HIGHGUI) +extern vpDisplayOpenCV d; +#elif defined(VISP_HAVE_GTK) +extern vpDisplayGTK d; +#elif defined(VISP_HAVE_GDI) +extern vpDisplayGDI d; +#elif defined(VISP_HAVE_D3D9) +extern vpDisplayD3D d; +#endif - extern vpImage I_disp; /*!< Displayed image.*/ +extern vpImage I_disp; /*!< Displayed image.*/ - /** - * \brief Display a RGB image and catch the user clicks to know if - * the user wants to stop the program. - * - * \param[out] I The RGB image to display. - * \param[in] title The title of the window. - * \param[in] blockingMode If true, wait for a click to switch to the next image. - * \return true The user wants to continue the application. - * \return false The user wants to stop the application. - */ - bool display(vpImage &I, const std::string &title, const bool &blockingMode); +/** + * \brief Display a RGB image and catch the user clicks to know if + * the user wants to stop the program. + * + * \param[out] I The RGB image to display. + * \param[in] title The title of the window. + * \param[in] blockingMode If true, wait for a click to switch to the next image. + * \return true The user wants to continue the application. + * \return false The user wants to stop the application. + */ +bool display(vpImage &I, const std::string &title, const bool &blockingMode); - /** - * \brief Display a gray-scale image and catch the user clicks to know if - * the user wants to stop the program. - * - * \param[out] I The gray-scale image to display. - * \param[in] title The title of the window. - * \param[in] blockingMode If true, wait for a click to switch to the next image. - * \return true The user wants to continue the application. - * \return false The user wants to stop the application. - */ - bool display(vpImage &I, const std::string &title, const bool &blockingMode); +/** + * \brief Display a gray-scale image and catch the user clicks to know if + * the user wants to stop the program. + * + * \param[out] I The gray-scale image to display. + * \param[in] title The title of the window. + * \param[in] blockingMode If true, wait for a click to switch to the next image. + * \return true The user wants to continue the application. + * \return false The user wants to stop the application. + */ +bool display(vpImage &I, const std::string &title, const bool &blockingMode); - /** - * \brief Display a double precision image and catch the user clicks to know if - * the user wants to stop the program. - * - * \param[out] I The double precision image to display. - * \param[in] title The title of the window. - * \param[in] blockingMode If true, wait for a click to switch to the next image. - * \return true The user wants to continue the application. - * \return false The user wants to stop the application. - */ - bool display(vpImage &D, const std::string &title, const bool &blockingMode); +/** + * \brief Display a double precision image and catch the user clicks to know if + * the user wants to stop the program. + * + * \param[out] D The double precision image to display. + * \param[in] title The title of the window. + * \param[in] blockingMode If true, wait for a click to switch to the next image. + * \return true The user wants to continue the application. + * \return false The user wants to stop the application. + */ +bool display(vpImage &D, const std::string &title, const bool &blockingMode); - /** - * \brief Display a floating-point precision image and catch the user clicks to know if - * the user wants to stop the program. - * - * \param[out] I The floating-point precision image to display. - * \param[in] title The title of the window. - * \param[in] blockingMode If true, wait for a click to switch to the next image. - * \return true The user wants to continue the application. - * \return false The user wants to stop the application. - */ - bool display(vpImage &F, const std::string &title, const bool &blockingMode); +/** + * \brief Display a floating-point precision image and catch the user clicks to know if + * the user wants to stop the program. + * + * \param[out] F The floating-point precision image to display. + * \param[in] title The title of the window. + * \param[in] blockingMode If true, wait for a click to switch to the next image. + * \return true The user wants to continue the application. + * \return false The user wants to stop the application. + */ +bool display(vpImage &F, const std::string &title, const bool &blockingMode); } #endif diff --git a/tutorial/image/tutorial-image-colormap.cpp b/tutorial/image/tutorial-image-colormap.cpp index d281bd793d..b4bc0ff063 100644 --- a/tutorial/image/tutorial-image-colormap.cpp +++ b/tutorial/image/tutorial-image-colormap.cpp @@ -10,7 +10,6 @@ int main() { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { std::map colormaps_str = { {vpColormap::COLORMAP_AUTUMN, "Colormap Autumn"}, @@ -59,16 +58,16 @@ int main() vpImage Icolor(Irgbf.getHeight(), Irgbf.getWidth()); vpImage Icolor2(Irgbf.getHeight() * 2, Irgbf.getWidth() * 2); - #if defined(VISP_HAVE_X11) +#if defined(VISP_HAVE_X11) vpDisplayX d(Icolor2, 10, 10, "Memorial"); - #elif defined(VISP_HAVE_GDI) +#elif defined(VISP_HAVE_GDI) vpDisplayGDI d(Icolor2, 10, 10, "Memorial"); - #elif defined(HAVE_OPENCV_HIGHGUI) +#elif defined(HAVE_OPENCV_HIGHGUI) vpDisplayOpenCV d(Icolor2, 10, 10, "Memorial"); - #else +#else std::cout << "No image viewer is available..." << std::endl; return EXIT_SUCCESS; - #endif +#endif vpFont font(20); for (size_t i = 0; i < colormaps.size(); i++) { @@ -92,16 +91,16 @@ int main() vpImage Icolor(I.getHeight(), I.getWidth()); vpImage Icolor2(I.getHeight() * 2, I.getWidth() * 2); - #if defined(VISP_HAVE_X11) +#if defined(VISP_HAVE_X11) vpDisplayX d(Icolor2, 10, 10, "Monkey"); - #elif defined(VISP_HAVE_GDI) +#elif defined(VISP_HAVE_GDI) vpDisplayGDI d(Icolor2, 10, 10, "Monkey"); - #elif defined(HAVE_OPENCV_HIGHGUI) +#elif defined(HAVE_OPENCV_HIGHGUI) vpDisplayOpenCV d(Icolor2, 10, 10, "Monkey"); - #else +#else std::cout << "No image viewer is available..." << std::endl; return EXIT_SUCCESS; - #endif +#endif vpFont font(20); for (size_t i = 0; i < colormaps.size(); i++) { @@ -125,16 +124,16 @@ int main() vpImage Icolor(I.getHeight(), I.getWidth()); vpImage Icolor2(I.getHeight() * 2, I.getWidth() * 2); - #if defined(VISP_HAVE_X11) +#if defined(VISP_HAVE_X11) vpDisplayX d(Icolor2, 10, 10, "Monkey"); - #elif defined(VISP_HAVE_GDI) +#elif defined(VISP_HAVE_GDI) vpDisplayGDI d(Icolor2, 10, 10, "Monkey"); - #elif defined(HAVE_OPENCV_HIGHGUI) +#elif defined(HAVE_OPENCV_HIGHGUI) vpDisplayOpenCV d(Icolor2, 10, 10, "Monkey"); - #else +#else std::cout << "No image viewer is available..." << std::endl; return EXIT_SUCCESS; - #endif +#endif vpFont font(20); for (size_t i = 0; i < colormaps.size(); i++) { @@ -150,11 +149,10 @@ int main() vpDisplay::getClick(Icolor2); } } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e << std::endl; } -#else - std::cout << "This tutorial needs at least cxx11 standard." << std::endl; -#endif + return EXIT_SUCCESS; } diff --git a/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp b/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp index 105c71a613..d9e4b13c2b 100644 --- a/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp +++ b/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp @@ -15,8 +15,6 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - #include "drawingHelpers.h" //! [Enum input] @@ -535,10 +533,3 @@ int main(int argc, char **argv) } return EXIT_SUCCESS; } -#else -int main() -{ - std::cout << "This tutorial needs to be build at least with cxx 11 standard!" << std::endl; - return EXIT_SUCCESS; -} -#endif