From f9056d6ad01210a8fb2af93da3051a10d2740500 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 24 Jan 2024 11:03:30 +0100 Subject: [PATCH 01/12] Remove useless code in apriltag 3rd party --- 3rdparty/apriltag/common/string_util.h | 18 ------------------ 1 file changed, 18 deletions(-) diff --git a/3rdparty/apriltag/common/string_util.h b/3rdparty/apriltag/common/string_util.h index 1fec397610..152b3ae720 100644 --- a/3rdparty/apriltag/common/string_util.h +++ b/3rdparty/apriltag/common/string_util.h @@ -51,24 +51,6 @@ struct string_feeder int line, col; }; -/** - * Similar to sprintf(), except that it will malloc() enough space for the - * formatted string which it returns. It is the caller's responsibility to call - * free() on the returned string when it is no longer needed. - */ -char *sprintf_alloc(const char *fmt, ...) -#ifndef _MSC_VER -__attribute__ ((format (printf, 1, 2))) -#endif -; - -/** - * Similar to vsprintf(), except that it will malloc() enough space for the - * formatted string which it returns. It is the caller's responsibility to call - * free() on the returned string when it is no longer needed. - */ -char *vsprintf_alloc(const char *fmt, va_list args); - /** * Concatenates 1 or more strings together and returns the result, which will be a * newly allocated string which it is the caller's responsibility to free. From 55cefee473a8ba241443c1a4b12f43a15392f571 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 24 Jan 2024 11:04:31 +0100 Subject: [PATCH 02/12] Use std::min and std::max as templates --- 3rdparty/simdlib/Simd/SimdRuntime.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/3rdparty/simdlib/Simd/SimdRuntime.h b/3rdparty/simdlib/Simd/SimdRuntime.h index 30f7a286b1..8a0948acc1 100755 --- a/3rdparty/simdlib/Simd/SimdRuntime.h +++ b/3rdparty/simdlib/Simd/SimdRuntime.h @@ -122,8 +122,8 @@ namespace Simd { count += 1; sum += value; - min = std::min(min, value); - max = std::max(max, value); + min = std::min(min, value); + max = std::max(max, value); } SIMD_INLINE int64_t Mean() const @@ -201,7 +201,7 @@ namespace Simd { size_t M; size_t N; size_t K; const float * alpha; const float * A; size_t lda; const float * B; size_t ldb; const float * beta; float * C; size_t ldc; SIMD_INLINE GemmArgs(size_t M_, size_t N_, size_t K_, const float * alpha_, const float * A_, size_t lda_, const float * B_, size_t ldb_, const float * beta_, float * C_, size_t ldc_) - :M(M_), N(N_), K(K_), alpha(alpha_), A(A_), lda(lda_), B(B_), ldb(ldb_), beta(beta_), ldc(ldc_), C(C_) + :M(M_), N(N_), K(K_), alpha(alpha_), A(A_), lda(lda_), B(B_), ldb(ldb_), beta(beta_), ldc(ldc_), C(C_) {} }; @@ -287,8 +287,8 @@ namespace Simd ss << "GemmCb [" << args.M << ", " << args.N << ", " << args.K << "]"; return ss.str(); } -#endif - +#endif + SIMD_INLINE GemmKernelType Type() const { return _type; } SIMD_INLINE size_t BufferSize(size_t M, size_t N, size_t K) const @@ -310,7 +310,7 @@ namespace Simd }; typedef std::vector GemmCbFuncs; - SIMD_INLINE GemmCbFuncs InitGemmCbFuncs(GemmCbFunc::BufferSizePtr bufferSize, GemmCbFunc::ReorderBPtr reorderB, GemmCbFunc::RunPtr run, + SIMD_INLINE GemmCbFuncs InitGemmCbFuncs(GemmCbFunc::BufferSizePtr bufferSize, GemmCbFunc::ReorderBPtr reorderB, GemmCbFunc::RunPtr run, const String & name, GemmKernelType begin, GemmKernelType end) { GemmCbFuncs funcs; From 889c2f75bcf81fc9ecd231e274b4894133991108 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 24 Jan 2024 11:05:50 +0100 Subject: [PATCH 03/12] Enable nlohman_json 3rdparty only when cxx11 or greater --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4a5c0ec269..0c63f5b145 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -622,7 +622,7 @@ VP_OPTION(USE_ZBAR ZBAR "" "Include zbar support" "" O VP_OPTION(USE_DMTX DMTX "" "Include dmtx support" "" ON IF NOT WINRT AND NOT IOS) VP_OPTION(USE_PCL PCL QUIET "Include Point Cloud Library support" "" ON IF NOT WINRT AND NOT IOS) VP_OPTION(USE_TENSORRT TensorRT "" "Include TensorRT support" "" ON IF NOT WINRT AND NOT IOS) -VP_OPTION(USE_NLOHMANN_JSON nlohmann_json QUIET "Include nlohmann json support" "" ON) +VP_OPTION(USE_NLOHMANN_JSON nlohmann_json QUIET "Include nlohmann json support" "" ON IF (VISP_CXX_STANDARD GREATER VISP_CXX_STANDARD_98)) # ---------------------------------------------------------------------------- # Handle cxx standard depending on specific 3rd parties. Should be before module parsing and VISP3rdParty.cmake include From 5ee2d88274390ed1160591e61f9e134ebbe4f138 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 24 Jan 2024 11:10:17 +0100 Subject: [PATCH 04/12] Introduce mechanism to emaulate nullptr when cxx98 enabled --- cmake/VISPDetectCXXStandard.cmake | 45 +++++++++++---- cmake/checks/nullptr.cpp | 14 +++++ .../include/visp3/core/vpNullptrEmulated.h | 57 +++++++++++++++++++ 3 files changed, 104 insertions(+), 12 deletions(-) create mode 100644 cmake/checks/nullptr.cpp create mode 100644 modules/core/include/visp3/core/vpNullptrEmulated.h diff --git a/cmake/VISPDetectCXXStandard.cmake b/cmake/VISPDetectCXXStandard.cmake index 5a32ea01b4..1db6f2b962 100644 --- a/cmake/VISPDetectCXXStandard.cmake +++ b/cmake/VISPDetectCXXStandard.cmake @@ -9,41 +9,54 @@ if(DEFINED USE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 98) set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_98}) set(CXX98_CXX_FLAGS "-std=c++98" CACHE STRING "C++ compiler flags for C++98 support") + mark_as_advanced(CXX98_CXX_FLAGS) elseif(USE_CXX_STANDARD STREQUAL "11") set(CMAKE_CXX_STANDARD 11) set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_11}) vp_check_compiler_flag(CXX "-std=c++11" HAVE_STD_CXX11_FLAG "${PROJECT_SOURCE_DIR}/cmake/checks/cxx11.cpp") if(HAVE_STD_CXX11_FLAG) set(CXX11_CXX_FLAGS "-std=c++11" CACHE STRING "C++ compiler flags for C++11 support") - mark_as_advanced(HAVE_STD_CXX11_FLAG) + mark_as_advanced(CXX11_CXX_FLAGS) endif() + mark_as_advanced(HAVE_STD_CXX11_FLAG) elseif(USE_CXX_STANDARD STREQUAL "14") set(CMAKE_CXX_STANDARD 14) set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_14}) vp_check_compiler_flag(CXX "-std=c++14" HAVE_STD_CXX14_FLAG "${PROJECT_SOURCE_DIR}/cmake/checks/cxx14.cpp") if(HAVE_STD_CXX14_FLAG) set(CXX14_CXX_FLAGS "-std=c++14" CACHE STRING "C++ compiler flags for C++14 support") - mark_as_advanced(HAVE_STD_CXX14_FLAG) + mark_as_advanced(CXX14_CXX_FLAGS) endif() + mark_as_advanced(HAVE_STD_CXX14_FLAG) elseif(USE_CXX_STANDARD STREQUAL "17") set(CMAKE_CXX_STANDARD 17) set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_17}) vp_check_compiler_flag(CXX "-std=c++17" HAVE_STD_CXX17_FLAG "${PROJECT_SOURCE_DIR}/cmake/checks/cxx17.cpp") if(HAVE_STD_CXX17_FLAG) set(CXX17_CXX_FLAGS "-std=c++17" CACHE STRING "C++ compiler flags for C++17 support") - mark_as_advanced(HAVE_STD_CXX17_FLAG) + mark_as_advanced(CXX17_CXX_FLAGS) endif() + mark_as_advanced(HAVE_STD_CXX17_FLAG) endif() set(CMAKE_CXX_EXTENSIONS OFF) # use -std=c++11 instead of -std=gnu++11 + # Additional check for nullptr that is available with clang but not with g++ when cxx98 standard is enabled + vp_check_compiler_flag(CXX "" HAVE_NULLPTR "${PROJECT_SOURCE_DIR}/cmake/checks/nullptr.cpp") + mark_as_advanced(HAVE_NULLPTR) + else() set(AVAILABLE_CXX_STANDARD TRUE) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_11}) + set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_98}) 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 @@ -116,6 +129,8 @@ 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() @@ -126,8 +141,11 @@ 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") + set_property(CACHE USE_CXX_STANDARD APPEND_STRING PROPERTY STRINGS ";11") endif() if(CXX14_STANDARD_FOUND) set_property(CACHE USE_CXX_STANDARD APPEND_STRING PROPERTY STRINGS ";14") @@ -136,15 +154,18 @@ else() set_property(CACHE USE_CXX_STANDARD APPEND_STRING PROPERTY STRINGS ";17") endif() - if(USE_CXX_STANDARD STREQUAL "11") - set(CMAKE_CXX_STANDARD 11) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_11}) + 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}) 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() endif() endif() diff --git a/cmake/checks/nullptr.cpp b/cmake/checks/nullptr.cpp new file mode 100644 index 0000000000..1714f7fe0a --- /dev/null +++ b/cmake/checks/nullptr.cpp @@ -0,0 +1,14 @@ +#include +#include + +void g(int *) +{ + std::cout << "Function g called" << std::endl; +} + +int main() +{ + g(nullptr); + g(NULL); + g(0); +} diff --git a/modules/core/include/visp3/core/vpNullptrEmulated.h b/modules/core/include/visp3/core/vpNullptrEmulated.h new file mode 100644 index 0000000000..652f2fccc1 --- /dev/null +++ b/modules/core/include/visp3/core/vpNullptrEmulated.h @@ -0,0 +1,57 @@ +/* + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + */ + +#ifndef _vpNullptrEmulated_h_ +#define _vpNullptrEmulated_h_ + +// Inspired from this thread https://stackoverflow.com/questions/24433436/compile-error-nullptr-undeclared-identifier +// Does the emulation of nullptr when not available with cxx98 +const +class nullptr_t +{ +public: + template + inline operator T *() const // convertible to any type of null non-member pointer... + { + return 0; + } + + template + inline operator T C:: *() const // or any type of null member pointer... + { + return 0; + } + +private: + void operator&() const; // Can't take address of nullptr + +} nullptr = {}; + +#endif From 94ad7d639cec2afc18b58cf887c54148c53b047d Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 31 Jan 2024 11:27:48 +0100 Subject: [PATCH 05/12] Reintroduce compat with cxx98 --- 3rdparty/apriltag/common/string_util.cpp | 58 - .../simdlib/Simd/SimdBaseCustomFunctions.cpp | 2 +- 3rdparty/tinyexr/tinyexr.h | 4 + CMakeLists.txt | 103 +- cmake/templates/vpConfig.h.in | 17 + .../device/framegrabber/getRealSense2Info.cpp | 2 +- .../device/framegrabber/grabRealSense2.cpp | 3 +- .../framegrabber/grabRealSense2_T265.cpp | 2 +- .../device/framegrabber/readRealSenseData.cpp | 2 +- .../device/framegrabber/saveRealSenseData.cpp | 2 +- example/math/quadprog.cpp | 10 +- example/math/quadprog_eq.cpp | 10 +- modules/core/include/visp3/core/vpArray2D.h | 191 +- modules/core/include/visp3/core/vpCircle.h | 29 +- modules/core/include/visp3/core/vpClient.h | 2 +- modules/core/include/visp3/core/vpColVector.h | 7 + modules/core/include/visp3/core/vpColormap.h | 4 + modules/core/include/visp3/core/vpCylinder.h | 28 +- modules/core/include/visp3/core/vpDebug.h | 324 +- modules/core/include/visp3/core/vpException.h | 9 + .../core/include/visp3/core/vpFrameGrabber.h | 5 + .../include/visp3/core/vpHomogeneousMatrix.h | 14 +- modules/core/include/visp3/core/vpImage.h | 25 +- .../core/include/visp3/core/vpImagePoint.h | 12 +- .../core/include/visp3/core/vpImageTools.h | 18 +- modules/core/include/visp3/core/vpIoTools.h | 8 +- modules/core/include/visp3/core/vpLinProg.h | 2 + modules/core/include/visp3/core/vpLine.h | 23 +- modules/core/include/visp3/core/vpList.h | 30 +- modules/core/include/visp3/core/vpMatrix.h | 35 +- .../core/include/visp3/core/vpMomentCommon.h | 5 +- .../include/visp3/core/vpNullptrEmulated.h | 5 + modules/core/include/visp3/core/vpPoint.h | 49 +- modules/core/include/visp3/core/vpQuadProg.h | 2 + .../include/visp3/core/vpQuaternionVector.h | 16 +- modules/core/include/visp3/core/vpRGBa.h | 2 + modules/core/include/visp3/core/vpRGBf.h | 2 + modules/core/include/visp3/core/vpRansac.h | 13 +- .../core/include/visp3/core/vpRectOriented.h | 16 +- modules/core/include/visp3/core/vpRobust.h | 4 +- .../include/visp3/core/vpRotationMatrix.h | 66 +- modules/core/include/visp3/core/vpRowVector.h | 6 +- .../core/include/visp3/core/vpRxyzVector.h | 4 +- .../core/include/visp3/core/vpRzyxVector.h | 48 +- .../core/include/visp3/core/vpRzyzVector.h | 2 + modules/core/include/visp3/core/vpServer.h | 2 +- modules/core/include/visp3/core/vpSphere.h | 66 +- .../core/include/visp3/core/vpSubColVector.h | 2 +- modules/core/include/visp3/core/vpSubMatrix.h | 30 +- .../core/include/visp3/core/vpSubRowVector.h | 2 +- .../core/include/visp3/core/vpThetaUVector.h | 50 +- modules/core/include/visp3/core/vpTime.h | 46 +- .../include/visp3/core/vpTranslationVector.h | 38 +- modules/core/include/visp3/core/vpUniRand.h | 11 +- .../src/camera/vpColorDepthConversion.cpp | 73 +- .../src/image/private/vpImageConvert_impl.h | 6 +- modules/core/src/image/vpGaussianFilter.cpp | 2 +- modules/core/src/image/vpImageConvert.cpp | 2162 +++++--- modules/core/src/image/vpRGBa.cpp | 2 + modules/core/src/image/vpRGBf.cpp | 2 + modules/core/src/math/matrix/vpColVector.cpp | 12 +- modules/core/src/math/matrix/vpMatrix.cpp | 4648 ++++++++--------- modules/core/src/math/matrix/vpMatrix_qr.cpp | 3 +- modules/core/src/math/matrix/vpRowVector.cpp | 10 +- modules/core/src/math/matrix/vpSubMatrix.cpp | 7 +- modules/core/src/math/misc/vpMath.cpp | 10 +- modules/core/src/math/robust/vpRobust.cpp | 6 +- .../transformation/vpHomogeneousMatrix.cpp | 2 + .../transformation/vpQuaternionVector.cpp | 2 + .../math/transformation/vpRotationMatrix.cpp | 4 + .../src/math/transformation/vpRxyzVector.cpp | 2 + .../src/math/transformation/vpRzyxVector.cpp | 2 + .../src/math/transformation/vpRzyzVector.cpp | 2 + .../math/transformation/vpThetaUVector.cpp | 2 + .../transformation/vpTranslationVector.cpp | 2 + modules/core/src/tools/file/vpIoTools.cpp | 19 +- modules/core/src/tools/geometry/vpPolygon.cpp | 70 +- .../src/tools/geometry/vpRectOriented.cpp | 23 + .../core/src/tools/optimization/vpLinProg.cpp | 10 +- .../src/tools/optimization/vpQuadProg.cpp | 6 + modules/core/src/tools/time/vpTime.cpp | 3 +- modules/core/test/camera/testJsonCamera.cpp | 8 +- .../test/math/testJsonArrayConversion.cpp | 12 +- modules/core/test/math/testMath.cpp | 3 +- .../test/math/testMatrixInitialization.cpp | 21 + .../visp3/detection/vpDetectorAprilTag.h | 5 +- .../detection/vpDetectorDataMatrixCode.h | 2 +- .../include/visp3/detection/vpDetectorFace.h | 2 +- .../visp3/detection/vpDetectorQRCode.h | 6 +- .../visp3/gui/vpColorBlindFriendlyPalette.h | 2 + modules/gui/include/visp3/gui/vpD3DRenderer.h | 4 +- modules/gui/include/visp3/gui/vpDisplayGTK.h | 80 +- .../gui/include/visp3/gui/vpDisplayOpenCV.h | 74 +- .../gui/include/visp3/gui/vpDisplayWin32.h | 76 +- modules/gui/include/visp3/gui/vpDisplayX.h | 74 +- modules/gui/include/visp3/gui/vpGDIRenderer.h | 2 +- .../vpColorBlindFriendlyPalette.cpp | 7 +- modules/imgproc/src/vpRetinex.cpp | 5 +- modules/io/src/image/vpImageIo.cpp | 148 +- .../robot/include/visp3/robot/vpRobotAfma4.h | 10 +- .../robot/include/visp3/robot/vpRobotAfma6.h | 10 +- .../include/visp3/robot/vpRobotBiclops.h | 16 +- .../robot/include/visp3/robot/vpRobotCamera.h | 14 +- .../include/visp3/robot/vpRobotFlirPtu.h | 12 +- .../robot/include/visp3/robot/vpRobotFranka.h | 12 +- .../robot/include/visp3/robot/vpRobotKinova.h | 14 +- .../include/visp3/robot/vpRobotPioneer.h | 10 +- .../include/visp3/robot/vpRobotPololuPtu.h | 18 +- .../robot/include/visp3/robot/vpRobotPtu46.h | 10 +- .../include/visp3/robot/vpRobotTemplate.h | 16 +- .../visp3/robot/vpRobotUniversalRobots.h | 12 +- .../include/visp3/robot/vpRobotViper650.h | 8 +- .../include/visp3/robot/vpRobotViper850.h | 10 +- .../include/visp3/robot/vpSimulatorAfma6.h | 28 +- .../include/visp3/robot/vpSimulatorCamera.h | 14 +- .../include/visp3/robot/vpSimulatorPioneer.h | 14 +- .../visp3/robot/vpSimulatorPioneerPan.h | 14 +- .../include/visp3/robot/vpSimulatorViper850.h | 28 +- .../sensor/vpForceTorqueAtiNetFTSensor.h | 2 +- .../visp3/sensor/vpForceTorqueAtiSensor.h | 2 +- .../sensor/include/visp3/sensor/vpLaserScan.h | 5 +- .../visp3/sensor/vpOccipitalStructure.h | 6 +- .../sensor/include/visp3/sensor/vpRealSense.h | 2 +- .../include/visp3/sensor/vpRealSense2.h | 2 +- .../sensor/include/visp3/sensor/vpScanPoint.h | 2 + .../sensor/include/visp3/sensor/vpSickLDMRS.h | 2 +- .../vpOccipitalStructure.cpp | 2 +- .../src/rgb-depth/realsense/vpRealSense.cpp | 2 +- .../src/rgb-depth/realsense/vpRealSense2.cpp | 2 +- .../testOccipitalStructure_Core_images.cpp | 7 +- .../testOccipitalStructure_Core_imu.cpp | 9 +- .../testOccipitalStructure_Core_pcl.cpp | 10 +- .../test/rgb-depth/testRealSense2_D435.cpp | 3 +- .../rgb-depth/testRealSense2_D435_align.cpp | 3 +- .../rgb-depth/testRealSense2_D435_opencv.cpp | 2 +- .../rgb-depth/testRealSense2_D435_pcl.cpp | 3 +- .../test/rgb-depth/testRealSense2_SR300.cpp | 3 +- .../rgb-depth/testRealSense2_T265_images.cpp | 2 +- .../testRealSense2_T265_images_odometry.cpp | 2 +- ...tRealSense2_T265_images_odometry_async.cpp | 2 +- .../rgb-depth/testRealSense2_T265_imu.cpp | 2 +- .../testRealSense2_T265_odometry.cpp | 2 +- .../testRealSense2_T265_undistort.cpp | 2 +- .../test/rgb-depth/testRealSense_R200.cpp | 5 +- .../test/rgb-depth/testRealSense_SR300.cpp | 6 +- .../tracker/blob/include/visp3/blob/vpDot.h | 2 +- .../tracker/blob/include/visp3/blob/vpDot2.h | 8 +- modules/tracker/blob/src/dots/vpDot2.cpp | 27 +- .../include/visp3/mbt/vpMbDepthDenseTracker.h | 46 +- .../visp3/mbt/vpMbDepthNormalTracker.h | 46 +- .../include/visp3/mbt/vpMbEdgeKltTracker.h | 56 +- .../mbt/include/visp3/mbt/vpMbEdgeTracker.h | 52 +- .../include/visp3/mbt/vpMbGenericTracker.h | 154 +- .../mbt/include/visp3/mbt/vpMbKltTracker.h | 46 +- .../mbt/include/visp3/mbt/vpMbtMeEllipse.h | 2 +- .../mbt/include/visp3/mbt/vpMbtMeLine.h | 20 +- .../include/visp3/mbt/vpMbtTukeyEstimator.h | 2 +- .../mbt/src/depth/vpMbtFaceDepthDense.cpp | 6 +- .../mbt/src/depth/vpMbtFaceDepthNormal.cpp | 40 +- .../mbt/src/edge/vpMbtDistanceCircle.cpp | 16 +- .../mbt/src/edge/vpMbtDistanceCylinder.cpp | 69 +- .../mbt/src/edge/vpMbtDistanceLine.cpp | 38 +- .../tracker/mbt/src/edge/vpMbtMeEllipse.cpp | 59 +- modules/tracker/mbt/src/edge/vpMbtMeLine.cpp | 377 +- .../mbt/src/klt/vpMbtDistanceKltPoints.cpp | 4 +- .../testGenericTracker.cpp | 2 +- modules/tracker/me/include/visp3/me/vpMe.h | 85 +- .../tracker/me/include/visp3/me/vpMeEllipse.h | 57 +- .../tracker/me/include/visp3/me/vpMeLine.h | 42 +- .../tracker/me/include/visp3/me/vpMeSite.h | 200 +- .../tracker/me/include/visp3/me/vpMeTracker.h | 112 +- modules/tracker/me/src/moving-edges/vpMe.cpp | 288 +- .../me/src/moving-edges/vpMeEllipse.cpp | 704 +-- .../tracker/me/src/moving-edges/vpMeLine.cpp | 457 +- .../tracker/me/src/moving-edges/vpMeNurbs.cpp | 216 +- .../tracker/me/src/moving-edges/vpMeSite.cpp | 279 +- .../me/src/moving-edges/vpMeTracker.cpp | 196 +- .../tracker/me/src/moving-edges/vpNurbs.cpp | 12 +- modules/tracker/me/test/testJsonMe.cpp | 4 +- .../include/visp3/tt_mi/vpTemplateTrackerMI.h | 4 +- modules/vision/include/visp3/vision/vpPose.h | 1 - .../include/visp3/vision/vpPoseException.h | 2 +- .../include/visp3/vision/vpPoseFeatures.h | 70 +- .../src/pose-estimation/vpPoseDementhon.cpp | 6 +- .../src/pose-estimation/vpPoseFeatures.cpp | 4 + .../vision/src/pose-estimation/vpPoseRGBD.cpp | 2 +- .../src/pose-estimation/vpPoseRansac.cpp | 19 +- modules/vision/test/pose/testPoseFeatures.cpp | 4 + .../visp3/visual_features/vpFeatureDepth.h | 20 +- .../visp3/visual_features/vpFeatureEllipse.h | 14 +- .../visp3/visual_features/vpFeatureLine.h | 16 +- .../visual_features/vpFeatureLuminance.h | 18 +- .../visp3/visual_features/vpFeatureMoment.h | 14 +- .../visual_features/vpFeatureMomentAlpha.h | 21 +- .../visual_features/vpFeatureMomentArea.h | 13 +- .../vpFeatureMomentAreaNormalized.h | 26 +- .../visual_features/vpFeatureMomentBasic.h | 15 +- .../vpFeatureMomentCInvariant.h | 25 +- .../visual_features/vpFeatureMomentCentered.h | 15 +- .../vpFeatureMomentGravityCenter.h | 12 +- .../vpFeatureMomentGravityCenterNormalized.h | 13 +- .../visp3/visual_features/vpFeaturePoint.h | 15 +- .../visp3/visual_features/vpFeaturePoint3D.h | 16 +- .../visual_features/vpFeaturePointPolar.h | 14 +- .../visp3/visual_features/vpFeatureSegment.h | 14 +- .../visp3/visual_features/vpFeatureThetaU.h | 15 +- .../visual_features/vpFeatureTranslation.h | 14 +- .../visual_features/vpFeatureVanishingPoint.h | 17 +- .../visp3/visual_features/vpGenericFeature.h | 18 +- .../src/visual-feature/vpFeatureLuminance.cpp | 3 +- tutorial/grabber/tutorial-grabber-1394.cpp | 5 +- .../grabber/tutorial-grabber-basler-pylon.cpp | 5 +- tutorial/grabber/tutorial-grabber-bebop2.cpp | 7 +- .../grabber/tutorial-grabber-flycapture.cpp | 5 +- .../grabber/tutorial-grabber-ids-ueye.cpp | 5 +- .../tutorial-grabber-multiple-realsense.cpp | 6 +- tutorial/grabber/tutorial-grabber-opencv.cpp | 5 +- .../tutorial-grabber-realsense-T265.cpp | 6 +- .../grabber/tutorial-grabber-realsense.cpp | 5 +- ...torial-grabber-rgbd-D435-structurecore.cpp | 5 +- .../tutorial-grabber-structure-core.cpp | 5 +- tutorial/grabber/tutorial-grabber-v4l2.cpp | 5 +- tutorial/image/tutorial-image-colormap.cpp | 5 +- .../hough-transform/tutorial-circle-hough.cpp | 11 +- .../tutorial-mb-generic-tracker-read.cpp | 6 +- .../tutorial-mb-generic-tracker-save.cpp | 12 + 226 files changed, 7501 insertions(+), 6234 deletions(-) diff --git a/3rdparty/apriltag/common/string_util.cpp b/3rdparty/apriltag/common/string_util.cpp index e838e0498d..7a53b5b4cc 100644 --- a/3rdparty/apriltag/common/string_util.cpp +++ b/3rdparty/apriltag/common/string_util.cpp @@ -36,11 +36,6 @@ either expressed or implied, of the Regents of The University of Michigan. #include "string_util.h" #include "zarray.h" -// fix va_copy missing with msvc11 Visual 2012 -#ifdef _MSC_VER -#define my_va_copy(dest, src) (dest = src) -#endif - struct string_buffer { char *s; @@ -50,59 +45,6 @@ struct string_buffer #define MIN_PRINTF_ALLOC 16 -char *sprintf_alloc(const char *fmt, ...) -{ - assert(fmt != NULL); - - va_list args; - - va_start(args,fmt); - char *buf = vsprintf_alloc(fmt, args); - va_end(args); - - return buf; -} - -char *vsprintf_alloc(const char *fmt, va_list orig_args) -{ - assert(fmt != NULL); - - int size = MIN_PRINTF_ALLOC; - char *buf = (char *)malloc(size * sizeof(char)); - - int returnsize; - va_list args; - -#ifdef _MSC_VER - my_va_copy(args, orig_args); -#else - va_copy(args, orig_args); -#endif - returnsize = vsnprintf(buf, size, fmt, args); - va_end(args); - - // it was successful - if (returnsize < size) { - return buf; - } - - // otherwise, we should try again - free(buf); - size = returnsize + 1; - buf = (char *)malloc(size * sizeof(char)); - -#ifdef _MSC_VER - my_va_copy(args, orig_args); -#else - va_copy(args, orig_args); -#endif - returnsize = vsnprintf(buf, size, fmt, args); - va_end(args); - - assert(returnsize <= size); - return buf; -} - char *_str_concat_private(const char *first, ...) { size_t len = 0; diff --git a/3rdparty/simdlib/Simd/SimdBaseCustomFunctions.cpp b/3rdparty/simdlib/Simd/SimdBaseCustomFunctions.cpp index 9f3b37f9a6..45f68939c1 100644 --- a/3rdparty/simdlib/Simd/SimdBaseCustomFunctions.cpp +++ b/3rdparty/simdlib/Simd/SimdBaseCustomFunctions.cpp @@ -195,7 +195,7 @@ namespace Simd { for (size_t i = 0; i < size; i++) { int diff = img1[i] - img2[i] + 128; - imgDiff[i] = static_cast(std::max(std::min(diff, 255), 0)); + imgDiff[i] = static_cast(std::max(std::min(diff, 255), 0)); } } diff --git a/3rdparty/tinyexr/tinyexr.h b/3rdparty/tinyexr/tinyexr.h index 9245e1a904..cd6a1ef52a 100644 --- a/3rdparty/tinyexr/tinyexr.h +++ b/3rdparty/tinyexr/tinyexr.h @@ -7385,7 +7385,11 @@ static size_t SaveEXRNPartImageToMemory(const EXRImage* exr_images, { size_t len = 0; if ((len = strlen(exr_headers[i]->name)) > 0) { +#if TINYEXR_HAS_CXX11 partnames.emplace(exr_headers[i]->name); +#else + partnames.insert(std::string(exr_headers[i]->name)); +#endif if (partnames.size() != i + 1) { SetErrorMessage("'name' attributes must be unique for a multi-part file", err); return 0; diff --git a/CMakeLists.txt b/CMakeLists.txt index 0c63f5b145..e9ab927636 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -622,19 +622,7 @@ VP_OPTION(USE_ZBAR ZBAR "" "Include zbar support" "" O VP_OPTION(USE_DMTX DMTX "" "Include dmtx support" "" ON IF NOT WINRT AND NOT IOS) VP_OPTION(USE_PCL PCL QUIET "Include Point Cloud Library support" "" ON IF NOT WINRT AND NOT IOS) VP_OPTION(USE_TENSORRT TensorRT "" "Include TensorRT support" "" ON IF NOT WINRT AND NOT IOS) -VP_OPTION(USE_NLOHMANN_JSON nlohmann_json QUIET "Include nlohmann json support" "" ON IF (VISP_CXX_STANDARD GREATER VISP_CXX_STANDARD_98)) - -# ---------------------------------------------------------------------------- -# 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++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.") - unset(USE_MAVSDK) - set(USE_MAVSDK OFF CACHE BOOL "Include mavsdk support for mavlink compatible devices" FORCE) - endif() -endif() +VP_OPTION(USE_NLOHMANN_JSON nlohmann_json QUIET "Include nlohmann json support" "" ON) # Upgrade c++ standard to 14 for pcl 1.9.1.99 that enables by default c++ 14 standard if(USE_PCL) @@ -648,27 +636,49 @@ if(USE_PCL) # That's why here, we are using vp_find_pcl() macro that will set PCL_DEPS_INCLUDE_DIRS and PCL_DEPS_LIBRARIES # that contains also VTK material location. vp_find_pcl(PCL_LIBRARIES PCL_DEPS_INCLUDE_DIRS PCL_DEPS_LIBRARIES) - if(PCL_VERSION VERSION_GREATER 1.9.1) +endif() + +# ---------------------------------------------------------------------------- +# 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++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.") + unset(USE_MAVSDK) + set(USE_MAVSDK OFF CACHE BOOL "Include mavsdk support for mavlink compatible devices" FORCE) + endif() +endif() + +if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_14) + if(USE_FTIITSDK) + message(WARNING "IIT force-torque SDK 3rd party was detected and needs at least c++14 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable IIT force-torque usage turning USE_OPENCV=OFF.") + unset(USE_FTIITSDK) + set(USE_FTIITSDK OFF CACHE BOOL "Include IIT force-torque SDK support" FORCE) + endif() + if(USE_PCL AND (PCL_VERSION VERSION_GREATER 1.9.1)) # pcl > 1.9.1 requires c++14 - # if c++14 option is OFF, force to c++14 - if((VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_14) AND CXX14_STANDARD_FOUND) - message(WARNING "pcl ${PCL_VERSION} 3rd party was detected and needs c++14 compiler flags that is turned off. Thus to enable pcl usage we turn USE_CXX_STANDARD=14.") - set(USE_CXX_STANDARD "14" CACHE STRING "cxx standard" FORCE) # Update cmake-gui option - unset(CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_14}) # for vpConfig.h - endif() + message(WARNING "pcl 3rd party was detected and needs at least c++14 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable pcl usage turning USE_PCL=OFF.") + unset(USE_PCL) + set(USE_PCL OFF CACHE BOOL "Include pcl support" FORCE) endif() endif() -# Upgrade c++ standard to 14 for IIT force-torque SDK that needs at least c++ 14 standard -if(USE_FTIITSDK) - if((VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_14) AND CXX14_STANDARD_FOUND) - message(WARNING "IIT force-torque SDK 3rd party was detected and needs c++14 compiler flags that is turned off. Thus to enable IIT SDK usage we turn USE_CXX_STANDARD=14.") - set(USE_CXX_STANDARD "14" CACHE STRING "cxx standard" FORCE) # Update cmake-gui option - unset(CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) - set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_14}) # for vpConfig.h +if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_11) + if(USE_OPENCV) + message(WARNING "OpenCV 3rd party was detected and needs at least c++11 standard 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() + if(USE_NLOHMANN_JSON) + message(WARNING "nlohmann json 3rd party was detected and needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable nlohmann json usage turning USE_NLOHMANN_JSON=OFF.") + unset(USE_NLOHMANN_JSON) + set(USE_NLOHMANN_JSON OFF CACHE BOOL "Include nlohmann json 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 realsense2 usage turning USE_REALSENSE2=OFF.") + unset(USE_REALSENSE2) + set(USE_REALSENSE2 OFF CACHE BOOL "Include librealsense2 support" FORCE) endif() endif() @@ -682,17 +692,41 @@ 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 built-in library" "" ON) VP_OPTION(WITH_POLOLU "" "" "Build rapa pololu as built-in library" "" ON IF (NOT WINRT) AND (NOT IOS) AND (NOT ANDROID)) VP_OPTION(WITH_PUGIXML "" "" "Use pugixml built-in third-party" "" ON) VP_OPTION(WITH_SIMDLIB "" "" "Use simdlib built-in third-party" "" ON) VP_OPTION(WITH_STBIMAGE "" "" "Use std_image built-in third-party" "" ON) VP_OPTION(WITH_TINYEXR "" "" "Use tinyexr built-in third-party" "" ON) +if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_11) + if(WITH_CATCH2) + message(WARNING "catch2 3rd party needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable catch2 usage turning WITH_CATCH2=OFF.") + unset(WITH_CATCH2) + set(WITH_CATCH2 OFF CACHE BOOL "Use catch2 built-in library" FORCE) + endif() + if(WITH_POLOLU) + message(WARNING "pololu 3rd party needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable pololu usage turning WITH_POLOLU=OFF.") + unset(WITH_POLOLU) + set(WITH_POLOLU OFF CACHE BOOL "Build rapa pololu as built-in library" FORCE) + endif() + if(WITH_QBDEVICE) + message(WARNING "qbdevice-api 3rd party needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable qbdevice usage turning WITH_QBDEVICE=OFF.") + unset(WITH_QBDEVICE) + set(WITH_QBDEVICE OFF CACHE BOOL "Build rapa pololu as built-in library" FORCE) + endif() + if(WITH_TAKKTILE2) + message(WARNING "Right Hand takktile2 3rd party needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable takktile2 usage turning WITH_TAKKTILE2=OFF.") + unset(WITH_TAKKTILE2) + set(WITH_TAKKTILE2 OFF CACHE BOOL "Build rapa pololu as built-in library" FORCE) + endif() +endif() + # ---------------------------------------------------------------------------- -# Check for specific functions. Should be after cxx standard detection in VISPDetectCXXStandard.cmake and potential modification depending on pcl, realsense2, libfranka +# Check for specific functions. Should be after cxx standard detection in VISPDetectCXXStandard.cmake and +# potential modification depending on pcl, realsense2, libfranka # ---------------------------------------------------------------------------- VP_CHECK_PACKAGE(IsNaN) VP_CHECK_PACKAGE(IsInf) @@ -1027,6 +1061,7 @@ VP_SET(VISP_HAVE_DC1394_FIND_CAMERAS TRUE IF (USE_DC1394 AND DC1394_FIND_CAM VP_SET(VISP_HAVE_D3D9 TRUE IF USE_DIRECT3D) # for header vpConfig.h VP_SET(VISP_HAVE_GTK TRUE IF USE_GTK2) # for header vpConfig.h VP_SET(VISP_HAVE_XRANDR TRUE IF XRANDR) # for header vpConfig.h +VP_SET(VISP_HAVE_NULLPTR TRUE IF HAVE_NULLPTR) # for header vpConfig.h # Check if libfreenect dependencies (ie libusb-1.0 and threads) are available if(USE_LIBFREENECT AND USE_LIBUSB_1 AND USE_THREADS) diff --git a/cmake/templates/vpConfig.h.in b/cmake/templates/vpConfig.h.in index b54501a9bb..9f8ab7efb5 100644 --- a/cmake/templates/vpConfig.h.in +++ b/cmake/templates/vpConfig.h.in @@ -561,6 +561,23 @@ # define VISP_HAVE_DATASET_VERSION ${VISP_HAVE_DATASET_VERSION} #endif +// Defined if nullptr is available +#cmakedefine VISP_HAVE_NULLPTR + +// Emulate nullptr when not available when cxx98 is enabled +#if (!defined(VISP_HAVE_NULLPTR)) && (__cplusplus == 199711L) +#include +#endif + +// Macro to be able to add override keyword +#ifndef vp_override + #if (__cplusplus >= 201103L) || (defined(_MSC_VER) && _MSC_VER >= 1600) + #define vp_override override + #else + #define vp_override + #endif +#endif + // Handle portable symbol export. // Defining manually which symbol should be exported is required // under Windows whether MinGW or MSVC is used. diff --git a/example/device/framegrabber/getRealSense2Info.cpp b/example/device/framegrabber/getRealSense2Info.cpp index 3346e2ef2e..bd8c2f5dd2 100644 --- a/example/device/framegrabber/getRealSense2Info.cpp +++ b/example/device/framegrabber/getRealSense2Info.cpp @@ -42,7 +42,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) int main() { diff --git a/example/device/framegrabber/grabRealSense2.cpp b/example/device/framegrabber/grabRealSense2.cpp index 259285372d..6d2b7a4bdd 100644 --- a/example/device/framegrabber/grabRealSense2.cpp +++ b/example/device/framegrabber/grabRealSense2.cpp @@ -44,7 +44,8 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #ifdef VISP_HAVE_PCL #include diff --git a/example/device/framegrabber/grabRealSense2_T265.cpp b/example/device/framegrabber/grabRealSense2_T265.cpp index 959fe60067..26ac71efdf 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) && \ +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)&& \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() diff --git a/example/device/framegrabber/readRealSenseData.cpp b/example/device/framegrabber/readRealSenseData.cpp index ac2860bdf3..d7ad1c9336 100644 --- a/example/device/framegrabber/readRealSenseData.cpp +++ b/example/device/framegrabber/readRealSenseData.cpp @@ -40,7 +40,7 @@ #include -#if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include #include diff --git a/example/device/framegrabber/saveRealSenseData.cpp b/example/device/framegrabber/saveRealSenseData.cpp index 06e56f8e45..e22dbe4b08 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)) && \ +#if (defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2)) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PUGIXML) #include diff --git a/example/math/quadprog.cpp b/example/math/quadprog.cpp index 26324c8b1e..58c96eb47b 100644 --- a/example/math/quadprog.cpp +++ b/example/math/quadprog.cpp @@ -47,7 +47,7 @@ #include #include -#if defined(VISP_HAVE_LAPACK) +#if defined(VISP_HAVE_LAPACK) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include @@ -177,6 +177,14 @@ 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 079f34a77c..0605f4e7c6 100644 --- a/example/math/quadprog_eq.cpp +++ b/example/math/quadprog_eq.cpp @@ -47,7 +47,7 @@ #include #include -#if defined(VISP_HAVE_LAPACK) +#if defined(VISP_HAVE_LAPACK) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include "qp_plot.h" #include @@ -204,6 +204,14 @@ 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/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index 0d15edd28d..409c882ded 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -50,76 +50,76 @@ #endif /*! - \class vpArray2D - \ingroup group_core_matrices - - \brief Implementation of a generic 2D array used as base class for matrices - and vectors. - - This class implements a 2D array as a template class and all the basic - functionalities common to matrices and vectors. More precisely: - - concerning matrices, vpMatrix but also specific containers such as twist - (vpVelocityTwistMatrix and vpForceTwistMatrix), homogeneous - (vpHomogeneousMatrix), rotation (vpRotationMatrix) and homography - (vpHomography) matrices inherit from vpArray2D. - - concerning vectors, vpColVector, vpRowVector but also specific containers - describing the pose (vpPoseVector) and the rotation (vpRotationVector) - inherit also from vpArray2D. - - The code below shows how to create a 2-by-3 array of doubles, set the element values and access them: - \code -#include a(2, 3); - a[0][0] = -1; a[0][1] = -2; a[0][2] = -3; - a[1][0] = 4; a[1][1] = 5.5; a[1][2] = 6; - - std::cout << "a:" << std::endl; - for (unsigned int i = 0; i < a.getRows(); i++) { - for (unsigned int j = 0; j < a.getCols(); j++) { - std::cout << a[i][j] << " "; - } - std::cout << std::endl; - } -} - \endcode - Once build, this previous code produces the following output: - \code -a: --1 -2 -3 -4 5.5 6 - \endcode - If ViSP is build with c++11 enabled, you can do the same using: - \code -#include a{ {-1, -2, -3}, {4, 5.5, 6.0f} }; - std::cout << "a:\n" << a << std::endl; -} - \endcode - The array could also be initialized using operator=(const std::initializer_list< std::initializer_list< Type > > &) - \code -int main() -{ - vpArray2D a; - a = { {-1, -2, -3}, {4, 5.5, 6.0f} }; -} - \endcode - - You can also use reshape() function: - \code -#include a{ -1, -2, -3, 4, 5.5, 6.0f }; - a.reshape(2, 3); -} - \endcode + * \class vpArray2D + * \ingroup group_core_matrices + * + * \brief Implementation of a generic 2D array used as base class for matrices + * and vectors. + * + * This class implements a 2D array as a template class and all the basic + * functionalities common to matrices and vectors. More precisely: + * - concerning matrices, vpMatrix but also specific containers such as twist + * (vpVelocityTwistMatrix and vpForceTwistMatrix), homogeneous + * (vpHomogeneousMatrix), rotation (vpRotationMatrix) and homography + * (vpHomography) matrices inherit from vpArray2D. + * - concerning vectors, vpColVector, vpRowVector but also specific containers + * describing the pose (vpPoseVector) and the rotation (vpRotationVector) + * inherit also from vpArray2D. + * + * The code below shows how to create a 2-by-3 array of doubles, set the element values and access them: + * \code + * #include a(2, 3); + * a[0][0] = -1; a[0][1] = -2; a[0][2] = -3; + * a[1][0] = 4; a[1][1] = 5.5; a[1][2] = 6; + * + * std::cout << "a:" << std::endl; + * for (unsigned int i = 0; i < a.getRows(); i++) { + * for (unsigned int j = 0; j < a.getCols(); j++) { + * std::cout << a[i][j] << " "; + * } + * std::cout << std::endl; + * } + * } + * \endcode + * Once build, this previous code produces the following output: + * \code + * a: + * -1 -2 -3 + * 4 5.5 6 + * \endcode + * If ViSP is build with c++11 enabled, you can do the same using: + * \code + * #include a{ {-1, -2, -3}, {4, 5.5, 6.0f} }; + * std::cout << "a:\n" << a << std::endl; + * } + * \endcode + * The array could also be initialized using operator=(const std::initializer_list< std::initializer_list< Type > > &) + * \code + * int main() + * { + * vpArray2D a; + * a = { {-1, -2, -3}, {4, 5.5, 6.0f} }; + * } + * \endcode + * + * You can also use reshape() function: + * \code + * #include a{ -1, -2, -3, 4, 5.5, 6.0f }; + * a.reshape(2, 3); + * } + * \endcode */ template class vpArray2D { @@ -139,16 +139,21 @@ template class vpArray2D public: /*! - Basic constructor of a 2D array. - Number of columns and rows are set to zero. - */ + * Basic constructor of a 2D array. + * Number of columns and rows are set to zero. + */ vpArray2D() : rowNum(0), colNum(0), rowPtrs(nullptr), dsize(0), data(nullptr) { } /*! Copy constructor of a 2D array. */ vpArray2D(const vpArray2D &A) - : vpArray2D() + : +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher + vpArray2D() +#else + rowNum(0), colNum(0), rowPtrs(nullptr), dsize(0), data(nullptr) +#endif { resize(A.rowNum, A.colNum, false, false); memcpy(data, A.data, (size_t)rowNum * (size_t)colNum * sizeof(Type)); @@ -161,7 +166,12 @@ template class vpArray2D \param c : Array number of columns. */ vpArray2D(unsigned int r, unsigned int c) - : vpArray2D() + : +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher + vpArray2D() +#else + rowNum(0), colNum(0), rowPtrs(nullptr), dsize(0), data(nullptr) +#endif { resize(r, c); } @@ -174,12 +184,18 @@ template class vpArray2D \param val : Each element of the array is set to \e val. */ vpArray2D(unsigned int r, unsigned int c, Type val) - : vpArray2D() + : +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher + vpArray2D() +#else + rowNum(0), colNum(0), rowPtrs(nullptr), dsize(0), data(nullptr) +#endif { resize(r, c, false, false); *this = val; } +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher vpArray2D(vpArray2D &&A) noexcept { rowNum = A.rowNum; @@ -229,10 +245,11 @@ template class vpArray2D std::copy(it->begin(), it->end(), rowPtrs[i]); } } +#endif /*! - Destructor that deallocate memory. - */ + * Destructor that deallocate memory. + */ virtual ~vpArray2D() { if (data != nullptr) { @@ -437,6 +454,7 @@ template class vpArray2D return *this; } +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher vpArray2D &operator=(vpArray2D &&other) noexcept { if (this != &other) { @@ -489,6 +507,7 @@ 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 @@ -631,7 +650,7 @@ template class vpArray2D h += c; } if (header != nullptr) { -#if defined(__MINGW32__) || \ +#if defined(__MINGW32__) || \ !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX snprintf(header, h.size() + 1, "%s", h.c_str()); #else @@ -728,7 +747,7 @@ template class vpArray2D if (header != nullptr) { std::string h_ = h.substr(0, h.size() - 1); // Remove last '\n' char -#if defined(__MINGW32__) || \ +#if defined(__MINGW32__) || \ !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX snprintf(header, h_.size() + 1, "%s", h_.c_str()); #else @@ -824,7 +843,9 @@ template class vpArray2D vpArray2D M(3,4); vpArray2D::saveYAML("matrix.yml", M, "example: a YAML-formatted header"); vpArray2D::saveYAML("matrixIndent.yml", M, "example:\n - a YAML-formatted \ - header\n - with inner indentation"); \endcode Content of matrix.yml: + header\n - with inner indentation"); + \endcode + Content of matrix.yml: \code example: a YAML-formatted header rows: 3 @@ -941,7 +962,7 @@ template class vpArray2D \image html vpMatrix-conv2-mode.jpg "Convolution mode: full, same, valid (image credit: Theano doc)." \note This is a very basic implementation that does not use FFT. - */ + */ static void conv2(const vpArray2D &M, const vpArray2D &kernel, vpArray2D &res, const std::string &mode); /*! @@ -1215,7 +1236,7 @@ inline void from_json(const nlohmann::json &j, vpArray2D &array) } unsigned int ncols = 0; bool first = true; - for (const auto &item: j) { // Find number of columns, validate that all rows have same number of cols + for (const auto &item : j) { // Find number of columns, validate that all rows have same number of cols if (!item.is_array()) { throw vpException(vpException::badValue, "Trying to instantiate a 2D array with a JSON object that is not an array of array"); } @@ -1229,7 +1250,7 @@ inline void from_json(const nlohmann::json &j, vpArray2D &array) } array.resize(nrows, ncols); unsigned i = 0; - for (const auto &item: j) { + for (const auto &item : j) { std::vector row = item; std::copy(row.begin(), row.end(), array.rowPtrs[i]); ++i; @@ -1246,7 +1267,7 @@ inline void from_json(const nlohmann::json &j, vpArray2D &array) throw vpException(vpException::badValue, ss.str()); } unsigned i = 0; - for (const auto &jValue: jData) { + for (const auto &jValue : jData) { array.data[i] = jValue; ++i; } diff --git a/modules/core/include/visp3/core/vpCircle.h b/modules/core/include/visp3/core/vpCircle.h index c491f08985..5e76dded5f 100644 --- a/modules/core/include/visp3/core/vpCircle.h +++ b/modules/core/include/visp3/core/vpCircle.h @@ -88,20 +88,21 @@ class VISP_EXPORT vpCircle : public vpForwardProjection vpCircle(); explicit vpCircle(const vpColVector &oP); vpCircle(double oA, double oB, double oC, double oX, double oY, double oZ, double R); - virtual ~vpCircle() override; - - void changeFrame(const vpHomogeneousMatrix &noMo, vpColVector &noP) const override; - void changeFrame(const vpHomogeneousMatrix &cMo) override; + virtual ~vpCircle() vp_override; + void changeFrame(const vpHomogeneousMatrix &noMo, vpColVector &noP) const vp_override; + void changeFrame(const vpHomogeneousMatrix &cMo) vp_override; void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; + void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, + const vpColor &color = vpColor::green, unsigned int thickness = 1) vp_override; + void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); - void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &color = vpColor::green, unsigned int thickness = 1) override; void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); - vpCircle *duplicate() const override; + + vpCircle *duplicate() const vp_override; double get_x() const { return p[0]; } double get_y() const { return p[1]; } @@ -120,10 +121,10 @@ class VISP_EXPORT vpCircle : public vpForwardProjection double getR() const { return cP[6]; } - void projection() override; - void projection(const vpColVector &cP, vpColVector &p) const override; + void projection() vp_override; + void projection(const vpColVector &cP, vpColVector &p) const vp_override; + void setWorldCoordinates(const vpColVector &oP) vp_override; - void setWorldCoordinates(const vpColVector &oP) override; void setWorldCoordinates(double oA, double oB, double oC, double oX, double oY, double oZ, double R); //################### @@ -133,13 +134,13 @@ class VISP_EXPORT vpCircle : public vpForwardProjection const double &theta, double &i, double &j); protected: - void init() override; + void init() vp_override; public: #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) /*! @name Deprecated functions - */ + */ //@{ /*! * \deprecated You should rather use get_n20(). @@ -152,7 +153,7 @@ class VISP_EXPORT vpCircle : public vpForwardProjection * \deprecated You should rather use get_n11(). * This function is incorrectly named and is confusing since it * returns second order centered moments of the ellipse normalized - * by its area that corresponds to \f$n_11 = mu_11/a\f$. + * by its area that corresponds to \f$n_11 = mu@name Deprecated functions_11/a\f$. */ vp_deprecated double get_mu11() const { return p[3]; } /*! diff --git a/modules/core/include/visp3/core/vpClient.h b/modules/core/include/visp3/core/vpClient.h index 6550491ad5..ed64dc76a8 100644 --- a/modules/core/include/visp3/core/vpClient.h +++ b/modules/core/include/visp3/core/vpClient.h @@ -168,7 +168,7 @@ class VISP_EXPORT vpClient : public vpNetwork public: vpClient(); - virtual ~vpClient() override; + virtual ~vpClient() vp_override; bool connectToHostname(const std::string &hostname, const unsigned int &port_serv); bool connectToIP(const std::string &ip, const unsigned int &port_serv); diff --git a/modules/core/include/visp3/core/vpColVector.h b/modules/core/include/visp3/core/vpColVector.h index 518b461043..435d5abea0 100644 --- a/modules/core/include/visp3/core/vpColVector.h +++ b/modules/core/include/visp3/core/vpColVector.h @@ -241,14 +241,19 @@ class VISP_EXPORT vpColVector : public vpArray2D */ vpColVector(const std::vector &v); +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! * Move constructor that take rvalue. */ vpColVector(vpColVector &&v); +#endif + +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher vpColVector(const std::initializer_list &list) : vpArray2D(static_cast(list.size()), 1) { std::copy(list.begin(), list.end(), data); } +#endif /*! * Removes all elements from the vector (which are destroyed), @@ -627,6 +632,7 @@ class VISP_EXPORT vpColVector : public vpArray2D */ vpColVector &operator=(double x); +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! * Overloaded move assignment operator taking rvalue. */ @@ -656,6 +662,7 @@ 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 2609e6f3a0..74147bcdcd 100644 --- a/modules/core/include/visp3/core/vpColormap.h +++ b/modules/core/include/visp3/core/vpColormap.h @@ -93,7 +93,11 @@ class VISP_EXPORT vpColormap private: vpColormapType m_colormapType; +#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 unsigned char m_colormapSrgbBytes[256][3] = {}; +#else + unsigned char m_colormapSrgbBytes[256][3]; +#endif }; #endif diff --git a/modules/core/include/visp3/core/vpCylinder.h b/modules/core/include/visp3/core/vpCylinder.h index 6f402f7226..aaf327d2fd 100644 --- a/modules/core/include/visp3/core/vpCylinder.h +++ b/modules/core/include/visp3/core/vpCylinder.h @@ -108,27 +108,27 @@ class VISP_EXPORT vpCylinder : public vpForwardProjection explicit vpCylinder(const vpColVector &oP); vpCylinder(double oA, double oB, double oC, double oX, double oY, double oZ, double R); - void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const override; - void changeFrame(const vpHomogeneousMatrix &cMo) override; + void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const vp_override; + void changeFrame(const vpHomogeneousMatrix &cMo) vp_override; double computeZ(double x, double y) const; void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &color = vpColor::green, unsigned int thickness = 1) override; + const vpColor &color = vpColor::green, unsigned int thickness = 1) vp_override; void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); - vpCylinder *duplicate() const override; + vpCylinder *duplicate() const vp_override; - /*! - * Return the \f$\rho_1\f$ parameter of the line corresponding to the - * projection of the cylinder in the image plane. - * \sa getTheta1() - */ +/*! + * Return the \f$\rho_1\f$ parameter of the line corresponding to the + * projection of the cylinder in the image plane. + * \sa getTheta1() + */ double getRho1() const { return p[0]; } /*! * Return the \f$\theta_1\f$ parameter of the line corresponding to the @@ -185,12 +185,12 @@ class VISP_EXPORT vpCylinder : public vpForwardProjection */ double getR() const { return cP[6]; } - void init() override; + void init() vp_override; - void projection() override; - void projection(const vpColVector &cP, vpColVector &p) const override; + void projection() vp_override; + void projection(const vpColVector &cP, vpColVector &p) const vp_override; - void setWorldCoordinates(const vpColVector &oP) override; + void setWorldCoordinates(const vpColVector &oP) vp_override; void setWorldCoordinates(double oA, double oB, double oC, double oX, double oY, double oZ, double R); }; diff --git a/modules/core/include/visp3/core/vpDebug.h b/modules/core/include/visp3/core/vpDebug.h index 04c99805a7..5b3eee6b8b 100644 --- a/modules/core/include/visp3/core/vpDebug.h +++ b/modules/core/include/visp3/core/vpDebug.h @@ -77,11 +77,11 @@ - Macros for tracing: vpTRACE(), vpERROR_TRACE(), vpIN_FCT() and vpOUT_FCT() work like printf - with carreer return at the end of the string, while vpCTRACE() and + with career return at the end of the string, while vpCTRACE() and vpCERROR() work like the C++ output streams std::cout and std::cerr. - - Macros for debuging: vpDEBUG_TRACE(level) and vpDERROR_TRACE(level) + - Macros for debugging: vpDEBUG_TRACE(level) and vpDERROR_TRACE(level) work like printf, but print only if the tracing level \e level is greater than the debug level VP_DEBUG_MODE macro. vpCDEBUG(level) work like the C++ output stream std::cout. vpDEBUG_ENABLE(level) is @@ -91,41 +91,41 @@ The example below shows how to use these macros. \code -#define VP_TRACE // Activate the trace mode -#define VP_DEBUG // Activate the debug mode -#define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 + #define VP_TRACE // Activate the trace mode + #define VP_DEBUG // Activate the debug mode + #define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 -#include + #include -int main() -{ - vpIN_FCT("main()"); + int main() + { + vpIN_FCT("main()"); - // Check the active debug levels - std::cout << "Debug level 1 active: " << vpDEBUG_ENABLE(1) << std::endl; - std::cout << "Debug level 2 active: " << vpDEBUG_ENABLE(2) << std::endl; - std::cout << "Debug level 3 active: " << vpDEBUG_ENABLE(3) << std::endl; + // Check the active debug levels + std::cout << "Debug level 1 active: " << vpDEBUG_ENABLE(1) << std::endl; + std::cout << "Debug level 2 active: " << vpDEBUG_ENABLE(2) << std::endl; + std::cout << "Debug level 3 active: " << vpDEBUG_ENABLE(3) << std::endl; - // C-like debug printings - vpTRACE("C-like trace"); // stdout + // C-like debug printings + vpTRACE("C-like trace"); // stdout - // Printing depend only VP_DEBUG_MODE value is >= 1 - vpTRACE(1, "C-like trace level 1"); // stdout - vpERROR_TRACE(1, "C-like error trace level 1"); // stderr + // Printing depend only VP_DEBUG_MODE value is >= 1 + vpTRACE(1, "C-like trace level 1"); // stdout + vpERROR_TRACE(1, "C-like error trace level 1"); // stderr - // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 - vpDEBUG_TRACE(2, "C-like debug trace level 2"); // stdout - vpDERROR_TRACE(2, "C-like error trace level 2"); // stderr + // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 + vpDEBUG_TRACE(2, "C-like debug trace level 2"); // stdout + vpDERROR_TRACE(2, "C-like error trace level 2"); // stderr - // C++-like debug printings - vpCTRACE << "C++-like trace" << std::endl; // stdout - vpCERROR << "C++-like error trace" << std::endl; // stderr + // C++-like debug printings + vpCTRACE << "C++-like trace" << std::endl; // stdout + vpCERROR << "C++-like error trace" << std::endl; // stderr - // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 - vpCDEBUG(2) << "C++-like debug trace level 2" << std::endl; // stdout + // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 + vpCDEBUG(2) << "C++-like debug trace level 2" << std::endl; // stdout - vpOUT_FCT("main()"); -} + vpOUT_FCT("main()"); + } \endcode */ @@ -154,13 +154,12 @@ class vpTraceOutput */ vpTraceOutput(const char *file, int line, const char *func, bool error = false, const char *s = nullptr) : currentFile(file), currentFunc(func), currentLine(line), err(error), header(s) - { - } + { } /*! Displays a string if the debug level is inferior to VP_DEBUG_MODE. \param level Level of this message. - \param format Formating string. + \param format String format. */ void operator()(int level, const char *format, ...) { @@ -216,8 +215,9 @@ class vpTraceOutput // if we want to write to std::cerr/stderr if (err) { // first writes the header if there is one - if (header != nullptr) + if (header != nullptr) { std::cerr << header; + } // then writes the recorded namefile, function and line std::cerr << "!!\t" << currentFile << ": " << currentFunc << "(#" << currentLine << ") : "; // and finally writes the message passed to () operator. @@ -225,10 +225,12 @@ class vpTraceOutput fprintf(stderr, "\n"); // flushes the buffer fflush(stderr); - } else { + } + else { // first writes the header if there is one - if (header != nullptr) + if (header != nullptr) { std::cout << header; + } // then writes the recorded namefile, function and line std::cout << currentFile << ": " << currentFunc << "(#" << currentLine << ") : "; // and finally writes the message passed to () operator. @@ -240,12 +242,9 @@ class vpTraceOutput } }; -/* ------------------------------------------------------------------------- - */ -/* --- vpTRACE IN/OUT FONCTION --------------------------------------------- - */ -/* ------------------------------------------------------------------------- - */ +/* ------------------------------------------------------------------------- */ +/* --- vpTRACE IN/OUT FONCTION --------------------------------------------- */ +/* ------------------------------------------------------------------------- */ #ifdef VP_TRACE // Activate the trace mode @@ -254,15 +253,15 @@ class vpTraceOutput Works like vpTRACE() and should be used at the beginning of a function. \code -#define VP_TRACE // To activate the trace mode -#include + #define VP_TRACE // To activate the trace mode + #include -int main() -{ - vpIN_FCT("main()"); - // the body of the main() function - vpOUT_FCT("main()"); -} + int main() + { + vpIN_FCT("main()"); + // the body of the main() function + vpOUT_FCT("main()"); + } \endcode \sa vpOUT_FCT @@ -274,15 +273,15 @@ int main() Works like vpTRACE() and should be used at the end of a function. \code -#define VP_TRACE // To activate the trace mode -#include + #define VP_TRACE // To activate the trace mode + #include -int main() -{ - vpIN_FCT("main()"); - // the body of the main() function - vpOUT_FCT("main()"); -} + int main() + { + vpIN_FCT("main()"); + // the body of the main() function + vpOUT_FCT("main()"); + } \endcode \sa vpIN_FCT @@ -291,41 +290,38 @@ int main() #else // #ifdef VP_TRACE -inline void vpIN_FCT(const char * /* a */, ...) {} -inline void vpOUT_FCT(const char * /* a */, ...) {} +inline void vpIN_FCT(const char * /* a */, ...) { } +inline void vpOUT_FCT(const char * /* a */, ...) { } #endif // #ifdef VP_TRACE -/* -------------------------------------------------------------------------- - */ -/* --- vpTRACE -------------------------------------------------------------- - */ -/* -------------------------------------------------------------------------- - */ +/* -------------------------------------------------------------------------- */ +/* --- vpTRACE -------------------------------------------------------------- */ +/* -------------------------------------------------------------------------- */ #ifdef VP_TRACE /*! \ingroup group_core_debug Used to display trace messages on the standard stream (C++). - Use like this : vpCTRACE<<"my message"< + #include -int main() -{ - // C++-like debug printings - vpCTRACE << "C++-like trace" << std::endl; // stdout - vpCERROR << "C++-like error trace" << std::endl; // stderr + int main() + { + // C++-like debug printings + vpCTRACE << "C++-like trace" << std::endl; // stdout + vpCERROR << "C++-like error trace" << std::endl; // stderr - // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 - vpCDEBUG(2) << "C++-like debug trace level 2" << std::endl; // stdout -} + // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 + vpCDEBUG(2) << "C++-like debug trace level 2" << std::endl; // stdout + } \endcode \sa vpTRACE(), vpCERROR(), vpCDEBUG() @@ -338,28 +334,26 @@ int main() Use like this : vpCERROR<<"my message"< + #include -int main() -{ - // C++-like debug printings - vpCTRACE << "C++-like trace" << std::endl; // stdout - vpCERROR << "C++-like error trace" << std::endl; // stderr + int main() + { + // C++-like debug printings + vpCTRACE << "C++-like trace" << std::endl; // stdout + vpCERROR << "C++-like error trace" << std::endl; // stderr - // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 - vpCDEBUG(2) << "C++-like debug trace level 2" << std::endl; // stdout -} + // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 + vpCDEBUG(2) << "C++-like debug trace level 2" << std::endl; // stdout + } \endcode \sa vpCTRACE(), vpCDEBUG() */ -#define vpCERROR \ - std::cerr << "(L0) " \ - << "!!\t" << __FILE__ << ": " << __FUNCTION__ << "(#" << __LINE__ << ") : " +#define vpCERROR std::cerr << "(L0) " << "!!\t" << __FILE__ << ": " << __FUNCTION__ << "(#" << __LINE__ << ") : " /*! \ingroup group_core_debug @@ -370,17 +364,17 @@ int main() with any "printf" string. \code -#define VP_TRACE // To activate trace mode -#define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 + #define VP_TRACE // To activate trace mode + #define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 -#include + #include -int main() -{ - // Printing depend only VP_DEBUG_MODE value is >= 1 - vpTRACE(1, "C-like trace level 1"); // stdout - vpERROR_TRACE(1, "C-like error trace level 1"); // stderr -} + int main() + { + // Printing depend only VP_DEBUG_MODE value is >= 1 + vpTRACE(1, "C-like trace level 1"); // stdout + vpERROR_TRACE(1, "C-like error trace level 1"); // stderr + } \endcode \sa vpTRACE() @@ -396,14 +390,14 @@ int main() with any "printf" string. \code -#define VP_TRACE // To activate trace mode -#include + #define VP_TRACE // To activate trace mode + #include -int main() -{ - // C-like debug printings - vpTRACE("C-like trace"); // stdout -} + int main() + { + // C-like debug printings + vpTRACE("C-like trace"); // stdout + } \endcode \sa vpCTRACE(), vpERROR_TRACE() @@ -419,19 +413,16 @@ int main() if (false) \ std::cerr // Warning C4127 -inline void vpERROR_TRACE(const char * /* a */, ...) {} -inline void vpERROR_TRACE(int /* level */, const char * /* a */, ...) {} -inline void vpTRACE(const char * /* a */, ...) {} -inline void vpTRACE(int /* level */, const char * /* a */, ...) {} +inline void vpERROR_TRACE(const char * /* a */, ...) { } +inline void vpERROR_TRACE(int /* level */, const char * /* a */, ...) { } +inline void vpTRACE(const char * /* a */, ...) { } +inline void vpTRACE(int /* level */, const char * /* a */, ...) { } #endif // #ifdef VP_TRACE -/* ------------------------------------------------------------------------- - */ -/* --- VP_DEBUG ------------------------------------------------------------ - */ -/* ------------------------------------------------------------------------- - */ +/* ------------------------------------------------------------------------- */ +/* --- VP_DEBUG ------------------------------------------------------------ */ +/* ------------------------------------------------------------------------- */ #ifdef VP_DEBUG @@ -441,17 +432,17 @@ inline void vpTRACE(int /* level */, const char * /* a */, ...) {} tracing level is smaller than the debug level VP_DEBUG_MODE. \code -#define VP_DEBUG // Activate the debug mode -#define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 + #define VP_DEBUG // Activate the debug mode + #define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 -#include + #include -int main() -{ - // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 - vpDEBUG_TRACE(2, "C-like debug trace level 2"); // stdout - vpDERROR_TRACE(2, "C-like error trace level 2"); // stderr -} + int main() + { + // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 + vpDEBUG_TRACE(2, "C-like debug trace level 2"); // stdout + vpDERROR_TRACE(2, "C-like error trace level 2"); // stderr + } \endcode \sa vpDEBUG_TRACE() @@ -464,17 +455,17 @@ int main() tracing level level is greater than the debug level VP_DEBUG_MODE. \code -#define VP_DEBUG // Activate the debug mode -#define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 + #define VP_DEBUG // Activate the debug mode + #define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 -#include + #include -int main() -{ - // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 - vpDEBUG_TRACE(2, "C-like debug trace level 2"); // stdout - vpDERROR_TRACE(2, "C-like error trace level 2"); // stderr -} + int main() + { + // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 + vpDEBUG_TRACE(2, "C-like debug trace level 2"); // stdout + vpDERROR_TRACE(2, "C-like error trace level 2"); // stderr + } \endcode \sa vpDERROR_TRACE() @@ -485,20 +476,20 @@ int main() \ingroup group_core_debug vpCDEBUG(level) work like the C++ output stream std::cout. \code -#define VP_DEBUG // Activate the debug mode -#define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 + #define VP_DEBUG // Activate the debug mode + #define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 -#include + #include -int main() -{ - // C++-like debug printings - vpCTRACE << "C++-like trace" << std::endl; // stdout - vpCERROR << "C++-like error trace" << std::endl; // stderr + int main() + { + // C++-like debug printings + vpCTRACE << "C++-like trace" << std::endl; // stdout + vpCERROR << "C++-like error trace" << std::endl; // stderr - // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 - vpCDEBUG(2) << "C++-like debug trace level 2" << std::endl; // stdout -} + // Printing if VP_DEBUG defined and VP_DEBUG_MODE value >= 2 + vpCDEBUG(2) << "C++-like debug trace level 2" << std::endl; // stdout + } \endcode \sa vpCTRACE(), vpCERROR() @@ -513,31 +504,31 @@ int main() \ingroup group_core_debug vpDEBUG_ENABLE(level) is equal to 1 if the debug level \e level is greater -than the debug mode VP_DEBUG_MODE, 0 else. + than the debug mode VP_DEBUG_MODE, 0 else. \code -#define VP_DEBUG // Activate the debug mode -#define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 + #define VP_DEBUG // Activate the debug mode + #define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 -#include + #include -int main() -{ - // Check the active debug levels - std::cout << "Debug level 1 active: " << vpDEBUG_ENABLE(1) << std::endl; - std::cout << "Debug level 2 active: " << vpDEBUG_ENABLE(2) << std::endl; - std::cout << "Debug level 3 active: " << vpDEBUG_ENABLE(3) << std::endl; -} + int main() + { + // Check the active debug levels + std::cout << "Debug level 1 active: " << vpDEBUG_ENABLE(1) << std::endl; + std::cout << "Debug level 2 active: " << vpDEBUG_ENABLE(2) << std::endl; + std::cout << "Debug level 3 active: " << vpDEBUG_ENABLE(3) << std::endl; + } \endcode */ #define vpDEBUG_ENABLE(level) (VP_DEBUG_MODE >= level) #else // #ifdef VP_DEBUG -inline void vpDERROR_TRACE(const char * /* a */, ...) {} -inline void vpDEBUG_TRACE(const char * /* a */, ...) {} -inline void vpDERROR_TRACE(int /* level */, const char * /* a */, ...) {} -inline void vpDEBUG_TRACE(int /* level */, const char * /* a */, ...) {} +inline void vpDERROR_TRACE(const char * /* a */, ...) { } +inline void vpDEBUG_TRACE(const char * /* a */, ...) { } +inline void vpDERROR_TRACE(int /* level */, const char * /* a */, ...) { } +inline void vpDEBUG_TRACE(int /* level */, const char * /* a */, ...) { } #define vpCDEBUG(level) \ if (false) \ @@ -546,12 +537,9 @@ inline void vpDEBUG_TRACE(int /* level */, const char * /* a */, ...) {} #endif // #ifdef VP_DEBUG -/* -------------------------------------------------------------------------- - */ -/* --- DEFENSIF ------------------------------------------------------------- - */ -/* -------------------------------------------------------------------------- - */ +/* -------------------------------------------------------------------------- */ +/* --- DEFENSIF ------------------------------------------------------------- */ +/* -------------------------------------------------------------------------- */ #ifdef VP_DEFENSIF #define DEFENSIF(a) (a) #else diff --git a/modules/core/include/visp3/core/vpException.h b/modules/core/include/visp3/core/vpException.h index 917471c571..03f3965e4e 100644 --- a/modules/core/include/visp3/core/vpException.h +++ b/modules/core/include/visp3/core/vpException.h @@ -100,6 +100,15 @@ class VISP_EXPORT vpException : public std::exception */ vpException(int code, const std::string &msg); + /*! + Basic destructor. Do nothing but implemented to fit the inheritance from + std::exception + */ +#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 + virtual ~vpException() { } +#else + virtual ~vpException() throw() { } +#endif /*! * Constructor. */ diff --git a/modules/core/include/visp3/core/vpFrameGrabber.h b/modules/core/include/visp3/core/vpFrameGrabber.h index 0648906be2..b13fa3bd19 100644 --- a/modules/core/include/visp3/core/vpFrameGrabber.h +++ b/modules/core/include/visp3/core/vpFrameGrabber.h @@ -110,7 +110,12 @@ class VISP_EXPORT vpFrameGrabber public: vpFrameGrabber() : init(false), height(0), width(0) { }; + +#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 virtual ~vpFrameGrabber() = default; +#else + virtual ~vpFrameGrabber() { } +#endif virtual void open(vpImage &I) = 0; virtual void open(vpImage &I) = 0; diff --git a/modules/core/include/visp3/core/vpHomogeneousMatrix.h b/modules/core/include/visp3/core/vpHomogeneousMatrix.h index 4c7f498ad1..00066f19d4 100644 --- a/modules/core/include/visp3/core/vpHomogeneousMatrix.h +++ b/modules/core/include/visp3/core/vpHomogeneousMatrix.h @@ -34,7 +34,7 @@ /*! \file vpHomogeneousMatrix.h \brief Definition and computation on the homogeneous matrices -*/ + */ #ifndef _vpHomogeneousMatrix_h_ #define _vpHomogeneousMatrix_h_ @@ -207,7 +207,9 @@ 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); @@ -381,11 +383,11 @@ class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D /*! * @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(). diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 1259e7800c..8dbaa41ec5 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -32,9 +32,9 @@ */ /*! - \file vpImage.h - \brief Image handling. -*/ + * \file vpImage.h + * \brief Image handling. + */ #ifndef vpImage_H #define vpImage_H @@ -143,8 +143,10 @@ template class vpImage vpImage(); //! copy constructor vpImage(const vpImage &); +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher //! 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 @@ -482,7 +484,6 @@ inline std::ostream &operator<<(std::ostream &s, const vpImage &I) #if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) namespace { - struct vpImageLut_Param_t { unsigned int m_start_index; @@ -639,7 +640,6 @@ template void vpImage::init(unsigned int h, unsigned int w) { if (h != this->height) { if (row != nullptr) { - vpDEBUG_TRACE(10, "Destruction row[]"); delete[] row; row = nullptr; } @@ -647,7 +647,6 @@ template void vpImage::init(unsigned int h, unsigned int w) if ((h != this->height) || (w != this->width)) { if (bitmap != nullptr) { - vpDEBUG_TRACE(10, "Destruction bitmap[]"); if (hasOwnership) { delete[] bitmap; } @@ -664,11 +663,9 @@ template void vpImage::init(unsigned int h, unsigned int w) bitmap = new Type[npixels]; hasOwnership = true; } - if (bitmap == nullptr) { throw(vpException(vpException::memoryAllocationError, "cannot allocate bitmap ")); } - if (row == nullptr) row = new Type *[height]; if (row == nullptr) { @@ -822,11 +819,7 @@ template void vpImage::resize(unsigned int h, unsigned int w, */ template void vpImage::destroy() { - // vpERROR_TRACE("Deallocate "); - if (bitmap != nullptr) { - // vpERROR_TRACE("Deallocate bitmap memory %p",bitmap); - // vpDEBUG_TRACE(20,"Deallocate bitmap memory %p",bitmap); if (hasOwnership) { delete[] bitmap; } @@ -834,8 +827,6 @@ template void vpImage::destroy() } if (row != nullptr) { - // vpERROR_TRACE("Deallocate row memory %p",row); - // vpDEBUG_TRACE(20,"Deallocate row memory %p",row); delete[] row; row = nullptr; } @@ -860,6 +851,7 @@ vpImage::vpImage(const vpImage &I) memcpy(static_cast(bitmap), static_cast(I.bitmap), I.npixels * sizeof(Type)); } +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher /*! \relates vpImage */ @@ -876,6 +868,7 @@ vpImage::vpImage(vpImage &&I) I.row = nullptr; I.hasOwnership = false; } +#endif /*! * \brief Return the maximum value within the bitmap @@ -1258,10 +1251,6 @@ void vpImage::getMinMaxLoc(vpImagePoint *minLoc, vpImagePoint *maxLoc, Typ template vpImage &vpImage::operator=(vpImage other) { swap(*this, other); - // Swap back display pointer if it was not null - // vpImage I2(480, 640); - // vpDisplayX d(I2); - // I2 = I1; //copy only the data if (other.display != nullptr) display = other.display; diff --git a/modules/core/include/visp3/core/vpImagePoint.h b/modules/core/include/visp3/core/vpImagePoint.h index f1547df123..f0a69ed114 100644 --- a/modules/core/include/visp3/core/vpImagePoint.h +++ b/modules/core/include/visp3/core/vpImagePoint.h @@ -38,7 +38,7 @@ \file vpImagePoint.h \brief Class that defines a 2D point in an image. This class is useful for image processing -*/ + */ #include @@ -217,11 +217,19 @@ 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 ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher 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 { double i_ = (end.get_i() > this->i ? this->i + 1 : this->i - 1); +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher 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 } } @@ -235,6 +243,7 @@ class VISP_EXPORT vpImagePoint return *this; } +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher /*! Move operator. */ @@ -244,6 +253,7 @@ class VISP_EXPORT vpImagePoint this->j = ip.j; return *this; } +#endif vpImagePoint &operator+=(const vpImagePoint &ip); diff --git a/modules/core/include/visp3/core/vpImageTools.h b/modules/core/include/visp3/core/vpImageTools.h index 75a81034cf..55d3c002ea 100644 --- a/modules/core/include/visp3/core/vpImageTools.h +++ b/modules/core/include/visp3/core/vpImageTools.h @@ -179,7 +179,7 @@ class VISP_EXPORT vpImageTools template vp_deprecated static void createSubImage(const vpImage &I, const vpRect &rect, vpImage &S); -//@} + //@} #endif private: @@ -796,10 +796,10 @@ void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &c for (int v = 0; v < height; v++) { for (int u = 0; u < height; u++) { - double r2 = vpMath::sqr(((double)u - u0)/px) + - vpMath::sqr(((double)v-v0)/py); - double u_double = ((double)u - u0)*(1.0+kd*r2) + u0; - double v_double = ((double)v - v0)*(1.0+kd*r2) + v0; + double r2 = vpMath::sqr(((double)u - u0) / px) + + vpMath::sqr(((double)v - v0) / py); + double u_double = ((double)u - u0) * (1.0 + kd * r2) + u0; + double v_double = ((double)v - v0) * (1.0 + kd * r2) + v0; undistI[v][u] = I.getPixelBI((float)u_double, (float)v_double); } } @@ -1092,7 +1092,7 @@ template void vpImageTools::resize(const vpImage &I, vpImage &Ires, const vpImageInterpolationType &method, unsigned int #if defined(_OPENMP) - nThreads + nThreads #endif ) { @@ -1145,7 +1145,7 @@ inline void vpImageTools::resize(const vpImage &I, vpImage &I, vpImage &Ires const vpImageInterpolationType &method, unsigned int #if defined(_OPENMP) - nThreads + nThreads #endif ) { @@ -1304,7 +1304,7 @@ void vpImageTools::warpImage(const vpImage &src, const vpMatrix &T, vpImag warpNN(src, M, dst, affine, pixelCenter, fixedPointArithmetic); } else { - // bilinear interpolation + // bilinear interpolation warpLinear(src, M, dst, affine, pixelCenter, fixedPointArithmetic); } } diff --git a/modules/core/include/visp3/core/vpIoTools.h b/modules/core/include/visp3/core/vpIoTools.h index d4366e6a8a..f0b1210d93 100644 --- a/modules/core/include/visp3/core/vpIoTools.h +++ b/modules/core/include/visp3/core/vpIoTools.h @@ -85,7 +85,7 @@ struct NpyArray { num_vals = 1; for (size_t i = 0; i < shape.size(); i++) num_vals *= shape[i]; - data_holder = std::shared_ptr>( + data_holder = std::shared_ptr >( new std::vector(num_vals * word_size)); } @@ -115,14 +115,17 @@ struct NpyArray return data_holder->size(); } - std::shared_ptr> data_holder; + std::shared_ptr > data_holder; std::vector shape; size_t word_size; bool fortran_order; size_t num_vals; }; +#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 using npz_t = std::map; +VISP_EXPORT npz_t npz_load(std::string fname); +#endif VISP_EXPORT char BigEndianTest(); VISP_EXPORT char map_type(const std::type_info &t); @@ -130,7 +133,6 @@ template std::vector create_npy_header(const std::vector &shape, bool &fortran_order); VISP_EXPORT void parse_npy_header(unsigned char *buffer, size_t &word_size, std::vector &shape, bool &fortran_order); VISP_EXPORT void parse_zip_footer(FILE *fp, uint16_t &nrecs, size_t &global_header_size, size_t &global_header_offset); -VISP_EXPORT npz_t npz_load(std::string fname); VISP_EXPORT NpyArray npz_load(std::string fname, std::string varname); VISP_EXPORT NpyArray npy_load(std::string fname); diff --git a/modules/core/include/visp3/core/vpLinProg.h b/modules/core/include/visp3/core/vpLinProg.h index 8483699958..7edbb3c2d3 100644 --- a/modules/core/include/visp3/core/vpLinProg.h +++ b/modules/core/include/visp3/core/vpLinProg.h @@ -61,6 +61,7 @@ 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). * @@ -121,6 +122,7 @@ class VISP_EXPORT vpLinProg const double &tol = 1e-6); //@} +#endif /** @name Dimension reduction for equality constraints */ //@{ diff --git a/modules/core/include/visp3/core/vpLine.h b/modules/core/include/visp3/core/vpLine.h index 6b73e68511..44082d8da2 100644 --- a/modules/core/include/visp3/core/vpLine.h +++ b/modules/core/include/visp3/core/vpLine.h @@ -102,19 +102,21 @@ class VISP_EXPORT vpLine : public vpForwardProjection public: vpLine(); - void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const override; - void changeFrame(const vpHomogeneousMatrix &cMo) override; + void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const vp_override; + void changeFrame(const vpHomogeneousMatrix &cMo) vp_override; void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; + void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, + const vpColor &color = vpColor::green, unsigned int thickness = 1) vp_override; + void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); - void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &color = vpColor::green, unsigned int thickness = 1) override; void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); - vpLine *duplicate() const override; + vpLine *duplicate() const vp_override; + /*! * Gets the \f$ \rho \f$ value corresponding to one of the @@ -163,13 +165,12 @@ class VISP_EXPORT vpLine : public vpForwardProjection void setWorldCoordinates(const vpColVector &oP1, const vpColVector &oP2); - void setWorldCoordinates(const vpColVector &oP) override; - - void projection() override; - void projection(const vpColVector &cP, vpColVector &p) const override; + void setWorldCoordinates(const vpColVector &oP) vp_override; + void projection() vp_override; + void projection(const vpColVector &cP, vpColVector &p) const vp_override; protected: - void init() override; + void init() vp_override; }; #endif diff --git a/modules/core/include/visp3/core/vpList.h b/modules/core/include/visp3/core/vpList.h index 15edf87bd0..16528f03e9 100644 --- a/modules/core/include/visp3/core/vpList.h +++ b/modules/core/include/visp3/core/vpList.h @@ -35,9 +35,9 @@ #define VP_LIST_H /*! - \file vpList.h - \brief Definition of the list managment class -*/ + * \file vpList.h + * \brief Definition of the list management class + */ #include #include @@ -66,7 +66,7 @@ template class vpListElement // } public: - vpListElement() : prev(nullptr), next(nullptr), val(){}; + vpListElement() : prev(nullptr), next(nullptr), val() { }; vpListElement *prev; ///! pointer to the previous element in the list vpListElement *next; ///! pointer to the next element in the list type val; ///! value of the element @@ -211,7 +211,6 @@ template void vpList::init() \sa init() */ template vpList::vpList() : nb(0), first(nullptr), last(nullptr), cur(nullptr) { init(); } - /*! \brief vpList destructor \sa kill() @@ -394,7 +393,8 @@ template void vpList::addRight(const type &v) x->val = v; if (empty()) { cur = first; - } else { + } + else { if (outside()) std::cout << "vpList: outside with addRight " << std::endl; } @@ -424,7 +424,8 @@ template void vpList::addLeft(const type &v) if (empty()) { cur = last; - } else { + } + else { if (outside()) std::cout << "vpList: outside with addLeft " << std::endl; } @@ -453,7 +454,8 @@ template void vpList::addRight(type &v) x->val = v; if (empty()) { cur = first; - } else { + } + else { if (outside()) std::cout << "vpList: outside with addRight " << std::endl; } @@ -483,7 +485,8 @@ template void vpList::addLeft(type &v) if (empty()) { cur = last; - } else { + } + else { if (outside()) std::cout << "vpList: outside with addLeft " << std::endl; } @@ -530,7 +533,8 @@ template void vpList::swapLeft() prevTmp->prev = cur; prevTmp->next = nextTmp; - } else { + } + else { std::cout << "vpList: previous element is outside (swapLeft) " << std::endl; } } @@ -560,7 +564,8 @@ template void vpList::swapRight() nextTmp->prev = prevTmp; nextTmp->next = cur; - } else { + } + else { std::cout << "vpList: next element is outside (swapRight) " << std::endl; } } @@ -601,8 +606,9 @@ template void vpList::suppress(void) x = cur; cur = cur->next; - if (x != nullptr) + if (x != nullptr) { delete x; + } nb--; } diff --git a/modules/core/include/visp3/core/vpMatrix.h b/modules/core/include/visp3/core/vpMatrix.h index 09b7145244..771c162f01 100644 --- a/modules/core/include/visp3/core/vpMatrix.h +++ b/modules/core/include/visp3/core/vpMatrix.h @@ -186,19 +186,21 @@ class VISP_EXPORT vpMatrix : public vpArray2D The following example shows how to create a matrix from an homogeneous matrix: -\code -vpRotationMatrix R; -vpMatrix M(R); -\endcode + \code + vpRotationMatrix R; + vpMatrix M(R); + \endcode */ vpMatrix(const vpArray2D &A) : vpArray2D(A) { } 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), @@ -272,10 +274,13 @@ vpMatrix M(R); vpMatrix &operator,(double val); vpMatrix &operator=(const vpArray2D &A); vpMatrix &operator=(const vpMatrix &A); + +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix &operator=(vpMatrix &&A); vpMatrix &operator=(const std::initializer_list &list); vpMatrix &operator=(const std::initializer_list > &lists); +#endif vpMatrix &operator=(double x); //@} @@ -464,8 +469,7 @@ vpMatrix M(R); unsigned int pseudoInverse(vpMatrix &Ap, double svThreshold = 1e-6) const; unsigned int pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThreshold = 1e-6) const; unsigned int pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt) const; - unsigned int pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, - vpMatrix &kerAt) const; + unsigned int pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const; vpMatrix pseudoInverse(int rank_in) const; int pseudoInverse(vpMatrix &Ap, int rank_in) const; int pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in) const; @@ -476,37 +480,31 @@ vpMatrix M(R); vpMatrix pseudoInverseLapack(double svThreshold = 1e-6) const; unsigned int pseudoInverseLapack(vpMatrix &Ap, double svThreshold = 1e-6) const; unsigned int pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double svThreshold = 1e-6) const; - unsigned int pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, - vpMatrix &kerAt) const; + unsigned int pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const; vpMatrix pseudoInverseLapack(int rank_in) const; int pseudoInverseLapack(vpMatrix &Ap, int rank_in) const; int pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in) const; - int pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, - vpMatrix &kerAt) const; + int pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const; #endif #if defined(VISP_HAVE_EIGEN3) vpMatrix pseudoInverseEigen3(double svThreshold = 1e-6) const; unsigned int pseudoInverseEigen3(vpMatrix &Ap, double svThreshold = 1e-6) const; unsigned int pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double svThreshold = 1e-6) const; - unsigned int pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, - vpMatrix &kerAt) const; + unsigned int pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const; vpMatrix pseudoInverseEigen3(int rank_in) const; int pseudoInverseEigen3(vpMatrix &Ap, int rank_in) const; int pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in) const; - int pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, - vpMatrix &kerAt) const; + int pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const; #endif #if defined(VISP_HAVE_OPENCV) vpMatrix pseudoInverseOpenCV(double svThreshold = 1e-6) const; unsigned int pseudoInverseOpenCV(vpMatrix &Ap, double svThreshold = 1e-6) const; unsigned int pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double svThreshold = 1e-6) const; - unsigned int pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, - vpMatrix &kerAt) const; + unsigned int pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const; vpMatrix pseudoInverseOpenCV(int rank_in) const; int pseudoInverseOpenCV(vpMatrix &Ap, int rank_in) const; int pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in) const; - int pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, - vpMatrix &kerAt) const; + int pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const; #endif //@} @@ -978,7 +976,6 @@ vpMatrix M(R); //@} #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) - vp_deprecated double euclideanNorm() const; /*! diff --git a/modules/core/include/visp3/core/vpMomentCommon.h b/modules/core/include/visp3/core/vpMomentCommon.h index 33e6a19979..a6b112ebb3 100644 --- a/modules/core/include/visp3/core/vpMomentCommon.h +++ b/modules/core/include/visp3/core/vpMomentCommon.h @@ -128,12 +128,13 @@ class VISP_EXPORT vpMomentCommon : public vpMomentDatabase public: vpMomentCommon(double dstSurface, const std::vector &ref, double refAlpha, double dstZ = 1.0, bool flg_sxsyfromnormalized = false); - virtual ~vpMomentCommon() override; + + virtual ~vpMomentCommon() vp_override; static double getAlpha(vpMomentObject &object); static std::vector getMu3(vpMomentObject &object); static double getSurface(vpMomentObject &object); - void updateAll(vpMomentObject &object) override; + void updateAll(vpMomentObject &object) vp_override; }; #endif // VPCOMMONMOMENTS_H diff --git a/modules/core/include/visp3/core/vpNullptrEmulated.h b/modules/core/include/visp3/core/vpNullptrEmulated.h index 652f2fccc1..144cec8e1f 100644 --- a/modules/core/include/visp3/core/vpNullptrEmulated.h +++ b/modules/core/include/visp3/core/vpNullptrEmulated.h @@ -31,6 +31,10 @@ #ifndef _vpNullptrEmulated_h_ #define _vpNullptrEmulated_h_ +#include + +#if (!defined(VISP_HAVE_NULLPTR)) && (__cplusplus == 199711L) + // Inspired from this thread https://stackoverflow.com/questions/24433436/compile-error-nullptr-undeclared-identifier // Does the emulation of nullptr when not available with cxx98 const @@ -55,3 +59,4 @@ class nullptr_t } nullptr = {}; #endif +#endif diff --git a/modules/core/include/visp3/core/vpPoint.h b/modules/core/include/visp3/core/vpPoint.h index 9710e1ecc1..b2f4f069b3 100644 --- a/modules/core/include/visp3/core/vpPoint.h +++ b/modules/core/include/visp3/core/vpPoint.h @@ -54,23 +54,23 @@ class vpHomogeneousMatrix; A 3D point has the followings parameters: - **in the object frame**: the normalized 3D coordinates oX, oY, oZ, oW of the point. These - parameters registered in vpForwardProjection::oP internal 4-dim vector are set using the constructors vpPoint(double - oX, double oY, double oZ), vpPoint(const vpColVector &oP) and vpPoint(const std::vector &oP) or the functions - setWorldCoordinates(double oX, double oY, double oZ), - setWorldCoordinates(const vpColVector &oP) and setWorldCoordinates(const std::vector &oP). - To get theses parameters use get_oP(). + parameters registered in vpForwardProjection::oP internal 4-dim vector are set using the constructors vpPoint(double + oX, double oY, double oZ), vpPoint(const vpColVector &oP) and vpPoint(const std::vector &oP) or the functions + setWorldCoordinates(double oX, double oY, double oZ), + setWorldCoordinates(const vpColVector &oP) and setWorldCoordinates(const std::vector &oP). + To get theses parameters use get_oP(). - **in the camera frame**: the normalized coordinates cX, cY, cZ, 1 of the point. These - parameters registered in vpTracker::cP internal 4-dim vector are computed using - changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const or changeFrame(const vpHomogeneousMatrix &cMo). - These parameters could be retrieved using get_X(), get_Y() and get_Z(). - To get theses parameters use get_cP(). + parameters registered in vpTracker::cP internal 4-dim vector are computed using + changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const or changeFrame(const vpHomogeneousMatrix &cMo). + These parameters could be retrieved using get_X(), get_Y() and get_Z(). + To get theses parameters use get_cP(). - **in the image plane**: the 2D normalized coordinates (x, y, 1) corresponding - to the perspective projection of the point. These parameters are registered in vpTracker::p internal 3-dim vector and - computed using projection() and projection(const vpColVector &cP, vpColVector &p) const. They could be retrieved using - get_x() and get_y(). They correspond to 2D normalized point parameters with values expressed in meters. To get theses - parameters use get_p(). + to the perspective projection of the point. These parameters are registered in vpTracker::p internal 3-dim vector and + computed using projection() and projection(const vpColVector &cP, vpColVector &p) const. They could be retrieved using + get_x() and get_y(). They correspond to 2D normalized point parameters with values expressed in meters. To get theses + parameters use get_p(). */ class VISP_EXPORT vpPoint : public vpForwardProjection @@ -85,18 +85,20 @@ class VISP_EXPORT vpPoint : public vpForwardProjection public: // Compute the 3D coordinates _cP (camera frame) - void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const override; - void changeFrame(const vpHomogeneousMatrix &cMo) override; + void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const vp_override; + void changeFrame(const vpHomogeneousMatrix &cMo) vp_override; void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; + void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, + const vpColor &color = vpColor::green, unsigned int thickness = 1) vp_override; + void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); - void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &color = vpColor::green, unsigned int thickness = 1) override; void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); - vpPoint *duplicate() const override; + + vpPoint *duplicate() const vp_override; // Get coordinates double get_X() const; @@ -120,9 +122,9 @@ class VISP_EXPORT vpPoint : public vpForwardProjection //! Projection onto the image plane of a point. Input: the 3D coordinates in //! the camera frame _cP, output : the 2D coordinates _p. - void projection(const vpColVector &_cP, vpColVector &_p) const override; - void projection() override; + void projection(const vpColVector &_cP, vpColVector &_p) const vp_override; + void projection() vp_override; // Set coordinates void set_X(double cX); @@ -138,12 +140,13 @@ class VISP_EXPORT vpPoint : public vpForwardProjection void set_w(double w); void setWorldCoordinates(double oX, double oY, double oZ); - void setWorldCoordinates(const vpColVector &oP) override; + + void setWorldCoordinates(const vpColVector &oP) vp_override; void setWorldCoordinates(const std::vector &oP); protected: //! Basic construction. - void init() override; + void init() vp_override; }; #endif diff --git a/modules/core/include/visp3/core/vpQuadProg.h b/modules/core/include/visp3/core/vpQuadProg.h index 138f431316..052dcbd1d0 100644 --- a/modules/core/include/visp3/core/vpQuadProg.h +++ b/modules/core/include/visp3/core/vpQuadProg.h @@ -69,6 +69,7 @@ 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; @@ -156,5 +157,6 @@ 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 af3fd9e751..86081b5300 100644 --- a/modules/core/include/visp3/core/vpQuaternionVector.h +++ b/modules/core/include/visp3/core/vpQuaternionVector.h @@ -35,12 +35,11 @@ #define _vpQuaternionVector_h_ /*! - \file vpQuaternionVector.h - - \brief Class that consider the case of a quaternion and basic - operations on it. - -*/ + * \file vpQuaternionVector.h + * + * \brief Class that consider the case of a quaternion and basic + * operations on it. + */ #include #include @@ -101,8 +100,7 @@ double z = q.z(); double w = q.w(); \endcode - - */ + */ class VISP_EXPORT vpQuaternionVector : public vpRotationVector { private: @@ -141,8 +139,10 @@ 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 b36d8af960..772ba97f3a 100644 --- a/modules/core/include/visp3/core/vpRGBa.h +++ b/modules/core/include/visp3/core/vpRGBa.h @@ -114,7 +114,9 @@ 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 ba03ebbc21..828a59b087 100644 --- a/modules/core/include/visp3/core/vpRGBf.h +++ b/modules/core/include/visp3/core/vpRGBf.h @@ -101,7 +101,9 @@ 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/vpRansac.h b/modules/core/include/visp3/core/vpRansac.h index d1b0f83530..2602e12f6a 100644 --- a/modules/core/include/visp3/core/vpRansac.h +++ b/modules/core/include/visp3/core/vpRansac.h @@ -33,8 +33,6 @@ /*! \file vpRansac.h - - template class for */ #ifndef vpRANSAC_HH @@ -45,6 +43,7 @@ #include // debug and trace #include #include // random number generation + /*! \class vpRansac \ingroup group_core_robust @@ -62,7 +61,6 @@ http://www.csse.uwa.edu.au/~pk \sa vpHomography - */ template class vpRansac { @@ -171,8 +169,9 @@ bool vpRansac::ransac(unsigned int npts, const vpColVector &x, vpTransformation::computeResidual(x, M, d); // Find the indices of points that are inliers to this model. - if (residual != nullptr) + if (residual != nullptr) { *residual = 0.0; + } ninliers = 0; for (unsigned int i = 0; i < npts; i++) { double resid = fabs(d[i]); @@ -182,7 +181,8 @@ bool vpRansac::ransac(unsigned int npts, const vpColVector &x, if (residual != nullptr) { *residual += fabs(d[i]); } - } else + } + else inliers[i] = 0; } @@ -217,7 +217,8 @@ bool vpRansac::ransac(unsigned int npts, const vpColVector &x, { M = bestM; inliers = bestinliers; - } else { + } + else { vpTRACE("ransac was unable to find a useful solution"); M = 0; } diff --git a/modules/core/include/visp3/core/vpRectOriented.h b/modules/core/include/visp3/core/vpRectOriented.h index 7819f3a91e..517939dac5 100644 --- a/modules/core/include/visp3/core/vpRectOriented.h +++ b/modules/core/include/visp3/core/vpRectOriented.h @@ -35,10 +35,10 @@ #define vpRectOriented_h /*! - \class vpRectOriented - \ingroup group_core_geometry - \brief Defines an oriented rectangle in the plane. -*/ + * \class vpRectOriented + * \ingroup group_core_geometry + * \brief Defines an oriented rectangle in the plane. + */ #include #include @@ -47,13 +47,21 @@ 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 c01fa0cb25..5c52ef4e89 100644 --- a/modules/core/include/visp3/core/vpRobust.h +++ b/modules/core/include/visp3/core/vpRobust.h @@ -32,7 +32,7 @@ */ /*! - \file vpRobust.h + \file vpRobust.h */ #ifndef vpRobust_h @@ -140,7 +140,9 @@ 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 minimal value of diff --git a/modules/core/include/visp3/core/vpRotationMatrix.h b/modules/core/include/visp3/core/vpRotationMatrix.h index c0464c3146..457ffd9ac6 100644 --- a/modules/core/include/visp3/core/vpRotationMatrix.h +++ b/modules/core/include/visp3/core/vpRotationMatrix.h @@ -64,52 +64,52 @@ The code below shows how to create a rotation matrix, set the element values and access them: \code -#include + #include -int main() -{ - vpRotationMatrix R; - R[0][0] = 0; R[0][1] = 0; R[0][2] = -1; - R[1][0] = 0; R[1][1] = -1; R[1][2] = 0; - R[2][0] = -1; R[2][1] = 0; R[2][2] = 0; - - std::cout << "R:" << std::endl; - for (unsigned int i = 0; i < R.getRows(); i++) { - for (unsigned int j = 0; j < R.getCols(); j++) { - std::cout << R[i][j] << " "; + int main() + { + vpRotationMatrix R; + R[0][0] = 0; R[0][1] = 0; R[0][2] = -1; + R[1][0] = 0; R[1][1] = -1; R[1][2] = 0; + R[2][0] = -1; R[2][1] = 0; R[2][2] = 0; + + std::cout << "R:" << std::endl; + for (unsigned int i = 0; i < R.getRows(); i++) { + for (unsigned int j = 0; j < R.getCols(); j++) { + std::cout << R[i][j] << " "; + } + std::cout << std::endl; } - std::cout << std::endl; } -} \endcode Once build, this previous code produces the following output: \code -R: -0 0 -1 -0 -1 0 --1 0 0 + R: + 0 0 -1 + 0 -1 0 + -1 0 0 \endcode You can also use operator<< to initialize a rotation matrix as previously: \code -#include + #include -int main() -{ - vpRotationMatrix R; - R << 0, 0, -1, 0, -1, 0, -1, 0, 0; - std::cout << "R:\n" << R << std::endl; -} + int main() + { + vpRotationMatrix R; + R << 0, 0, -1, 0, -1, 0, -1, 0, 0; + std::cout << "R:\n" << R << std::endl; + } \endcode If ViSP is build with c++11 enabled, you can do the same using: \code -#include @@ -127,7 +127,9 @@ 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); @@ -152,7 +154,9 @@ 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 830dcb5c51..396b89d18f 100644 --- a/modules/core/include/visp3/core/vpRowVector.h +++ b/modules/core/include/visp3/core/vpRowVector.h @@ -121,8 +121,10 @@ 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), @@ -207,8 +209,10 @@ 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; @@ -323,7 +327,7 @@ class VISP_EXPORT vpRowVector : public vpArray2D */ vp_deprecated void setIdentity(const double &val = 1.0); vp_deprecated double euclideanNorm() const; -//@} + //@} #endif }; diff --git a/modules/core/include/visp3/core/vpRxyzVector.h b/modules/core/include/visp3/core/vpRxyzVector.h index 02d288feef..9c13ec776c 100644 --- a/modules/core/include/visp3/core/vpRxyzVector.h +++ b/modules/core/include/visp3/core/vpRxyzVector.h @@ -42,7 +42,7 @@ parameterization for the rotation. Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi) -*/ + */ #include #include @@ -199,8 +199,10 @@ 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 e21bd61a25..0e7156e8ee 100644 --- a/modules/core/include/visp3/core/vpRzyxVector.h +++ b/modules/core/include/visp3/core/vpRzyxVector.h @@ -140,36 +140,36 @@ class vpThetaUVector; from the build rotation matrix. \code -#include -#include -#include + #include + #include + #include -int main() -{ - vpRzyxVector rzyx; + int main() + { + vpRzyxVector rzyx; - // Initialise the Euler angles - rzyx[0] = vpMath::rad( 45.f); // phi angle in rad/s around z axis - rzyx[1] = vpMath::rad(-30.f); // theta angle in rad/s around y axis - rzyx[2] = vpMath::rad( 90.f); // psi angle in rad/s around x axis + // Initialise the Euler angles + rzyx[0] = vpMath::rad( 45.f); // phi angle in rad/s around z axis + rzyx[1] = vpMath::rad(-30.f); // theta angle in rad/s around y axis + rzyx[2] = vpMath::rad( 90.f); // psi angle in rad/s around x axis - // Construct a rotation matrix from the Euler angles - vpRotationMatrix R(rzyx); + // Construct a rotation matrix from the Euler angles + vpRotationMatrix R(rzyx); - // Extract the Euler angles around z,y,x axis from a rotation matrix - rzyx.buildFrom(R); + // Extract the Euler angles around z,y,x axis from a rotation matrix + rzyx.buildFrom(R); - // Print the extracted Euler angles. Values are the same than the - // one used for initialization - std::cout << rzyx; + // Print the extracted Euler angles. Values are the same than the + // one used for initialization + std::cout << rzyx; - // Since the rotation vector is 3 values column vector, the - // transpose operation produce a row vector. - vpRowVector rzyx_t = rzyx.t(); + // Since the rotation vector is 3 values column vector, the + // transpose operation produce a row vector. + vpRowVector rzyx_t = rzyx.t(); - // Print the transpose row vector - std::cout << rzyx_t << std::endl; -} + // Print the transpose row vector + std::cout << rzyx_t << std::endl; + } \endcode */ @@ -200,8 +200,10 @@ 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 82fd27d331..b7d86a2715 100644 --- a/modules/core/include/visp3/core/vpRzyzVector.h +++ b/modules/core/include/visp3/core/vpRzyzVector.h @@ -199,7 +199,9 @@ 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/vpServer.h b/modules/core/include/visp3/core/vpServer.h index 83054b6696..b2c06cd1c5 100644 --- a/modules/core/include/visp3/core/vpServer.h +++ b/modules/core/include/visp3/core/vpServer.h @@ -174,7 +174,7 @@ class VISP_EXPORT vpServer : public vpNetwork explicit vpServer(const int &port); vpServer(const std::string &adress_serv, const int &port_serv); - virtual ~vpServer() override; + virtual ~vpServer() vp_override; bool checkForConnections(); diff --git a/modules/core/include/visp3/core/vpSphere.h b/modules/core/include/visp3/core/vpSphere.h index 1992d8695c..d28a723cab 100644 --- a/modules/core/include/visp3/core/vpSphere.h +++ b/modules/core/include/visp3/core/vpSphere.h @@ -54,25 +54,25 @@ * * A sphere has the followings parameters: * - **in the object frame**: the 3D coordinates oX, oY, oZ of the center and radius R. These - *. parameters registered in vpForwardProjection::oP internal 4-dim vector are set using the constructors vpSphere(double - *. oX, double oY, double oZ, double R), vpSphere(const vpColVector &oP) or the functions setWorldCoordinates(double oX, - *. double oY, double oZ, double R) and setWorldCoordinates(const vpColVector &oP). To get theses parameters use get_oP(). + * parameters registered in vpForwardProjection::oP internal 4-dim vector are set using the constructors vpSphere(double + * oX, double oY, double oZ, double R), vpSphere(const vpColVector &oP) or the functions setWorldCoordinates(double oX, + * double oY, double oZ, double R) and setWorldCoordinates(const vpColVector &oP). To get theses parameters use get_oP(). * * - **in the camera frame**: the coordinates cX, cY, cZ of the center and radius R. These - *. parameters registered in vpTracker::cP internal 4-dim vector are computed using - *. changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const or changeFrame(const vpHomogeneousMatrix &cMo). - *. These parameters could be retrieved using getX(), getY(), getZ() and getR(). - *. To get theses parameters use get_cP(). + * parameters registered in vpTracker::cP internal 4-dim vector are computed using + * changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const or changeFrame(const vpHomogeneousMatrix &cMo). + * These parameters could be retrieved using getX(), getY(), getZ() and getR(). + * To get theses parameters use get_cP(). * * - **in the image plane**: here we consider the parameters of the ellipse corresponding - *. to the perspective projection of the 3D sphere. The parameters are the ellipse centroid (x, y) - *. and n20, n11, n02 which are the second order centered moments of - *. the ellipse normalized by its area (i.e., such that \f$n_{ij} = \mu_{ij}/a\f$ where - *. \f$\mu_{ij}\f$ are the centered moments and a the area). - *. These parameters are registered in vpTracker::p internal 5-dim vector and computed using projection() and - *. projection(const vpColVector &cP, vpColVector &p) const. They could be retrieved using get_x(), get_y(), get_n20(), - *. get_n11() and get_n02(). They correspond to 2D normalized sphere parameters with values expressed in meters. - *. To get theses parameters use get_p(). + * to the perspective projection of the 3D sphere. The parameters are the ellipse centroid (x, y) + * and n20, n11, n02 which are the second order centered moments of + * the ellipse normalized by its area (i.e., such that \f$n_{ij} = \mu_{ij}/a\f$ where + * \f$\mu_{ij}\f$ are the centered moments and a the area). + * These parameters are registered in vpTracker::p internal 5-dim vector and computed using projection() and + * projection(const vpColVector &cP, vpColVector &p) const. They could be retrieved using get_x(), get_y(), get_n20(), + * get_n11() and get_n02(). They correspond to 2D normalized sphere parameters with values expressed in meters. + * To get theses parameters use get_p(). */ class VISP_EXPORT vpSphere : public vpForwardProjection { @@ -81,19 +81,20 @@ class VISP_EXPORT vpSphere : public vpForwardProjection explicit vpSphere(const vpColVector &oP); vpSphere(double oX, double oY, double oZ, double R); - void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const override; - void changeFrame(const vpHomogeneousMatrix &cMo) override; + void changeFrame(const vpHomogeneousMatrix &cMo, vpColVector &cP) const vp_override; + void changeFrame(const vpHomogeneousMatrix &cMo) vp_override; void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; + void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, + const vpColor &color = vpColor::green, unsigned int thickness = 1) vp_override; + void display(const vpImage &I, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); - void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &color = vpColor::green, unsigned int thickness = 1) override; void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &color = vpColor::green, unsigned int thickness = 1); - vpSphere *duplicate() const override; + vpSphere *duplicate() const vp_override; double get_x() const { return p[0]; } double get_y() const { return p[1]; } @@ -107,27 +108,28 @@ class VISP_EXPORT vpSphere : public vpForwardProjection double getZ() const { return cP[2]; } double getR() const { return cP[3]; } - void projection() override; - void projection(const vpColVector &cP, vpColVector &p) const override; - void setWorldCoordinates(const vpColVector &oP) override; + void projection() vp_override; + void projection(const vpColVector &cP, vpColVector &p) const vp_override; + void setWorldCoordinates(const vpColVector &oP) vp_override; + void setWorldCoordinates(double oX, double oY, double oZ, double R); protected: - void init() override; + void init() vp_override; public: #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) /*! * @name Deprecated functions */ - //@{ - /*! - * \deprecated You should rather use get_n20(). - * This function is incorrectly named and is confusing since it - * returns second order centered moments of the ellipse normalized - * by its area that corresponds to \f$n_20 = mu_20/a\f$. - */ + //@{ + /*! + * \deprecated You should rather use get_n20(). + * This function is incorrectly named and is confusing since it + * returns second order centered moments of the ellipse normalized + * by its area that corresponds to \f$n_20 = mu_20/a\f$. + */ vp_deprecated double get_mu20() const { return p[2]; } /*! * \deprecated You should rather use get_n11(). diff --git a/modules/core/include/visp3/core/vpSubColVector.h b/modules/core/include/visp3/core/vpSubColVector.h index 99fa0579b2..ad97b7d2df 100644 --- a/modules/core/include/visp3/core/vpSubColVector.h +++ b/modules/core/include/visp3/core/vpSubColVector.h @@ -67,7 +67,7 @@ class VISP_EXPORT vpSubColVector : public vpColVector public: vpSubColVector(); vpSubColVector(vpColVector &v, const unsigned int &offset, const unsigned int &nrows); - virtual ~vpSubColVector() override; + virtual ~vpSubColVector() vp_override; void checkParentStatus() const; diff --git a/modules/core/include/visp3/core/vpSubMatrix.h b/modules/core/include/visp3/core/vpSubMatrix.h index 989cf9bf71..d4fbfe6b01 100644 --- a/modules/core/include/visp3/core/vpSubMatrix.h +++ b/modules/core/include/visp3/core/vpSubMatrix.h @@ -37,26 +37,22 @@ #include /*! - \file vpSubMatrix.h - - \brief Definition of the vpSubMatrix class -*/ + * \file vpSubMatrix.h + * + * \brief Definition of the vpSubMatrix class + */ /*! - \class vpSubMatrix - \ingroup group_core_matrices - \brief Definition of the vpSubMatrix - vpSubMatrix class provides a mask on a vpMatrix - all properties of vpMatrix are available with - a vpSubMatrix - - \author Jean Laneurit (IRISA - INRIA Rennes) - - \sa vpMatrix vpColVector vpRowVector -*/ + * \class vpSubMatrix + * \ingroup group_core_matrices + * \brief Definition of the vpSubMatrix class that provides a mask on a vpMatrix. + * All properties of vpMatrix are available with a vpSubMatrix. + * + * + * \sa vpMatrix vpColVector vpRowVector + */ class VISP_EXPORT vpSubMatrix : public vpMatrix { - private: //! Eye method unavailable void eye(unsigned int n); @@ -77,7 +73,7 @@ class VISP_EXPORT vpSubMatrix : public vpMatrix vpSubMatrix(vpMatrix &m, const unsigned int &row, const unsigned int &col, const unsigned int &nrows, const unsigned int &ncols); //! Destructor - virtual ~vpSubMatrix() override; + virtual ~vpSubMatrix() vp_override; //! Initialisation of vpMatrix void init(vpMatrix &m, const unsigned int &row, const unsigned int &col, const unsigned int &nrows, diff --git a/modules/core/include/visp3/core/vpSubRowVector.h b/modules/core/include/visp3/core/vpSubRowVector.h index d5fc68e2b2..c5fa99611a 100644 --- a/modules/core/include/visp3/core/vpSubRowVector.h +++ b/modules/core/include/visp3/core/vpSubRowVector.h @@ -67,7 +67,7 @@ class VISP_EXPORT vpSubRowVector : public vpRowVector public: vpSubRowVector(); vpSubRowVector(vpRowVector &v, const unsigned int &offset, const unsigned int &ncols); - virtual ~vpSubRowVector() override; + virtual ~vpSubRowVector() vp_override; void checkParentStatus() const; diff --git a/modules/core/include/visp3/core/vpThetaUVector.h b/modules/core/include/visp3/core/vpThetaUVector.h index 58df309e97..0b624334ea 100644 --- a/modules/core/include/visp3/core/vpThetaUVector.h +++ b/modules/core/include/visp3/core/vpThetaUVector.h @@ -129,37 +129,37 @@ class vpQuaternionVector; matrix. \code -#include -#include -#include -#include + #include + #include + #include + #include -int main() -{ - vpThetaUVector tu; + int main() + { + vpThetaUVector tu; - // Initialise the theta U rotation vector - tu[0] = vpMath::rad( 45.f); - tu[1] = vpMath::rad(-30.f); - tu[2] = vpMath::rad( 90.f); + // Initialise the theta U rotation vector + tu[0] = vpMath::rad( 45.f); + tu[1] = vpMath::rad(-30.f); + tu[2] = vpMath::rad( 90.f); - // Construct a rotation matrix from the theta U angles - vpRotationMatrix R(tu); + // Construct a rotation matrix from the theta U angles + vpRotationMatrix R(tu); - // Extract the theta U angles from a rotation matrix - tu.buildFrom(R); + // Extract the theta U angles from a rotation matrix + tu.buildFrom(R); - // Print the extracted theta U angles. Values are the same than the - // one used for initialization - std::cout << tu; + // Print the extracted theta U angles. Values are the same than the + // one used for initialization + std::cout << tu; - // Since the rotation vector is 3 values column vector, the - // transpose operation produce a row vector. - vpRowVector tu_t = tu.t(); + // Since the rotation vector is 3 values column vector, the + // transpose operation produce a row vector. + vpRowVector tu_t = tu.t(); - // Print the transpose row vector - std::cout << tu_t << std::endl; -} + // Print the transpose row vector + std::cout << tu_t << std::endl; + } \endcode */ class VISP_EXPORT vpThetaUVector : public vpRotationVector @@ -216,7 +216,9 @@ 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 0977febeec..472b8bdd5b 100644 --- a/modules/core/include/visp3/core/vpTime.h +++ b/modules/core/include/visp3/core/vpTime.h @@ -37,35 +37,36 @@ /*! \file vpTime.h \brief Time management and measurement -*/ + */ #include #include #include +#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 #include +#endif #include /*! - \ingroup group_core_time - \brief Time management and measurement. - - The example below shows how to synchronize a loop to a given framerate. - - \code -#include - -int main() -{ - double t; - for ( ; ; ) { - t = vpTime::measureTimeMs(); - ... - vpTime::wait(t, 40); // Loop time is set to 40 ms, ie 25 Hz - } -} - \endcode - -*/ + * \ingroup group_core_time + * \brief Time management and measurement. + * + * The example below shows how to synchronize a loop to a given framerate. + * + * \code + * #include + * + * int main() + * { + * double t; + * for ( ; ; ) { + * t = vpTime::measureTimeMs(); + * ... + * vpTime::wait(t, 40); // Loop time is set to 40 ms, ie 25 Hz + * } + * } + * \endcode + */ namespace vpTime { @@ -92,7 +93,8 @@ class VISP_EXPORT vpChrono private: double m_durationMs; -#if (defined(_MSC_VER) && _MSC_VER >= 1900 /* VS2015 */ || !defined(_MSC_VER)) +#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 && \ + (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 0d9c9a4fd2..f9a20a4786 100644 --- a/modules/core/include/visp3/core/vpTranslationVector.h +++ b/modules/core/include/visp3/core/vpTranslationVector.h @@ -35,9 +35,9 @@ #define vpTRANSLATIONVECTOR_H /*! - \file vpTranslationVector.h - \brief Class that consider the case of a translation vector. -*/ + * \file vpTranslationVector.h + * \brief Class that consider the case of a translation vector. + */ #include #include @@ -87,25 +87,25 @@ homogeneous matrix. \code -#include -#include -#include + #include + #include + #include -int main() -{ - vpTranslationVector t; // Translation vector + int main() + { + vpTranslationVector t; // Translation vector - // Initialization of the translation vector - t[0] = 0.2; // tx = 0.2 meters - t[1] = -0.1; // ty = -0.1 meters - t[2] = 1.0; // tz = 1 meters + // Initialization of the translation vector + t[0] = 0.2; // tx = 0.2 meters + t[1] = -0.1; // ty = -0.1 meters + t[2] = 1.0; // tz = 1 meters - // Construction of a rotation matrix - vpRotationMatrix R; // Set to identity by default + // Construction of a rotation matrix + vpRotationMatrix R; // Set to identity by default - // Construction of an homogeneous matrix - vpHomogeneousMatrix M(t, R); -} + // Construction of an homogeneous matrix + vpHomogeneousMatrix M(t, R); + } \endcode */ class VISP_EXPORT vpTranslationVector : public vpArray2D @@ -148,7 +148,9 @@ 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 34dfd32833..b57614149f 100644 --- a/modules/core/include/visp3/core/vpUniRand.h +++ b/modules/core/include/visp3/core/vpUniRand.h @@ -30,6 +30,7 @@ * Description: * Pseudo random number generator. */ + /* * PCG Random Number Generation for C. * @@ -72,9 +73,13 @@ typedef unsigned __int32 uint32_t; #include #endif +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_11) #include // std::shuffle #include // std::mt19937 #include // std::iota +#else +#include // std::random_shuffle +#endif #include /*! @@ -121,7 +126,7 @@ class VISP_EXPORT vpUniRand { // Internals are *Private*. uint64_t state; // RNG state. All values are possible. uint64_t inc; // Controls which RNG sequence (stream) is - // selected. Must *always* be odd. + // selected. Must *always* be odd. vpPcgStateSetseq_64_t(uint64_t state_ = 0x853c49e6748fea9bULL, uint64_t inc_ = 0xda3e39cb94b95bdbULL) : state(state_), inc(inc_) @@ -152,7 +157,11 @@ 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 67774be7e3..2b44d0211d 100644 --- a/modules/core/src/camera/vpColorDepthConversion.cpp +++ b/modules/core/src/camera/vpColorDepthConversion.cpp @@ -59,7 +59,11 @@ namespace */ vpImagePoint adjust2DPointToBoundary(const vpImagePoint &ip, double width, double height) { +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) 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 } /*! @@ -71,9 +75,15 @@ vpImagePoint adjust2DPointToBoundary(const vpImagePoint &ip, double width, doubl */ vpColVector transform(const vpHomogeneousMatrix &extrinsics_params, vpColVector from_point) { +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) 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.stack(1.); + return vpColVector(extrinsics_params * from_point, 0, 3); +#endif } /*! @@ -85,7 +95,11 @@ vpColVector transform(const vpHomogeneousMatrix &extrinsics_params, vpColVector */ vpImagePoint project(const vpCameraParameters &intrinsic_cam_params, const vpColVector &point) { +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpImagePoint iP {}; +#else + vpImagePoint iP; +#endif vpMeterPixelConversion::convertPoint(intrinsic_cam_params, point[0] / point[2], point[1] / point[2], iP); return iP; @@ -101,9 +115,20 @@ 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_11) 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 } } // namespace @@ -124,9 +149,9 @@ vpColVector deproject(const vpCameraParameters &intrinsic_cam_params, const vpIm * \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, - const vpCameraParameters &depth_intrinsics, const vpCameraParameters &color_intrinsics, - const vpHomogeneousMatrix &color_M_depth, const vpHomogeneousMatrix &depth_M_color, const vpImagePoint &from_pixel) + const vpImage &I_depth, double depth_scale, double depth_min, double depth_max, + const vpCameraParameters &depth_intrinsics, const vpCameraParameters &color_intrinsics, + const vpHomogeneousMatrix &color_M_depth, const vpHomogeneousMatrix &depth_M_color, const vpImagePoint &from_pixel) { return projectColorToDepth(I_depth.bitmap, depth_scale, depth_min, depth_max, I_depth.getWidth(), I_depth.getHeight(), depth_intrinsics, color_intrinsics, color_M_depth, depth_M_color, from_pixel); @@ -150,10 +175,11 @@ vpImagePoint vpColorDepthConversion::projectColorToDepth( * \return Image point expressed into the depth camera frame. */ vpImagePoint vpColorDepthConversion::projectColorToDepth( - const uint16_t *data, double depth_scale, double depth_min, double depth_max, double depth_width, - 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) + const uint16_t *data, double depth_scale, double depth_min, double depth_max, double depth_width, + 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_11) vpImagePoint depth_pixel {}; // Find line start pixel @@ -188,5 +214,40 @@ vpImagePoint vpColorDepthConversion::projectColorToDepth( } } +#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()); + 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 975c8cdd23..810caa53fe 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) +#if defined(VISP_HAVE_OPENMP) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include #endif @@ -60,7 +60,7 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage= VISP_CXX_STANDARD_11) int nThreads = omp_get_max_threads(); std::vector > histograms(nThreads); for (int i = 0; i < nThreads; i++) { @@ -120,7 +120,7 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage= VISP_CXX_STANDARD_11) int nThreads = omp_get_max_threads(); std::vector > histograms(nThreads); for (int i = 0; i < nThreads; i++) { diff --git a/modules/core/src/image/vpGaussianFilter.cpp b/modules/core/src/image/vpGaussianFilter.cpp index c58e7e3d40..efba11d42f 100644 --- a/modules/core/src/image/vpGaussianFilter.cpp +++ b/modules/core/src/image/vpGaussianFilter.cpp @@ -150,7 +150,7 @@ void vpGaussianFilter::apply(const vpImage &I, vpImage &I, vpImage &I_blur) { m_impl->apply(I, I_blur); } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpGaussianFilter.cpp.o) has no symbols + // Work around to avoid warning: libvisp_core.a(vpGaussianFilter.cpp.o) has no symbols void dummy_vpGaussianFilter() { }; #endif diff --git a/modules/core/src/image/vpImageConvert.cpp b/modules/core/src/image/vpImageConvert.cpp index 0d4f1e2a62..b9a9b592e3 100644 --- a/modules/core/src/image/vpImageConvert.cpp +++ b/modules/core/src/image/vpImageConvert.cpp @@ -106,14 +106,17 @@ void vpImageConvert::convert(const vpImage &src, vpImage & src.getMinMaxValue(min, max); - for (unsigned int i = 0; i < max_xy; i++) { - float val = 255.f * (src.bitmap[i] - min) / (max - min); - if (val < 0) + for (unsigned int i = 0; i < max_xy; ++i) { + float val = 255.f * ((src.bitmap[i] - min) / (max - min)); + if (val < 0) { dest.bitmap[i] = 0; - else if (val > 255) + } + else if (val > 255) { dest.bitmap[i] = 255; - else - dest.bitmap[i] = (unsigned char)val; + } + else { + dest.bitmap[i] = static_cast(val); + } } } @@ -125,21 +128,25 @@ void vpImageConvert::convert(const vpImage &src, vpImage & */ void vpImageConvert::convert(const vpImage &src, vpImage &dest) { + const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth(); dest.resize(src.getHeight(), src.getWidth()); vpRGBf min, max; src.getMinMaxValue(min, max); - for (unsigned int i = 0; i < src.getHeight(); i++) { - for (unsigned int j = 0; j < src.getWidth(); j++) { - for (unsigned int c = 0; c < 3; c++) { - float val = 255.f * (reinterpret_cast(&(src[i][j]))[c] - reinterpret_cast(&min)[c]) / - (reinterpret_cast(&max)[c] - reinterpret_cast(&min)[c]); - if (val < 0) + for (unsigned int i = 0; i < srcHeight; ++i) { + for (unsigned int j = 0; j < srcWidth; ++j) { + for (unsigned int c = 0; c < 3; ++c) { + float val = 255.f * ((reinterpret_cast(&(src[i][j]))[c] - reinterpret_cast(&min)[c]) / + (reinterpret_cast(&max)[c] - reinterpret_cast(&min)[c])); + if (val < 0) { reinterpret_cast(&(dest[i][j]))[c] = 0; - else if (val > 255) + } + else if (val > 255) { reinterpret_cast(&(dest[i][j]))[c] = 255; - else - reinterpret_cast(&(dest[i][j]))[c] = (unsigned char)val; + } + else { + reinterpret_cast(&(dest[i][j]))[c] = static_cast(val); + } } } } @@ -152,9 +159,12 @@ void vpImageConvert::convert(const vpImage &src, vpImage &dest) */ void vpImageConvert::convert(const vpImage &src, vpImage &dest) { - dest.resize(src.getHeight(), src.getWidth()); - for (unsigned int i = 0; i < src.getHeight() * src.getWidth(); i++) - dest.bitmap[i] = (float)src.bitmap[i]; + const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth(); + const unsigned int srcSize = srcHeight * srcWidth; + dest.resize(srcHeight, srcWidth); + for (unsigned int i = 0; i < srcSize; ++i) { + dest.bitmap[i] = static_cast(src.bitmap[i]); + } } /*! @@ -171,14 +181,17 @@ void vpImageConvert::convert(const vpImage &src, vpImage src.getMinMaxValue(min, max); - for (unsigned int i = 0; i < max_xy; i++) { - double val = 255. * (src.bitmap[i] - min) / (max - min); - if (val < 0) + for (unsigned int i = 0; i < max_xy; ++i) { + double val = 255. * ((src.bitmap[i] - min) / (max - min)); + if (val < 0) { dest.bitmap[i] = 0; - else if (val > 255) + } + else if (val > 255) { dest.bitmap[i] = 255; - else - dest.bitmap[i] = (unsigned char)val; + } + else { + dest.bitmap[i] = static_cast(val); + } } } @@ -190,10 +203,12 @@ void vpImageConvert::convert(const vpImage &src, vpImage */ void vpImageConvert::convert(const vpImage &src, vpImage &dest, unsigned char bitshift) { + const unsigned int srcSize = src.getSize(); dest.resize(src.getHeight(), src.getWidth()); - for (unsigned int i = 0; i < src.getSize(); i++) + for (unsigned int i = 0; i < srcSize; ++i) { dest.bitmap[i] = static_cast(src.bitmap[i] >> bitshift); + } } /*! @@ -204,10 +219,12 @@ void vpImageConvert::convert(const vpImage &src, vpImage &src, vpImage &dest, unsigned char bitshift) { + const unsigned int srcSize = src.getSize(); dest.resize(src.getHeight(), src.getWidth()); - for (unsigned int i = 0; i < src.getSize(); i++) + for (unsigned int i = 0; i < srcSize; ++i) { dest.bitmap[i] = static_cast(src.bitmap[i] << bitshift); + } } /*! @@ -217,9 +234,12 @@ void vpImageConvert::convert(const vpImage &src, vpImage &src, vpImage &dest) { - dest.resize(src.getHeight(), src.getWidth()); - for (unsigned int i = 0; i < src.getHeight() * src.getWidth(); i++) - dest.bitmap[i] = (double)src.bitmap[i]; + const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth(); + const unsigned int srcSize = srcHeight * srcWidth; + dest.resize(srcHeight, srcWidth); + for (unsigned int i = 0; i < srcSize; ++i) { + dest.bitmap[i] = static_cast(src.bitmap[i]); + } } /*! @@ -312,26 +332,29 @@ void vpImageConvert::createDepthHistogram(const vpImage &src_depth, vpIma */ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool flip) { - dest.resize((unsigned int)src.rows, (unsigned int)src.cols); - + dest.resize(static_cast(src.rows), static_cast(src.cols)); + unsigned int destRows = dest.getRows(); + unsigned int destCols = dest.getCols(); if (src.type() == CV_8UC4) { vpRGBa rgbaVal; - for (unsigned int i = 0; i < dest.getRows(); ++i) - for (unsigned int j = 0; j < dest.getCols(); ++j) { - cv::Vec4b tmp = src.at((int)i, (int)j); + for (unsigned int i = 0; i < destRows; ++i) + for (unsigned int j = 0; j < destCols; ++j) { + cv::Vec4b tmp = src.at(static_cast(i), static_cast(j)); rgbaVal.R = tmp[2]; rgbaVal.G = tmp[1]; rgbaVal.B = tmp[0]; rgbaVal.A = tmp[3]; - if (flip) - dest[dest.getRows() - i - 1][j] = rgbaVal; - else + if (flip) { + dest[destRows - i - 1][j] = rgbaVal; + } + else { dest[i][j] = rgbaVal; + } } } else if (src.type() == CV_8UC3) { #if defined(VISP_HAVE_SIMDLIB) - if (src.isContinuous() && !flip) { + if (src.isContinuous() && (!flip)) { SimdRgbToBgra(src.data, src.cols, src.rows, src.step[0], reinterpret_cast(dest.bitmap), dest.getWidth() * sizeof(vpRGBa), vpRGBa::alpha_default); } @@ -339,14 +362,14 @@ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool fli #endif vpRGBa rgbaVal; rgbaVal.A = vpRGBa::alpha_default; - for (unsigned int i = 0; i < dest.getRows(); ++i) { - for (unsigned int j = 0; j < dest.getCols(); ++j) { - cv::Vec3b tmp = src.at((int)i, (int)j); + for (unsigned int i = 0; i < destRows; ++i) { + for (unsigned int j = 0; j < destCols; ++j) { + cv::Vec3b tmp = src.at(static_cast(i), static_cast(j)); rgbaVal.R = tmp[2]; rgbaVal.G = tmp[1]; rgbaVal.B = tmp[0]; if (flip) { - dest[dest.getRows() - i - 1][j] = rgbaVal; + dest[destRows - i - 1][j] = rgbaVal; } else { dest[i][j] = rgbaVal; @@ -359,19 +382,19 @@ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool fli } else if (src.type() == CV_8UC1) { #if defined(VISP_HAVE_SIMDLIB) - if (src.isContinuous() && !flip) { + if (src.isContinuous() && (!flip)) { SimdGrayToBgra(src.data, src.cols, src.rows, src.step[0], reinterpret_cast(dest.bitmap), dest.getWidth() * sizeof(vpRGBa), vpRGBa::alpha_default); } else { #endif vpRGBa rgbaVal; - for (unsigned int i = 0; i < dest.getRows(); ++i) { - for (unsigned int j = 0; j < dest.getCols(); ++j) { - rgbaVal = src.at((int)i, (int)j); + for (unsigned int i = 0; i < destRows; ++i) { + for (unsigned int j = 0; j < destCols; ++j) { + rgbaVal = src.at(static_cast(i), static_cast(j)); rgbaVal.A = vpRGBa::alpha_default; if (flip) { - dest[dest.getRows() - i - 1][j] = rgbaVal; + dest[destRows - i - 1][j] = rgbaVal; } else { dest[i][j] = rgbaVal; @@ -422,63 +445,69 @@ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool fli void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool flip, unsigned int nThreads) { if (src.type() == CV_8UC1) { - dest.resize((unsigned int)src.rows, (unsigned int)src.cols); - if (src.isContinuous() && !flip) { - memcpy(dest.bitmap, src.data, (size_t)(src.rows * src.cols)); + dest.resize(static_cast(src.rows), static_cast(src.cols)); + unsigned int destRows = dest.getRows(); + unsigned int destCols = dest.getCols(); + if (src.isContinuous() && (!flip)) { + memcpy(dest.bitmap, src.data, static_cast(src.rows * src.cols)); } else { if (flip) { - for (unsigned int i = 0; i < dest.getRows(); ++i) { - memcpy(dest.bitmap + i * dest.getCols(), src.data + (dest.getRows() - i - 1) * src.step1(), (size_t)src.step); + for (unsigned int i = 0; i < destRows; ++i) { + memcpy(dest.bitmap + (i * destCols), src.data + ((destRows - i - 1) * src.step1()), static_cast(src.step)); } } else { - for (unsigned int i = 0; i < dest.getRows(); ++i) { - memcpy(dest.bitmap + i * dest.getCols(), src.data + i * src.step1(), (size_t)src.step); + for (unsigned int i = 0; i < destRows; ++i) { + memcpy(dest.bitmap + (i * destCols), src.data + (i * src.step1()), static_cast(src.step)); } } } } else if (src.type() == CV_8UC3) { - dest.resize((unsigned int)src.rows, (unsigned int)src.cols); + dest.resize(static_cast(src.rows), static_cast(src.cols)); + unsigned int destRows = dest.getRows(); + unsigned int destCols = dest.getCols(); if (src.isContinuous()) { - BGRToGrey((unsigned char *)src.data, (unsigned char *)dest.bitmap, (unsigned int)src.cols, (unsigned int)src.rows, + BGRToGrey((unsigned char *)src.data, (unsigned char *)dest.bitmap, static_cast(src.cols), static_cast(src.rows), flip, nThreads); } else { if (flip) { - for (unsigned int i = 0; i < dest.getRows(); ++i) { - BGRToGrey((unsigned char *)src.data + i * src.step1(), - (unsigned char *)dest.bitmap + (dest.getRows() - i - 1) * dest.getCols(), - (unsigned int)dest.getCols(), 1, false); + for (unsigned int i = 0; i < destRows; ++i) { + BGRToGrey((unsigned char *)src.data + (i * src.step1()), + (unsigned char *)dest.bitmap + ((destRows - i - 1) * destCols), + static_cast(destCols), 1, false); } } else { - for (unsigned int i = 0; i < dest.getRows(); ++i) { - BGRToGrey((unsigned char *)src.data + i * src.step1(), (unsigned char *)dest.bitmap + i * dest.getCols(), - (unsigned int)dest.getCols(), 1, false); + for (unsigned int i = 0; i < destRows; ++i) { + BGRToGrey((unsigned char *)src.data + (i * src.step1()), (unsigned char *)dest.bitmap + (i * destCols), + static_cast(destCols), 1, false); } } } } else if (src.type() == CV_8UC4) { - dest.resize((unsigned int)src.rows, (unsigned int)src.cols); + dest.resize(static_cast(src.rows), static_cast(src.cols)); + unsigned int destRows = dest.getRows(); + unsigned int destCols = dest.getCols(); if (src.isContinuous()) { - BGRaToGrey((unsigned char *)src.data, (unsigned char *)dest.bitmap, (unsigned int)src.cols, - (unsigned int)src.rows, flip, nThreads); + BGRaToGrey((unsigned char *)src.data, (unsigned char *)dest.bitmap, static_cast(src.cols), + static_cast(src.rows), flip, nThreads); } else { if (flip) { - for (unsigned int i = 0; i < dest.getRows(); ++i) { - BGRaToGrey((unsigned char *)src.data + i * src.step1(), - (unsigned char *)dest.bitmap + (dest.getRows() - i - 1) * dest.getCols(), - (unsigned int)dest.getCols(), 1, false); + for (unsigned int i = 0; i < destRows; ++i) { + BGRaToGrey((unsigned char *)src.data + (i * src.step1()), + (unsigned char *)dest.bitmap + ((destRows - i - 1) * destCols), + static_cast(destCols), 1, false); } } else { - for (unsigned int i = 0; i < dest.getRows(); ++i) { - BGRaToGrey((unsigned char *)src.data + i * src.step1(), (unsigned char *)dest.bitmap + i * dest.getCols(), - (unsigned int)dest.getCols(), 1, false); + for (unsigned int i = 0; i < destRows; ++i) { + BGRaToGrey((unsigned char *)src.data + (i * src.step1()), (unsigned char *)dest.bitmap + (i * destCols), + static_cast(destCols), 1, false); } } } @@ -494,15 +523,19 @@ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, b */ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool flip) { - dest.resize((unsigned int)src.rows, (unsigned int)src.cols); + dest.resize(static_cast(src.rows), static_cast(src.cols)); + unsigned int destRows = dest.getRows(); + unsigned int destCols = dest.getCols(); if (src.type() == CV_32FC1) { - for (unsigned int i = 0; i < dest.getRows(); ++i) - for (unsigned int j = 0; j < dest.getCols(); ++j) { - if (flip) - dest[dest.getRows() - i - 1][j] = src.at((int)i, (int)j); - else - dest[i][j] = src.at((int)i, (int)j); + for (unsigned int i = 0; i < destRows; ++i) + for (unsigned int j = 0; j < destCols; ++j) { + if (flip) { + dest[dest.getRows() - i - 1][j] = src.at(static_cast(i), static_cast(j)); + } + else { + dest[i][j] = src.at(static_cast(i), static_cast(j)); + } } } else { @@ -521,8 +554,8 @@ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool fli { vpImage I_float; convert(src, I_float, flip); - unsigned int nbRows = (unsigned int)src.rows; - unsigned int nbCols = (unsigned int)src.cols; + unsigned int nbRows = static_cast(src.rows); + unsigned int nbCols = static_cast(src.cols); dest.resize(nbRows, nbCols); for (unsigned int i = 0; i < nbRows; ++i) { for (unsigned int j = 0; j < nbCols; ++j) { @@ -540,21 +573,23 @@ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool fli */ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool flip) { - dest.resize((unsigned int)src.rows, (unsigned int)src.cols); + dest.resize(static_cast(src.rows), static_cast(src.cols)); + unsigned int destRows = dest.getRows(); + unsigned int destCols = dest.getCols(); if (src.type() == CV_16UC1) { if (src.isContinuous()) { - memcpy(dest.bitmap, src.data, (size_t)(src.rows * src.cols) * sizeof(uint16_t)); + memcpy(dest.bitmap, src.data, static_cast(src.rows * src.cols) * sizeof(uint16_t)); } else { if (flip) { - for (unsigned int i = 0; i < dest.getRows(); ++i) { - memcpy(dest.bitmap + i * dest.getCols(), src.data + (dest.getRows() - i - 1) * src.step1() * sizeof(uint16_t), (size_t)src.step); + for (unsigned int i = 0; i < destRows; ++i) { + memcpy(dest.bitmap + (i * destCols), src.data + ((destRows - i - 1) * src.step1() * sizeof(uint16_t)), static_cast(src.step)); } } else { - for (unsigned int i = 0; i < dest.getRows(); ++i) { - memcpy(dest.bitmap + i * dest.getCols(), src.data + i * src.step1() * sizeof(uint16_t), (size_t)src.step); + for (unsigned int i = 0; i < destRows; ++i) { + memcpy(dest.bitmap + (i * destCols), src.data + (i * src.step1() * sizeof(uint16_t)), static_cast(src.step)); } } } @@ -573,20 +608,24 @@ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool f */ void vpImageConvert::convert(const cv::Mat &src, vpImage &dest, bool flip) { - dest.resize((unsigned int)src.rows, (unsigned int)src.cols); + dest.resize(static_cast(src.rows), static_cast(src.cols)); + unsigned int destRows = dest.getRows(); + unsigned int destCols = dest.getCols(); if (src.type() == CV_32FC3) { vpRGBf rgbVal; - for (unsigned int i = 0; i < dest.getRows(); ++i) - for (unsigned int j = 0; j < dest.getCols(); ++j) { - cv::Vec3f tmp = src.at((int)i, (int)j); + for (unsigned int i = 0; i < destRows; ++i) + for (unsigned int j = 0; j < destCols; ++j) { + cv::Vec3f tmp = src.at(static_cast(i), static_cast(j)); rgbVal.R = tmp[2]; rgbVal.G = tmp[1]; rgbVal.B = tmp[0]; - if (flip) - dest[dest.getRows() - i - 1][j] = rgbVal; - else + if (flip) { + dest[destRows - i - 1][j] = rgbVal; + } + else { dest[i][j] = rgbVal; + } } } else { @@ -632,7 +671,7 @@ int main() */ void vpImageConvert::convert(const vpImage &src, cv::Mat &dest) { - cv::Mat vpToMat((int)src.getRows(), (int)src.getCols(), CV_8UC4, (void *)src.bitmap); + cv::Mat vpToMat(static_cast(src.getRows()), static_cast(src.getCols()), CV_8UC4, (void *)src.bitmap); cv::cvtColor(vpToMat, dest, cv::COLOR_RGBA2BGR); } @@ -677,22 +716,22 @@ int main() void vpImageConvert::convert(const vpImage &src, cv::Mat &dest, bool copyData) { if (copyData) { - cv::Mat tmpMap((int)src.getRows(), (int)src.getCols(), CV_8UC1, (void *)src.bitmap); + cv::Mat tmpMap(static_cast(src.getRows()), static_cast(src.getCols()), CV_8UC1, (void *)src.bitmap); dest = tmpMap.clone(); } else { - dest = cv::Mat((int)src.getRows(), (int)src.getCols(), CV_8UC1, (void *)src.bitmap); + dest = cv::Mat(static_cast(src.getRows()), static_cast(src.getCols()), CV_8UC1, (void *)src.bitmap); } } void vpImageConvert::convert(const vpImage &src, cv::Mat &dest, bool copyData) { if (copyData) { - cv::Mat tmpMap((int)src.getRows(), (int)src.getCols(), CV_32FC1, (void *)src.bitmap); + cv::Mat tmpMap(static_cast(src.getRows()), static_cast(src.getCols()), CV_32FC1, (void *)src.bitmap); dest = tmpMap.clone(); } else { - dest = cv::Mat((int)src.getRows(), (int)src.getCols(), CV_32FC1, (void *)src.bitmap); + dest = cv::Mat(static_cast(src.getRows()), static_cast(src.getCols()), CV_32FC1, (void *)src.bitmap); } } @@ -711,7 +750,7 @@ void vpImageConvert::convert(const vpImage &src, cv::Mat &dest, bool cop void vpImageConvert::convert(const vpImage &src, cv::Mat &dest) { - cv::Mat vpToMat((int)src.getRows(), (int)src.getCols(), CV_32FC3, (void *)src.bitmap); + cv::Mat vpToMat(static_cast(src.getRows()), static_cast(src.getCols()), CV_32FC3, (void *)src.bitmap); cv::cvtColor(vpToMat, dest, cv::COLOR_RGB2BGR); } @@ -758,8 +797,9 @@ void vpImageConvert::convert(const vpImage &src, yarp::sig::Image dest->resize(src.getWidth(), src.getHeight()); memcpy(dest->getRawImage(), src.bitmap, src.getHeight() * src.getWidth()); } - else - dest->setExternal(src.bitmap, (int)src.getCols(), (int)src.getRows()); + else { + dest->setExternal(src.bitmap, static_cast(src.getCols()), static_cast(src.getRows())); + } } /*! @@ -804,10 +844,12 @@ void vpImageConvert::convert(const yarp::sig::ImageOf *src bool copyData) { dest.resize(src->height(), src->width()); - if (copyData) + if (copyData) { memcpy(dest.bitmap, src->getRawImage(), src->height() * src->width() * sizeof(yarp::sig::PixelMono)); - else + } + else { dest.bitmap = src->getRawImage(); + } } /*! @@ -850,8 +892,9 @@ void vpImageConvert::convert(const vpImage &src, yarp::sig::ImageOfresize(src.getWidth(), src.getHeight()); memcpy(dest->getRawImage(), src.bitmap, src.getHeight() * src.getWidth() * sizeof(vpRGBa)); } - else - dest->setExternal(src.bitmap, (int)src.getCols(), (int)src.getRows()); + else { + dest->setExternal(src.bitmap, static_cast(src.getCols()), static_cast(src.getRows())); + } } /*! @@ -897,8 +940,9 @@ void vpImageConvert::convert(const yarp::sig::ImageOf *src dest.resize(src->height(), src->width()); if (copyData) memcpy(dest.bitmap, src->getRawImage(), src->height() * src->width() * sizeof(yarp::sig::PixelRgba)); - else + else { dest.bitmap = static_cast(src->getRawImage()); + } } /*! @@ -935,9 +979,10 @@ int main() */ void vpImageConvert::convert(const vpImage &src, yarp::sig::ImageOf *dest) { + const unsigned int srcRows = src.getRows(), srcWidth = src.getWidth(); dest->resize(src.getWidth(), src.getHeight()); - for (unsigned int i = 0; i < src.getRows(); i++) { - for (unsigned int j = 0; j < src.getWidth(); j++) { + for (unsigned int i = 0; i < srcRows; ++i) { + for (unsigned int j = 0; j < srcWidth; ++j) { dest->pixel(j, i).r = src[i][j].R; dest->pixel(j, i).g = src[i][j].G; dest->pixel(j, i).b = src[i][j].B; @@ -985,9 +1030,10 @@ int main() */ void vpImageConvert::convert(const yarp::sig::ImageOf *src, vpImage &dest) { - dest.resize(src->height(), src->width()); - for (int i = 0; i < src->height(); i++) { - for (int j = 0; j < src->width(); j++) { + const int srcHeight = src->height(), srcWidth = src->width(); + dest.resize(srcHeight, srcWidth); + for (int i = 0; i < srcHeight; ++i) { + for (int j = 0; j < srcWidth; ++j) { dest[i][j].R = src->pixel(j, i).r; dest[i][j].G = src->pixel(j, i).g; dest[i][j].B = src->pixel(j, i).b; @@ -1000,10 +1046,10 @@ void vpImageConvert::convert(const yarp::sig::ImageOf *src, #define vpSAT(c) \ if (c & (~255)) { \ - if (c < 0) \ - c = 0; \ + if (c < 0) \ + {c = 0;} \ else \ - c = 255; \ + {c = 255;} \ } /*! Convert an image from YUYV 4:2:2 (y0 u01 y1 v01 y2 u23 y3 v23 ...) to RGB32. @@ -1024,8 +1070,8 @@ void vpImageConvert::YUYVToRGBa(unsigned char *yuyv, unsigned char *rgba, unsign int w, h; int r, g, b, cr, cg, cb, y1, y2; - h = (int)height; - w = (int)width; + h = static_cast(height); + w = static_cast(width); s = yuyv; d = rgba; while (h--) { @@ -1036,7 +1082,7 @@ void vpImageConvert::YUYVToRGBa(unsigned char *yuyv, unsigned char *rgba, unsign cg = (*s++ - 128) * 88; y2 = *s++; cr = ((*s - 128) * 359) >> 8; - cg = (cg + (*s++ - 128) * 183) >> 8; + cg = (cg + ((*s++ - 128) * 183)) >> 8; r = y1 + cr; b = y1 + cb; @@ -1078,8 +1124,8 @@ void vpImageConvert::YUYVToRGB(unsigned char *yuyv, unsigned char *rgb, unsigned int h, w; int r, g, b, cr, cg, cb, y1, y2; - h = (int)height; - w = (int)width; + h = static_cast(height); + w = static_cast(width); s = yuyv; d = rgb; while (h--) { @@ -1090,7 +1136,7 @@ void vpImageConvert::YUYVToRGB(unsigned char *yuyv, unsigned char *rgb, unsigned cg = (*s++ - 128) * 88; y2 = *s++; cr = ((*s - 128) * 359) >> 8; - cg = (cg + (*s++ - 128) * 183) >> 8; + cg = (cg + ((*s++ - 128) * 183)) >> 8; r = y1 + cr; b = y1 + cb; @@ -1126,8 +1172,8 @@ void vpImageConvert::YUYVToRGB(unsigned char *yuyv, unsigned char *rgb, unsigned void vpImageConvert::YUYVToGrey(unsigned char *yuyv, unsigned char *grey, unsigned int size) { unsigned int i = 0, j = 0; - - while (j < size * 2) { + const unsigned int doubleSize = size * 2; + while (j < doubleSize) { grey[i++] = yuyv[j]; grey[i++] = yuyv[j + 2]; j += 4; @@ -1147,12 +1193,12 @@ void vpImageConvert::YUV411ToRGBa(unsigned char *yuv, unsigned char *rgba, unsig { #if 1 // std::cout << "call optimized ConvertYUV411ToRGBa()" << std::endl; - for (unsigned int i = size / 4; i; i--) { - int U = (int)((*yuv++ - 128) * 0.354); + for (unsigned int i = size / 4; i; --i) { + int U = static_cast((*yuv++ - 128) * 0.354); int U5 = 5 * U; int Y0 = *yuv++; int Y1 = *yuv++; - int V = (int)((*yuv++ - 128) * 0.707); + int V = static_cast((*yuv++ - 128) * 0.707); int V2 = 2 * V; int Y2 = *yuv++; int Y3 = *yuv++; @@ -1163,105 +1209,130 @@ void vpImageConvert::YUV411ToRGBa(unsigned char *yuv, unsigned char *rgba, unsig // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U int R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } int G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } int B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y2 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y2 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y2 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y3 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y3 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y3 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; } #else // tres tres lent .... unsigned int i = 0, j = 0; unsigned char r, g, b; - while (j < numpixels * 3 / 2) { + const unsigned int iterLimit = (numpixels * 3) / 2; + while (j < iterLimit) { YUVToRGB(yuv[j + 1], yuv[j], yuv[j + 3], r, g, b); rgba[i] = r; @@ -1313,61 +1384,73 @@ void vpImageConvert::YUV422ToRGBa(unsigned char *yuv, unsigned char *rgba, unsig #if 1 // std::cout << "call optimized convertYUV422ToRGBa()" << std::endl; - for (unsigned int i = size / 2; i; i--) { - int U = (int)((*yuv++ - 128) * 0.354); + for (unsigned int i = size / 2; i; --i) { + int U = static_cast((*yuv++ - 128) * 0.354); int U5 = 5 * U; int Y0 = *yuv++; - int V = (int)((*yuv++ - 128) * 0.707); + int V = static_cast((*yuv++ - 128) * 0.707); int V2 = 2 * V; int Y1 = *yuv++; int UV = -U - V; //--- int R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } int G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } int B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; } @@ -1375,8 +1458,8 @@ void vpImageConvert::YUV422ToRGBa(unsigned char *yuv, unsigned char *rgba, unsig // tres tres lent .... unsigned int i = 0, j = 0; unsigned char r, g, b; - - while (j < size * 2) { + const unsigned int doubleSize = size * 2; + while (j < doubleSize) { YUVToRGB(yuv[j + 1], yuv[j], yuv[j + 2], r, g, b); rgba[i] = r; @@ -1407,7 +1490,8 @@ void vpImageConvert::YUV422ToRGBa(unsigned char *yuv, unsigned char *rgba, unsig void vpImageConvert::YUV411ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size) { unsigned int i = 0, j = 0; - while (j < size * 3 / 2) { + const unsigned int iterLimit = (size * 3) / 2; + while (j < iterLimit) { grey[i] = yuv[j + 1]; grey[i + 1] = yuv[j + 2]; grey[i + 2] = yuv[j + 4]; @@ -1433,68 +1517,80 @@ void vpImageConvert::YUV422ToRGB(unsigned char *yuv, unsigned char *rgb, unsigne { #if 1 // std::cout << "call optimized convertYUV422ToRGB()" << std::endl; - for (unsigned int i = size / 2; i; i--) { - int U = (int)((*yuv++ - 128) * 0.354); + for (unsigned int i = size / 2; i; --i) { + int U = static_cast((*yuv++ - 128) * 0.354); int U5 = 5 * U; int Y0 = *yuv++; - int V = (int)((*yuv++ - 128) * 0.707); + int V = static_cast((*yuv++ - 128) * 0.707); int V2 = 2 * V; int Y1 = *yuv++; int UV = -U - V; //--- int R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } int G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } int B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); } #else // tres tres lent .... unsigned int i = 0, j = 0; unsigned char r, g, b; - - while (j < size * 2) { + const unsigned int doubleSize = size * 2; + while (j < doubleSize) { YUVToRGB(yuv[j + 1], yuv[j], yuv[j + 2], r, g, b); rgb[i] = r; @@ -1525,8 +1621,9 @@ void vpImageConvert::YUV422ToRGB(unsigned char *yuv, unsigned char *rgb, unsigne void vpImageConvert::YUV422ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size) { unsigned int i = 0, j = 0; + const unsigned int doubleSize = size * 2; - while (j < size * 2) { + while (j < doubleSize) { grey[i++] = yuv[j + 1]; grey[i++] = yuv[j + 3]; j += 4; @@ -1545,12 +1642,12 @@ void vpImageConvert::YUV411ToRGB(unsigned char *yuv, unsigned char *rgb, unsigne { #if 1 // std::cout << "call optimized ConvertYUV411ToRGB()" << std::endl; - for (unsigned int i = size / 4; i; i--) { - int U = (int)((*yuv++ - 128) * 0.354); + for (unsigned int i = size / 4; i; --i) { + int U = static_cast((*yuv++ - 128) * 0.354); int U5 = 5 * U; int Y0 = *yuv++; int Y1 = *yuv++; - int V = (int)((*yuv++ - 128) * 0.707); + int V = static_cast((*yuv++ - 128) * 0.707); int V2 = 2 * V; int Y2 = *yuv++; int Y3 = *yuv++; @@ -1561,95 +1658,119 @@ void vpImageConvert::YUV411ToRGB(unsigned char *yuv, unsigned char *rgb, unsigne // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U int R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } int G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } int B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y2 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y2 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y2 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y3 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y3 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y3 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); } #else // tres tres lent .... @@ -1657,7 +1778,8 @@ void vpImageConvert::YUV411ToRGB(unsigned char *yuv, unsigned char *rgb, unsigne unsigned int i = 0, j = 0; unsigned char r, g, b; - while (j < size * 3 / 2) { + const unsigned int iterLimit = (size * 3) / 2; + while (j < iterLimit) { YUVToRGB(yuv[j + 1], yuv[j], yuv[j + 3], r, g, b); rgb[i] = r; rgb[i + 1] = g; @@ -1705,121 +1827,146 @@ void vpImageConvert::YUV420ToRGBa(unsigned char *yuv, unsigned char *rgba, unsig int Y0, Y1, Y2, Y3; unsigned int size = width * height; unsigned char *iU = yuv + size; - unsigned char *iV = yuv + 5 * size / 4; - for (unsigned int i = 0; i < height / 2; i++) { - for (unsigned int j = 0; j < width / 2; j++) { - U = (int)((*iU++ - 128) * 0.354); + unsigned char *iV = yuv + ((5 * size) / 4); + const unsigned int halfHeight = height / 2, halfWidth = width / 2; + for (unsigned int i = 0; i < halfHeight; ++i) { + for (unsigned int j = 0; j < halfWidth; ++j) { + U = static_cast((*iU++ - 128) * 0.354); U5 = 5 * U; - V = (int)((*iV++ - 128) * 0.707); + V = static_cast((*iV++ - 128) * 0.707); V2 = 2 * V; UV = -U - V; Y0 = *yuv++; Y1 = *yuv; - yuv = yuv + width - 1; + yuv = yuv + (width - 1); Y2 = *yuv++; Y3 = *yuv; - yuv = yuv - width + 1; + yuv = (yuv - width) + 1; // Original equations // R = Y + 1.402 V // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba = vpRGBa::alpha_default; rgba = rgba + 4 * width - 7; //--- R = Y2 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y2 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y2 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y3 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y3 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y3 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba = vpRGBa::alpha_default; - rgba = rgba - 4 * width + 1; + rgba = (rgba - (4 * width)) + 1; } yuv += width; rgba += 4 * width; @@ -1841,117 +1988,142 @@ void vpImageConvert::YUV420ToRGB(unsigned char *yuv, unsigned char *rgb, unsigne int Y0, Y1, Y2, Y3; unsigned int size = width * height; unsigned char *iU = yuv + size; - unsigned char *iV = yuv + 5 * size / 4; - for (unsigned int i = 0; i < height / 2; i++) { - for (unsigned int j = 0; j < width / 2; j++) { - U = (int)((*iU++ - 128) * 0.354); + unsigned char *iV = yuv + ((5 * size) / 4); + const unsigned int halfHeight = height / 2, halfWidth = width / 2; + for (unsigned int i = 0; i < halfHeight; ++i) { + for (unsigned int j = 0; j < halfWidth; ++j) { + U = static_cast((*iU++ - 128) * 0.354); U5 = 5 * U; - V = (int)((*iV++ - 128) * 0.707); + V = static_cast((*iV++ - 128) * 0.707); V2 = 2 * V; UV = -U - V; Y0 = *yuv++; Y1 = *yuv; - yuv = yuv + width - 1; + yuv = yuv + (width - 1); Y2 = *yuv++; Y3 = *yuv; - yuv = yuv - width + 1; + yuv = (yuv - width) + 1; // Original equations // R = Y + 1.402 V // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb = (unsigned char)B; - rgb = rgb + 3 * width - 5; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb = static_cast(B); + rgb = rgb + ((3 * width) - 5); //--- R = Y2 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y2 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y2 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y3 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y3 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y3 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb = (unsigned char)B; - rgb = rgb - 3 * width + 1; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb = static_cast(B); + rgb = (rgb - (3 * width)) + 1; } yuv += width; rgb += 3 * width; @@ -1967,7 +2139,7 @@ void vpImageConvert::YUV420ToRGB(unsigned char *yuv, unsigned char *rgb, unsigne */ void vpImageConvert::YUV420ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size) { - for (unsigned int i = 0; i < size; i++) { + for (unsigned int i = 0; i < size; ++i) { *grey++ = *yuv++; } } @@ -1983,11 +2155,11 @@ void vpImageConvert::YUV420ToGrey(unsigned char *yuv, unsigned char *grey, unsig */ void vpImageConvert::YUV444ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size) { - for (unsigned int i = 0; i < size; i++) { - int U = (int)((*yuv++ - 128) * 0.354); + for (unsigned int i = 0; i < size; ++i) { + int U = static_cast((*yuv++ - 128) * 0.354); int U5 = 5 * U; int Y = *yuv++; - int V = (int)((*yuv++ - 128) * 0.707); + int V = static_cast((*yuv++ - 128) * 0.707); int V2 = 2 * V; int UV = -U - V; @@ -1996,26 +2168,32 @@ void vpImageConvert::YUV444ToRGBa(unsigned char *yuv, unsigned char *rgba, unsig // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U int R = Y + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } int G = Y + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } int B = Y + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; } } @@ -2029,11 +2207,11 @@ void vpImageConvert::YUV444ToRGBa(unsigned char *yuv, unsigned char *rgba, unsig */ void vpImageConvert::YUV444ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int size) { - for (unsigned int i = 0; i < size; i++) { - int U = (int)((*yuv++ - 128) * 0.354); + for (unsigned int i = 0; i < size; ++i) { + int U = static_cast((*yuv++ - 128) * 0.354); int U5 = 5 * U; int Y = *yuv++; - int V = (int)((*yuv++ - 128) * 0.707); + int V = static_cast((*yuv++ - 128) * 0.707); int V2 = 2 * V; int UV = -U - V; @@ -2042,26 +2220,32 @@ void vpImageConvert::YUV444ToRGB(unsigned char *yuv, unsigned char *rgb, unsigne // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U int R = Y + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } int G = Y + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } int B = Y + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); } } @@ -2074,8 +2258,8 @@ void vpImageConvert::YUV444ToRGB(unsigned char *yuv, unsigned char *rgb, unsigne */ void vpImageConvert::YUV444ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size) { - yuv++; - for (unsigned int i = 0; i < size; i++) { + ++yuv; + for (unsigned int i = 0; i < size; ++i) { *grey++ = *yuv; yuv = yuv + 3; } @@ -2098,121 +2282,146 @@ void vpImageConvert::YV12ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigne int Y0, Y1, Y2, Y3; unsigned int size = width * height; unsigned char *iV = yuv + size; - unsigned char *iU = yuv + 5 * size / 4; - for (unsigned int i = 0; i < height / 2; i++) { - for (unsigned int j = 0; j < width / 2; j++) { - U = (int)((*iU++ - 128) * 0.354); + unsigned char *iU = yuv + ((5 * size) / 4); + const unsigned int halfHeight = height / 2, halfWidth = width / 2; + for (unsigned int i = 0; i < halfHeight; ++i) { + for (unsigned int j = 0; j < halfWidth; ++j) { + U = static_cast((*iU++ - 128) * 0.354); U5 = 5 * U; - V = (int)((*iV++ - 128) * 0.707); + V = static_cast((*iV++ - 128) * 0.707); V2 = 2 * V; UV = -U - V; Y0 = *yuv++; Y1 = *yuv; - yuv = yuv + width - 1; + yuv = yuv + (width - 1); Y2 = *yuv++; Y3 = *yuv; - yuv = yuv - width + 1; + yuv = (yuv - width) + 1; // Original equations // R = Y + 1.402 V // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba = 0; - rgba = rgba + 4 * width - 7; + rgba = rgba + ((4 * width) - 7); //--- R = Y2 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y2 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y2 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y3 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y3 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y3 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba = vpRGBa::alpha_default; - rgba = rgba - 4 * width + 1; + rgba = (rgba - (4 * width)) + 1; } yuv += width; rgba += 4 * width; @@ -2234,117 +2443,142 @@ void vpImageConvert::YV12ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int Y0, Y1, Y2, Y3; unsigned int size = width * height; unsigned char *iV = yuv + size; - unsigned char *iU = yuv + 5 * size / 4; - for (unsigned int i = 0; i < height / 2; i++) { - for (unsigned int j = 0; j < width / 2; j++) { - U = (int)((*iU++ - 128) * 0.354); + unsigned char *iU = yuv + ((5 * size) / 4); + const unsigned int halfHeight = height / 2, halfWidth = width / 2; + for (unsigned int i = 0; i < halfHeight; ++i) { + for (unsigned int j = 0; j < halfWidth; ++j) { + U = static_cast((*iU++ - 128) * 0.354); U5 = 5 * U; - V = (int)((*iV++ - 128) * 0.707); + V = static_cast((*iV++ - 128) * 0.707); V2 = 2 * V; UV = -U - V; Y0 = *yuv++; Y1 = *yuv; - yuv = yuv + width - 1; + yuv = yuv + (width - 1); Y2 = *yuv++; Y3 = *yuv; - yuv = yuv - width + 1; + yuv = (yuv - width) + 1; // Original equations // R = Y + 1.402 V // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb = (unsigned char)B; - rgb = rgb + 3 * width - 5; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb = static_cast(B); + rgb = rgb + ((3 * width) - 5); //--- R = Y2 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y2 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y2 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y3 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y3 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y3 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb = (unsigned char)B; - rgb = rgb - 3 * width + 1; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb = static_cast(B); + rgb = (rgb - (3 * width)) + 1; } yuv += width; rgb += 3 * width; @@ -2368,422 +2602,519 @@ void vpImageConvert::YVU9ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigne int Y0, Y1, Y2, Y3, Y4, Y5, Y6, Y7, Y8, Y9, Y10, Y11, Y12, Y13, Y14, Y15; unsigned int size = width * height; unsigned char *iV = yuv + size; - unsigned char *iU = yuv + 17 * size / 16; - for (unsigned int i = 0; i < height / 4; i++) { - for (unsigned int j = 0; j < width / 4; j++) { - U = (int)((*iU++ - 128) * 0.354); + unsigned char *iU = yuv + ((17 * size) / 16); + const unsigned int quarterHeight = height / 4, quarterWidth = width / 4; + for (unsigned int i = 0; i < quarterHeight; ++i) { + for (unsigned int j = 0; j < quarterWidth; ++j) { + U = static_cast((*iU++ - 128) * 0.354); U5 = 5 * U; - V = (int)((*iV++ - 128) * 0.707); + V = static_cast((*iV++ - 128) * 0.707); V2 = 2 * V; UV = -U - V; Y0 = *yuv++; Y1 = *yuv++; Y2 = *yuv++; Y3 = *yuv; - yuv = yuv + width - 3; + yuv = yuv + (width - 3); Y4 = *yuv++; Y5 = *yuv++; Y6 = *yuv++; Y7 = *yuv; - yuv = yuv + width - 3; + yuv = yuv + (width - 3); Y8 = *yuv++; Y9 = *yuv++; Y10 = *yuv++; Y11 = *yuv; - yuv = yuv + width - 3; + yuv = yuv + (width - 3); Y12 = *yuv++; Y13 = *yuv++; Y14 = *yuv++; Y15 = *yuv; - yuv = yuv - 3 * width + 1; + yuv = (yuv - (3 * width)) + 1; // Original equations // R = Y + 1.402 V // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y2 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y2 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y2 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y3 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y3 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y3 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba = vpRGBa::alpha_default; - rgba = rgba + 4 * width - 15; + rgba = rgba + ((4 * width) - 15); R = Y4 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y4 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y4 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y5 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y5 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y5 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y6 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y6 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y6 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y7 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y7 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y7 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba = vpRGBa::alpha_default; - rgba = rgba + 4 * width - 15; + rgba = rgba + ((4 * width) - 15); R = Y8 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y8 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y8 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y9 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y9 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y9 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y10 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y10 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y10 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y11 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y11 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y11 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba = vpRGBa::alpha_default; - rgba = rgba + 4 * width - 15; + rgba = rgba + ((4 * width) - 15); R = Y12 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y12 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y12 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y13 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y13 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y13 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y14 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y14 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y14 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba++ = vpRGBa::alpha_default; //--- R = Y15 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y15 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y15 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgba++ = (unsigned char)R; - *rgba++ = (unsigned char)G; - *rgba++ = (unsigned char)B; + *rgba++ = static_cast(R); + *rgba++ = static_cast(G); + *rgba++ = static_cast(B); *rgba = vpRGBa::alpha_default; - rgba = rgba - 12 * width + 1; + rgba = (rgba - (12 * width)) + 1; } yuv += 3 * width; rgba += 12 * width; @@ -2804,406 +3135,503 @@ void vpImageConvert::YVU9ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int Y0, Y1, Y2, Y3, Y4, Y5, Y6, Y7, Y8, Y9, Y10, Y11, Y12, Y13, Y14, Y15; unsigned int size = width * height; unsigned char *iV = yuv + size; - unsigned char *iU = yuv + 17 * size / 16; - for (unsigned int i = 0; i < height / 4; i++) { - for (unsigned int j = 0; j < width / 4; j++) { - U = (int)((*iU++ - 128) * 0.354); + unsigned char *iU = yuv + ((17 * size) / 16); + const unsigned int quarterHeight = height / 4, quarterWidth = width / 4; + for (unsigned int i = 0; i < quarterHeight; ++i) { + for (unsigned int j = 0; j < quarterWidth; ++j) { + U = static_cast((*iU++ - 128) * 0.354); U5 = 5 * U; - V = (int)((*iV++ - 128) * 0.707); + V = static_cast((*iV++ - 128) * 0.707); V2 = 2 * V; UV = -U - V; Y0 = *yuv++; Y1 = *yuv++; Y2 = *yuv++; Y3 = *yuv; - yuv = yuv + width - 3; + yuv = yuv + (width - 3); Y4 = *yuv++; Y5 = *yuv++; Y6 = *yuv++; Y7 = *yuv; - yuv = yuv + width - 3; + yuv = yuv + (width - 3); Y8 = *yuv++; Y9 = *yuv++; Y10 = *yuv++; Y11 = *yuv; - yuv = yuv + width - 3; + yuv = yuv + (width - 3); Y12 = *yuv++; Y13 = *yuv++; Y14 = *yuv++; Y15 = *yuv; - yuv = yuv - 3 * width + 1; + yuv = (yuv - (3 * width)) + 1; // Original equations // R = Y + 1.402 V // G = Y - 0.344 U - 0.714 V // B = Y + 1.772 U R = Y0 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y0 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y0 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y1 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y1 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y1 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y2 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y2 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y2 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y3 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y3 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y3 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb = (unsigned char)B; - rgb = rgb + 3 * width - 11; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb = static_cast(B); + rgb = rgb + ((3 * width) - 11); R = Y4 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y4 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y4 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y5 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y5 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y5 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y6 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y6 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y6 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y7 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y7 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y7 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb = (unsigned char)B; - rgb = rgb + 3 * width - 11; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb = static_cast(B); + rgb = rgb + ((3 * width) - 11); R = Y8 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y8 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y8 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y9 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y9 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y9 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y10 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y10 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y10 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y11 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y11 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y11 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb = static_cast(B); rgb = rgb + 3 * width - 11; R = Y12 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y12 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y12 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y13 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y13 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y13 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y14 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y14 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y14 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); //--- R = Y15 + V2; - if ((R >> 8) > 0) + if ((R >> 8) > 0) { R = 255; - else if (R < 0) + } + else if (R < 0) { R = 0; + } G = Y15 + UV; - if ((G >> 8) > 0) + if ((G >> 8) > 0) { G = 255; - else if (G < 0) + } + else if (G < 0) { G = 0; + } B = Y15 + U5; - if ((B >> 8) > 0) + if ((B >> 8) > 0) { B = 255; - else if (B < 0) + } + else if (B < 0) { B = 0; + } - *rgb++ = (unsigned char)R; - *rgb++ = (unsigned char)G; - *rgb++ = (unsigned char)B; - rgb = rgb - 9 * width + 1; + *rgb++ = static_cast(R); + *rgb++ = static_cast(G); + *rgb++ = static_cast(B); + rgb = (rgb - (9 * width)) + 1; } yuv += 3 * width; rgb += 9 * width; @@ -3248,19 +3676,19 @@ void vpImageConvert::RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned } else { #endif -// if we have to flip the image, we start from the end last scanline so the -// step is negative - int lineStep = (flip) ? -(int)(width * 3) : (int)(width * 3); + // if we have to flip the image, we start from the end last scanline so the + // step is negative + int lineStep = flip ? -static_cast(width * 3) : static_cast(width * 3); // starting source address = last line if we need to flip the image - unsigned char *src = (flip) ? (rgb + (width * height * 3) + lineStep) : rgb; + unsigned char *src = flip ? (rgb + (width * height * 3) + lineStep) : rgb; unsigned int j = 0; unsigned int i = 0; - for (i = 0; i < height; i++) { + for (i = 0; i < height; ++i) { unsigned char *line = src; - for (j = 0; j < width; j++) { + for (j = 0; j < width; ++j) { *rgba++ = *(line++); *rgba++ = *(line++); *rgba++ = *(line++); @@ -3292,7 +3720,7 @@ void vpImageConvert::RGBaToRGB(unsigned char *rgba, unsigned char *rgb, unsigned SimdBgraToBgr(rgba, size, 1, size * 4, rgb, size * 3); #else unsigned char *pt_input = rgba; - unsigned char *pt_end = rgba + 4 * size; + unsigned char *pt_end = rgba + (4 * size); unsigned char *pt_output = rgb; while (pt_input != pt_end) { @@ -3345,23 +3773,23 @@ void vpImageConvert::RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned #endif // if we have to flip the image, we start from the end last scanline so // the step is negative - int lineStep = (flip) ? -(int)(width * 3) : (int)(width * 3); + int lineStep = flip ? -static_cast(width * 3) : static_cast(width * 3); // starting source address = last line if we need to flip the image - unsigned char *src = (flip) ? rgb + (width * height * 3) + lineStep : rgb; + unsigned char *src = flip ? (rgb + (width * height * 3) + lineStep) : rgb; unsigned int j = 0; unsigned int i = 0; unsigned r, g, b; - for (i = 0; i < height; i++) { + for (i = 0; i < height; ++i) { unsigned char *line = src; - for (j = 0; j < width; j++) { + for (j = 0; j < width; ++j) { r = *(line++); g = *(line++); b = *(line++); - *grey++ = (unsigned char)(0.2126 * r + 0.7152 * g + 0.0722 * b); + *grey++ = static_cast((0.2126 * r) + (0.7152 * g) + (0.0722 * b)); } // go to the next line @@ -3390,19 +3818,20 @@ void vpImageConvert::RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned void vpImageConvert::RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height, unsigned int #if defined(_OPENMP) - nThreads + nThreads #endif ) { #if defined(VISP_HAVE_SIMDLIB) + const int heightAsInt = static_cast(height); #if defined(_OPENMP) if (nThreads > 0) { omp_set_num_threads(static_cast(nThreads)); } #pragma omp parallel for #endif - for (int i = 0; i < static_cast(height); i++) { - SimdRgbaToGray(rgba + i * width * 4, width, 1, width * 4, grey + i * width, width); + for (int i = 0; i < heightAsInt; ++i) { + SimdRgbaToGray(rgba + (i * width * 4), width, 1, width * 4, grey + (i * width), width); } #else #if defined(_OPENMP) @@ -3432,11 +3861,11 @@ void vpImageConvert::RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsign SimdRgbaToGray(rgba, size, 1, size * 4, grey, size); #else unsigned char *pt_input = rgba; - unsigned char *pt_end = rgba + size * 4; + unsigned char *pt_end = rgba + (size * 4); unsigned char *pt_output = grey; while (pt_input != pt_end) { - *pt_output = (unsigned char)(0.2126 * (*pt_input) + 0.7152 * (*(pt_input + 1)) + 0.0722 * (*(pt_input + 2))); + *pt_output = static_cast((0.2126 * (*pt_input)) + (0.7152 * (*(pt_input + 1))) + (0.0722 * (*(pt_input + 2)))); pt_input += 4; pt_output++; } @@ -3554,14 +3983,14 @@ void vpImageConvert::BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned #endif // if we have to flip the image, we start from the end last scanline so the // step is negative - int lineStep = (flip) ? -(int)(width * 3) : (int)(width * 3); + int lineStep = flip ? -static_cast(width * 3) : static_cast(width * 3); // starting source address = last line if we need to flip the image - unsigned char *src = (flip) ? (bgr + (width * height * 3) + lineStep) : bgr; + unsigned char *src = flip ? (bgr + (width * height * 3) + lineStep) : bgr; - for (unsigned int i = 0; i < height; i++) { + for (unsigned int i = 0; i < height; ++i) { unsigned char *line = src; - for (unsigned int j = 0; j < width; j++) { + for (unsigned int j = 0; j < width; ++j) { *rgba++ = *(line + 2); *rgba++ = *(line + 1); *rgba++ = *(line + 0); @@ -3602,14 +4031,14 @@ void vpImageConvert::BGRaToRGBa(unsigned char *bgra, unsigned char *rgba, unsign #endif // if we have to flip the image, we start from the end last scanline so the // step is negative - int lineStep = (flip) ? -(int)(width * 4) : (int)(width * 4); + int lineStep = flip ? -static_cast(width * 4) : static_cast(width * 4); // starting source address = last line if we need to flip the image - unsigned char *src = (flip) ? (bgra + (width * height * 4) + lineStep) : bgra; + unsigned char *src = flip ? (bgra + (width * height * 4) + lineStep) : bgra; - for (unsigned int i = 0; i < height; i++) { + for (unsigned int i = 0; i < height; ++i) { unsigned char *line = src; - for (unsigned int j = 0; j < width; j++) { + for (unsigned int j = 0; j < width; ++j) { *rgba++ = *(line + 2); *rgba++ = *(line + 1); *rgba++ = *(line + 0); @@ -3643,11 +4072,12 @@ void vpImageConvert::BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned bool flip, unsigned int #if defined(_OPENMP) - nThreads + nThreads #endif ) { #if defined(VISP_HAVE_SIMDLIB) + const int heightAsInt = static_cast(height); if (!flip) { #if defined(_OPENMP) if (nThreads > 0) { @@ -3655,23 +4085,23 @@ void vpImageConvert::BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned } #pragma omp parallel for #endif - for (int i = 0; i < static_cast(height); i++) { - SimdBgrToGray(bgr + i * width * 3, width, 1, width * 3, grey + i * width, width); + for (int i = 0; i < heightAsInt; ++i) { + SimdBgrToGray(bgr + (i * width * 3), width, 1, width * 3, grey + (i * width), width); } } else { #endif // if we have to flip the image, we start from the end last scanline so // the step is negative - int lineStep = (flip) ? -(int)(width * 3) : (int)(width * 3); + int lineStep = flip ? -static_cast(width * 3) : static_cast(width * 3); // starting source address = last line if we need to flip the image - unsigned char *src = (flip) ? bgr + (width * height * 3) + lineStep : bgr; + unsigned char *src = flip ? (bgr + (width * height * 3) + lineStep) : bgr; - for (unsigned int i = 0; i < height; i++) { + for (unsigned int i = 0; i < height; ++i) { unsigned char *line = src; - for (unsigned int j = 0; j < width; j++) { - *grey++ = (unsigned char)(0.2126 * *(line + 2) + 0.7152 * *(line + 1) + 0.0722 * *(line + 0)); + for (unsigned int j = 0; j < width; ++j) { + *grey++ = static_cast((0.2126 * *(line + 2)) + (0.7152 * *(line + 1)) + (0.0722 * *(line + 0))); line += 3; } @@ -3704,35 +4134,36 @@ void vpImageConvert::BGRaToGrey(unsigned char *bgra, unsigned char *grey, unsign bool flip, unsigned int #if defined(_OPENMP) - nThreads + nThreads #endif ) { #if defined(VISP_HAVE_SIMDLIB) if (!flip) { + const int heightAsInt = static_cast(height); #if defined(_OPENMP) if (nThreads > 0) { omp_set_num_threads(static_cast(nThreads)); } #pragma omp parallel for #endif - for (int i = 0; i < static_cast(height); i++) { - SimdBgraToGray(bgra + i * width * 4, width, 1, width * 4, grey + i * width, width); + for (int i = 0; i < heightAsInt; ++i) { + SimdBgraToGray(bgra + (i * width * 4), width, 1, width * 4, grey + (i * width), width); } } else { #endif // if we have to flip the image, we start from the end last scanline so // the step is negative - int lineStep = (flip) ? -(int)(width * 4) : (int)(width * 4); + int lineStep = flip ? -static_cast(width * 4) : static_cast(width * 4); // starting source address = last line if we need to flip the image - unsigned char *src = (flip) ? bgra + (width * height * 4) + lineStep : bgra; + unsigned char *src = flip ? (bgra + (width * height * 4) + lineStep) : bgra; - for (unsigned int i = 0; i < height; i++) { + for (unsigned int i = 0; i < height; ++i) { unsigned char *line = src; - for (unsigned int j = 0; j < width; j++) { - *grey++ = (unsigned char)(0.2126 * *(line + 2) + 0.7152 * *(line + 1) + 0.0722 * *(line + 0)); + for (unsigned int j = 0; j < width; ++j) { + *grey++ = static_cast((0.2126 * *(line + 2)) + (0.7152 * *(line + 1)) + (0.0722 * *(line + 0))); line += 4; } @@ -3758,10 +4189,10 @@ void vpImageConvert::computeYCbCrLUT() while (index--) { int aux = index - 128; - vpImageConvert::vpCrr[index] = (int)(364.6610 * aux) >> 8; - vpImageConvert::vpCgb[index] = (int)(-89.8779 * aux) >> 8; - vpImageConvert::vpCgr[index] = (int)(-185.8154 * aux) >> 8; - vpImageConvert::vpCbb[index] = (int)(460.5724 * aux) >> 8; + vpImageConvert::vpCrr[index] = static_cast(364.6610 * aux) >> 8; + vpImageConvert::vpCgb[index] = static_cast(-89.8779 * aux) >> 8; + vpImageConvert::vpCgr[index] = static_cast(-185.8154 * aux) >> 8; + vpImageConvert::vpCbb[index] = static_cast(460.5724 * aux) >> 8; } YCbCrLUTcomputed = true; @@ -3905,8 +4336,8 @@ void vpImageConvert::YCbCrToRGBa(unsigned char *ycbcr, unsigned char *rgba, unsi void vpImageConvert::YCbCrToGrey(unsigned char *ycbcr, unsigned char *grey, unsigned int size) { unsigned int i = 0, j = 0; - - while (j < size * 2) { + const unsigned int doubleSize = size * 2; + while (j < doubleSize) { grey[i++] = ycbcr[j]; grey[i++] = ycbcr[j + 2]; j += 4; @@ -4093,16 +4524,16 @@ void vpImageConvert::split(const vpImage &src, vpImage *p src.getWidth()); if (!pR) { - delete[] ptrR; + delete [] ptrR; } if (!pG) { - delete[] ptrG; + delete [] ptrG; } if (!pB) { - delete[] ptrB; + delete [] ptrB; } if (!pa) { - delete[] ptrA; + delete [] ptrA; } } #else @@ -4126,9 +4557,9 @@ void vpImageConvert::split(const vpImage &src, vpImage *p tabChannel[3] = pa; size_t i; /* ordre */ - for (unsigned int j = 0; j < 4; j++) { - if (tabChannel[j] != NULL) { - if (tabChannel[j]->getHeight() != height || tabChannel[j]->getWidth() != width) { + for (unsigned int j = 0; j < 4; ++j) { + if (tabChannel[j] != nullptr) { + if ((tabChannel[j]->getHeight() != height) || (tabChannel[j]->getWidth() != width)) { tabChannel[j]->resize(height, width); } dst = (unsigned char *)tabChannel[j]->bitmap; @@ -4155,7 +4586,7 @@ void vpImageConvert::split(const vpImage &src, vpImage *p n += 3; } - for (; i < n; i++) { + for (; i < n; ++i) { *dst = *input; input += 4; dst++; @@ -4200,7 +4631,7 @@ void vpImageConvert::merge(const vpImage *R, const vpImagegetHeight()]++; } - if (mapOfWidths.size() == 1 && mapOfHeights.size() == 1) { + if ((mapOfWidths.size() == 1) && (mapOfHeights.size() == 1)) { unsigned int width = mapOfWidths.begin()->first; unsigned int height = mapOfHeights.begin()->first; @@ -4208,14 +4639,14 @@ void vpImageConvert::merge(const vpImage *R, const vpImagebitmap, width, G->bitmap, width, B->bitmap, width, a->bitmap, width, width, height, reinterpret_cast(RGBa.bitmap), width * sizeof(vpRGBa)); } else { #endif unsigned int size = width * height; - for (unsigned int i = 0; i < size; i++) { + for (unsigned int i = 0; i < size; ++i) { if (R != nullptr) { RGBa.bitmap[i].R = R->bitmap[i]; } @@ -4276,7 +4707,7 @@ void vpImageConvert::MONO16ToGrey(unsigned char *grey16, unsigned char *grey, un void vpImageConvert::MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, unsigned int size) { int i = (((int)size) << 1) - 1; - int j = (int)(size * 4 - 1); + int j = static_cast(size * 4 - 1); while (i >= 0) { int y = grey16[i--]; @@ -4301,7 +4732,7 @@ void vpImageConvert::MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, un void vpImageConvert::HSV2RGB(const double *hue_, const double *saturation_, const double *value_, unsigned char *rgb, unsigned int size, unsigned int step) { - for (unsigned int i = 0; i < size; i++) { + for (unsigned int i = 0; i < size; ++i) { double hue = hue_[i], saturation = saturation_[i], value = value_[i]; if (vpMath::equal(saturation, 0.0, std::numeric_limits::epsilon())) { @@ -4317,12 +4748,12 @@ void vpImageConvert::HSV2RGB(const double *hue_, const double *saturation_, cons h = 0.0; } - double f = h - (int)h; + double f = h - static_cast(h); double p = v * (1.0 - s); - double q = v * (1.0 - s * f); - double t = v * (1.0 - s * (1.0 - f)); + double q = v * (1.0 - (s * f)); + double t = v * (1.0 - (s * (1.0 - f))); - switch ((int)h) { + switch (static_cast(h)) { case 0: hue = v; saturation = t; @@ -4361,11 +4792,12 @@ void vpImageConvert::HSV2RGB(const double *hue_, const double *saturation_, cons } } - rgb[i * step] = (unsigned char)vpMath::round(hue * 255.0); - rgb[i * step + 1] = (unsigned char)vpMath::round(saturation * 255.0); - rgb[i * step + 2] = (unsigned char)vpMath::round(value * 255.0); - if (step == 4) // alpha + rgb[i * step] = static_cast(vpMath::round(hue * 255.0)); + rgb[i * step + 1] = static_cast(vpMath::round(saturation * 255.0)); + rgb[i * step + 2] = static_cast(vpMath::round(value * 255.0)); + if (step == 4) {// alpha rgb[i * step + 3] = vpRGBa::alpha_default; + } } } @@ -4382,7 +4814,7 @@ void vpImageConvert::HSV2RGB(const double *hue_, const double *saturation_, cons void vpImageConvert::RGB2HSV(const unsigned char *rgb, double *hue, double *saturation, double *value, unsigned int size, unsigned int step) { - for (unsigned int i = 0; i < size; i++) { + for (unsigned int i = 0; i < size; ++i) { double red, green, blue; double h, s, v; double min, max; @@ -4392,12 +4824,12 @@ void vpImageConvert::RGB2HSV(const unsigned char *rgb, double *hue, double *satu blue = rgb[i * step + 2] / 255.0; if (red > green) { - max = std::max(red, blue); - min = std::min(green, blue); + max = ((std::max))(red, blue); + min = ((std::min))(green, blue); } else { - max = std::max(green, blue); - min = std::min(red, blue); + max = ((std::max))(green, blue); + min = ((std::min))(red, blue); } v = max; @@ -4476,10 +4908,10 @@ void vpImageConvert::HSVToRGBa(const double *hue, const double *saturation, cons void vpImageConvert::HSVToRGBa(const unsigned char *hue, const unsigned char *saturation, const unsigned char *value, unsigned char *rgba, unsigned int size) { - for (unsigned int i = 0; i < size; i++) { + for (unsigned int i = 0; i < size; ++i) { double h = hue[i] / 255.0, s = saturation[i] / 255.0, v = value[i] / 255.0; - vpImageConvert::HSVToRGBa(&h, &s, &v, (rgba + i * 4), 1); + vpImageConvert::HSVToRGBa(&h, &s, &v, (rgba + (i * 4)), 1); } } @@ -4515,13 +4947,13 @@ void vpImageConvert::RGBaToHSV(const unsigned char *rgba, double *hue, double *s void vpImageConvert::RGBaToHSV(const unsigned char *rgba, unsigned char *hue, unsigned char *saturation, unsigned char *value, unsigned int size) { - for (unsigned int i = 0; i < size; i++) { + for (unsigned int i = 0; i < size; ++i) { double h, s, v; - vpImageConvert::RGBaToHSV((rgba + i * 4), &h, &s, &v, 1); + vpImageConvert::RGBaToHSV((rgba + (i * 4)), &h, &s, &v, 1); - hue[i] = (unsigned char)(255.0 * h); - saturation[i] = (unsigned char)(255.0 * s); - value[i] = (unsigned char)(255.0 * v); + hue[i] = static_cast(255.0 * h); + saturation[i] = static_cast(255.0 * s); + value[i] = static_cast(255.0 * v); } } @@ -4547,17 +4979,16 @@ void vpImageConvert::HSVToRGB(const double *hue, const double *saturation, const \param[in] hue : Array of hue values (range between [0 - 255]). \param[in] saturation : Array of saturation values (range between [0 - 255]). \param[in] value : Array of value values (range between [0 - 255]). - \param[out] rgb : Pointer to the 24-bit RGB image that should be allocated with a size of - width * height * 3. + \param[out] rgb : Pointer to the 24-bit RGB image that should be allocated with a size of width * height * 3. \param[in] size : The image size or the number of pixels corresponding to the image width * height. */ void vpImageConvert::HSVToRGB(const unsigned char *hue, const unsigned char *saturation, const unsigned char *value, unsigned char *rgb, unsigned int size) { - for (unsigned int i = 0; i < size; i++) { + for (unsigned int i = 0; i < size; ++i) { double h = hue[i] / 255.0, s = saturation[i] / 255.0, v = value[i] / 255.0; - vpImageConvert::HSVToRGB(&h, &s, &v, (rgb + i * 3), 1); + vpImageConvert::HSVToRGB(&h, &s, &v, (rgb + (i * 3)), 1); } } @@ -4565,11 +4996,9 @@ void vpImageConvert::HSVToRGB(const unsigned char *hue, const unsigned char *sat Converts an array of RGB to an array of hue, saturation, value values. \param[in] rgb : Pointer to the 24-bits RGB bitmap. - \param[out] hue : Array of hue values converted from RGB color space (range - between [0 - 1]). - \param[out] saturation : Array of saturation values converted - from RGB color space (range between [0 - 1]). - \param[out] value : Array of value values converted from RGB color space (range between [0 - 1]). + \param[out] hue : Array of hue values converted from RGB color space (range between [0 - 255]). + \param[out] saturation : Array of saturation values converted from RGB color space (range between [0 - 255]). + \param[out] value : Array of value values converted from RGB color space (range between [0 - 255]). \param[in] size : The image size or the number of pixels corresponding to the image width * height. */ void vpImageConvert::RGBToHSV(const unsigned char *rgb, double *hue, double *saturation, double *value, @@ -4584,21 +5013,20 @@ void vpImageConvert::RGBToHSV(const unsigned char *rgb, double *hue, double *sat \param[in] rgb : Pointer to the 24-bits RGB bitmap. \param[out] hue : Array of hue values converted from RGB color space (range between [0 - 255]). \param[out] saturation : Array of saturation values converted from RGB color space (range between [0 - 255]). - \param[out] value : Array of value values converted - from RGB color space (range between [0 - 255]). + \param[out] value : Array of value values converted from RGB color space (range between [0 - 255]). \param[in] size : The image size or the number of pixels corresponding to the image width * height. */ void vpImageConvert::RGBToHSV(const unsigned char *rgb, unsigned char *hue, unsigned char *saturation, unsigned char *value, unsigned int size) { - for (unsigned int i = 0; i < size; i++) { + for (unsigned int i = 0; i < size; ++i) { double h, s, v; - vpImageConvert::RGBToHSV((rgb + i * 3), &h, &s, &v, 1); + vpImageConvert::RGBToHSV((rgb + (i * 3)), &h, &s, &v, 1); - hue[i] = (unsigned char)(255.0 * h); - saturation[i] = (unsigned char)(255.0 * s); - value[i] = (unsigned char)(255.0 * v); + hue[i] = static_cast(255.0 * h); + saturation[i] = static_cast(255.0 * s); + value[i] = static_cast(255.0 * v); } } diff --git a/modules/core/src/image/vpRGBa.cpp b/modules/core/src/image/vpRGBa.cpp index 61660abc70..69147272c4 100644 --- a/modules/core/src/image/vpRGBa.cpp +++ b/modules/core/src/image/vpRGBa.cpp @@ -70,6 +70,7 @@ vpRGBa &vpRGBa::operator=(const vpRGBa &v) return *this; } +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Move operator. */ @@ -81,6 +82,7 @@ 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 5510bece32..5663ced711 100644 --- a/modules/core/src/image/vpRGBf.cpp +++ b/modules/core/src/image/vpRGBf.cpp @@ -69,6 +69,7 @@ vpRGBf &vpRGBf::operator=(const vpRGBf &v) return *this; } +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Move operator. */ @@ -79,6 +80,7 @@ vpRGBf &vpRGBf::operator=(const vpRGBf &&v) this->B = std::move(v.B); return *this; } +#endif /*! Cast a vpColVector in a vpRGBf diff --git a/modules/core/src/math/matrix/vpColVector.cpp b/modules/core/src/math/matrix/vpColVector.cpp index 0925573260..fc79ee2686 100644 --- a/modules/core/src/math/matrix/vpColVector.cpp +++ b/modules/core/src/math/matrix/vpColVector.cpp @@ -163,10 +163,12 @@ void vpColVector::init(const vpColVector &v, unsigned int r, unsigned int nrows) v.getRows())); resize(nrows, false); - if (this->rowPtrs == nullptr) // Fix coverity scan: explicit null dereferenced - return; // Nothing to do - for (unsigned int i = r; i < rnrows; i++) + if (this->rowPtrs == nullptr) { // Fix coverity scan: explicit null dereferenced + return; // Nothing to do + } + for (unsigned int i = r; i < rnrows; i++) { (*this)[i - r] = v[i]; + } } vpColVector::vpColVector(const vpRotationVector &v) : vpArray2D(v.size(), 1) @@ -216,6 +218,7 @@ 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; @@ -230,6 +233,7 @@ vpColVector::vpColVector(vpColVector &&v) : vpArray2D() v.dsize = 0; v.data = nullptr; } +#endif vpColVector vpColVector::operator-() const { @@ -404,6 +408,7 @@ std::vector vpColVector::toStdVector() const return v; } +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpColVector &vpColVector::operator=(vpColVector &&other) { if (this != &other) { @@ -432,6 +437,7 @@ 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 130e604556..74a8f69791 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -199,6 +199,7 @@ 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; @@ -215,77 +216,78 @@ vpMatrix::vpMatrix(vpMatrix &&A) : vpArray2D() } /*! - Construct a matrix from a list of double values. - \param list : List of double. + Construct a matrix from a list of double values. + \param list : List of double. - The following code shows how to use this constructor to initialize a 2-by-3 matrix using reshape() function: + The following code shows how to use this constructor to initialize a 2-by-3 matrix using reshape() function: - \code -#include + \code + #include -int main() -{ -vpMatrix M( {-1, -2, -3, 4, 5.5, 6.0f} ); -M.reshape(2, 3); -std::cout << "M:\n" << M << std::endl; -} - \endcode - It produces the following output: - \code -M: --1 -2 -3 -4 5.5 6 - \endcode - */ + int main() + { + vpMatrix M( {-1, -2, -3, 4, 5.5, 6.0f} ); + M.reshape(2, 3); + std::cout << "M:\n" << M << std::endl; + } + \endcode + It produces the following output: + \code + M: + -1 -2 -3 + 4 5.5 6 + \endcode +*/ vpMatrix::vpMatrix(const std::initializer_list &list) : vpArray2D(list) { } /*! - Construct a matrix from a list of double values. - \param ncols, nrows : Matrix size. - \param list : List of double. + Construct a matrix from a list of double values. + \param ncols, nrows : Matrix size. + \param list : List of double. - The following code shows how to use this constructor to initialize a 2-by-3 matrix: - \code -#include + The following code shows how to use this constructor to initialize a 2-by-3 matrix: + \code + #include -int main() -{ -vpMatrix M(2, 3, {-1, -2, -3, 4, 5.5, 6}); -std::cout << "M:\n" << M << std::endl; -} - \endcode - It produces the following output: - \code -M: --1 -2 -3 -4 5.5 6 - \endcode + int main() + { + vpMatrix M(2, 3, {-1, -2, -3, 4, 5.5, 6}); + std::cout << "M:\n" << M << std::endl; + } + \endcode + It produces the following output: + \code + M: + -1 -2 -3 + 4 5.5 6 + \endcode */ vpMatrix::vpMatrix(unsigned int nrows, unsigned int ncols, const std::initializer_list &list) : vpArray2D(nrows, ncols, list) { } /*! - Construct a matrix from a list of double values. - \param lists : List of double. - The following code shows how to use this constructor to initialize a 2-by-3 matrix function: - \code -#include + Construct a matrix from a list of double values. + \param lists : List of double. + The following code shows how to use this constructor to initialize a 2-by-3 matrix function: + \code + #include -int main() -{ -vpMatrix M( { {-1, -2, -3}, {4, 5.5, 6} } ); -std::cout << "M:\n" << M << std::endl; -} - \endcode - It produces the following output: - \code -M: --1 -2 -3 -4 5.5 6 - \endcode + int main() + { + vpMatrix M( { {-1, -2, -3}, {4, 5.5, 6} } ); + std::cout << "M:\n" << M << std::endl; + } + \endcode + It produces the following output: + \code + M: + -1 -2 -3 + 4 5.5 6 + \endcode */ vpMatrix::vpMatrix(const std::initializer_list > &lists) : vpArray2D(lists) { } +#endif /*! Initialize the matrix from a part of an input matrix \e M. @@ -297,38 +299,38 @@ vpMatrix::vpMatrix(const std::initializer_list > & \param ncols : Number of columns of the matrix that should be initialized. The sub-matrix starting from M[r][c] element and ending on -M[r+nrows-1][c+ncols-1] element is used to initialize the matrix. + M[r+nrows-1][c+ncols-1] element is used to initialize the matrix. The following code shows how to use this function: -\code -#include - -int main() -{ - vpMatrix M(4,5); - int val = 0; - for(size_t i=0; i + + int main() + { + vpMatrix M(4,5); + int val = 0; + for(size_t i=0; irowPtrs == nullptr) // Fix coverity scan: explicit null dereferenced + if (this->rowPtrs == nullptr) { // Fix coverity scan: explicit null dereferenced return; // Noting to do + } for (unsigned int i = 0; i < nrows; i++) { memcpy((*this)[i], &M[i + r][c], ncols * sizeof(double)); } @@ -363,32 +366,32 @@ void vpMatrix::init(const vpMatrix &M, unsigned int r, unsigned int c, unsigned The following code shows how to use this function: \code -#include - -int main() -{ - vpMatrix M(4,5); - int val = 0; - for(size_t i=0; i + + int main() + { + vpMatrix M(4,5); + int val = 0; + for(size_t i=0; i &A) @@ -674,6 +677,7 @@ vpMatrix &vpMatrix::operator=(const vpMatrix &A) return *this; } +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix &vpMatrix::operator=(vpMatrix &&other) { if (this != &other) { @@ -699,22 +703,26 @@ vpMatrix &vpMatrix::operator=(vpMatrix &&other) /*! Set matrix elements from a list of values. \param list : List of double. Matrix size (number of columns multiplied by number of columns) should match the number -of elements. \return The modified Matrix. The following example shows how to set each element of a 2-by-3 matrix. \code -#include + of elements. -int main() -{ - vpMatrix M; - M = { -1, -2, -3, -4, -5, -6 }; - M.reshape(2, 3); - std::cout << "M:\n" << M << std::endl; -} + \return The modified Matrix. The following example shows how to set each element of a 2-by-3 matrix. + + \code + #include + + int main() + { + vpMatrix M; + M = { -1, -2, -3, -4, -5, -6 }; + M.reshape(2, 3); + std::cout << "M:\n" << M << std::endl; + } \endcode It produces the following printings: \code -M: --1 -2 -3 --4 -5 -6 + M: + -1 -2 -3 + -4 -5 -6 \endcode \sa operator<<() */ @@ -735,20 +743,20 @@ vpMatrix &vpMatrix::operator=(const std::initializer_list &list) \return The modified Matrix. The following example shows how to set each element of a 2-by-3 matrix. \code -#include + #include -int main() -{ - vpMatrix M; - M = { {-1, -2, -3}, {-4, -5, -6} }; - std::cout << "M:\n" << M << std::endl; -} + int main() + { + vpMatrix M; + M = { {-1, -2, -3}, {-4, -5, -6} }; + std::cout << "M:\n" << M << std::endl; + } \endcode It produces the following printings: \code -M: --1 -2 -3 --4 -5 -6 + M: + -1 -2 -3 + -4 -5 -6 \endcode \sa operator<<() */ @@ -769,6 +777,7 @@ vpMatrix &vpMatrix::operator=(const std::initializer_list + \code + #include -#include -#include + #include + #include -int main() -{ - vpMatrix A; - vpColVector v(3); + int main() + { + vpMatrix A; + vpColVector v(3); - v[0] = 1; - v[1] = 2; - v[2] = 3; + v[0] = 1; + v[1] = 2; + v[2] = 3; - A.diag(v); + A.diag(v); - std::cout << "A:\n" << A << std::endl; -} -\endcode + std::cout << "A:\n" << A << std::endl; + } + \endcode Matrix A is now equal to: -\code -1 0 0 -0 2 0 -0 0 3 -\endcode + \code + 1 0 0 + 0 2 0 + 0 0 3 + \endcode */ void vpMatrix::diag(const vpColVector &A) { @@ -859,27 +868,27 @@ set to \e val. Elements that are not on the diagonal are set to 0. \sa eye() -\code -#include + \code + #include -#include + #include -int main() -{ - vpMatrix A(3, 4); + int main() + { + vpMatrix A(3, 4); - A.diag(2); + A.diag(2); - std::cout << "A:\n" << A << std::endl; -} -\endcode + std::cout << "A:\n" << A << std::endl; + } + \endcode Matrix A is now equal to: -\code -2 0 0 0 -0 2 0 0 -0 0 2 0 -\endcode + \code + 2 0 0 0 + 0 2 0 0 + 0 0 2 0 + \endcode */ void vpMatrix::diag(const double &val) { @@ -897,7 +906,7 @@ void vpMatrix::diag(const double &val) \param DA : Diagonal matrix DA[i][i] = A[i] -\sa diag() + \sa diag() */ void vpMatrix::createDiagonalMatrix(const vpColVector &A, vpMatrix &DA) @@ -912,7 +921,7 @@ void vpMatrix::createDiagonalMatrix(const vpColVector &A, vpMatrix &DA) /*! Operator that allows to multiply a matrix by a translation vector. The matrix should be of dimension (3x3) - */ +*/ vpTranslationVector vpMatrix::operator*(const vpTranslationVector &tv) const { vpTranslationVector t_out; @@ -1342,13 +1351,13 @@ vpMatrix vpMatrix::operator*(const vpForceTwistMatrix &V) const } /*! -Operation C = A*wA + B*wB + Operation C = A*wA + B*wB -The result is placed in the third parameter C and not returned. -A new matrix won't be allocated for every use of the function -(Speed gain if used many times with the same result matrix size). + The result is placed in the third parameter C and not returned. + A new matrix won't be allocated for every use of the function + (Speed gain if used many times with the same result matrix size). -\sa operator+() + \sa operator+() */ void vpMatrix::add2WeightedMatrices(const vpMatrix &A, const double &wA, const vpMatrix &B, const double &wB, @@ -1903,43 +1912,43 @@ vpMatrix vpMatrix::kron(const vpMatrix &m) const { return kron(*this, m); } \param x : Vector \f$ X \f$. Here an example: -\code -#include -#include + \code + #include + #include -int main() -{ -vpMatrix A(3,3); + int main() + { + vpMatrix A(3,3); -A[0][0] = 4.64; -A[0][1] = 0.288; -A[0][2] = -0.384; + A[0][0] = 4.64; + A[0][1] = 0.288; + A[0][2] = -0.384; -A[1][0] = 0.288; -A[1][1] = 7.3296; -A[1][2] = 2.2272; + A[1][0] = 0.288; + A[1][1] = 7.3296; + A[1][2] = 2.2272; -A[2][0] = -0.384; -A[2][1] = 2.2272; -A[2][2] = 6.0304; + A[2][0] = -0.384; + A[2][1] = 2.2272; + A[2][2] = 6.0304; -vpColVector X(3), B(3); -B[0] = 1; -B[1] = 2; -B[2] = 3; + vpColVector X(3), B(3); + B[0] = 1; + B[1] = 2; + B[2] = 3; -A.solveBySVD(B, X); + A.solveBySVD(B, X); -// Obtained values of X -// X[0] = 0.2468; -// X[1] = 0.120782; -// X[2] = 0.468587; + // Obtained values of X + // X[0] = 0.2468; + // X[1] = 0.120782; + // X[2] = 0.468587; -std::cout << "X:\n" << X << std::endl; -} -\endcode + std::cout << "X:\n" << X << std::endl; + } + \endcode -\sa solveBySVD(const vpColVector &) + \sa solveBySVD(const vpColVector &) */ void vpMatrix::solveBySVD(const vpColVector &b, vpColVector &x) const { x = pseudoInverse(1e-6) * b; } @@ -1955,42 +1964,42 @@ void vpMatrix::solveBySVD(const vpColVector &b, vpColVector &x) const { x = pseu \return Vector \f$ X \f$. Here an example: -\code -#include -#include + \code + #include + #include -int main() -{ -vpMatrix A(3,3); + int main() + { + vpMatrix A(3,3); -A[0][0] = 4.64; -A[0][1] = 0.288; -A[0][2] = -0.384; + A[0][0] = 4.64; + A[0][1] = 0.288; + A[0][2] = -0.384; -A[1][0] = 0.288; -A[1][1] = 7.3296; -A[1][2] = 2.2272; + A[1][0] = 0.288; + A[1][1] = 7.3296; + A[1][2] = 2.2272; -A[2][0] = -0.384; -A[2][1] = 2.2272; -A[2][2] = 6.0304; + A[2][0] = -0.384; + A[2][1] = 2.2272; + A[2][2] = 6.0304; -vpColVector X(3), B(3); -B[0] = 1; -B[1] = 2; -B[2] = 3; + vpColVector X(3), B(3); + B[0] = 1; + B[1] = 2; + B[2] = 3; -X = A.solveBySVD(B); -// Obtained values of X -// X[0] = 0.2468; -// X[1] = 0.120782; -// X[2] = 0.468587; + X = A.solveBySVD(B); + // Obtained values of X + // X[0] = 0.2468; + // X[1] = 0.120782; + // X[2] = 0.468587; -std::cout << "X:\n" << X << std::endl; -} -\endcode + std::cout << "X:\n" << X << std::endl; + } + \endcode -\sa solveBySVD(const vpColVector &, vpColVector &) + \sa solveBySVD(const vpColVector &, vpColVector &) */ vpColVector vpMatrix::solveBySVD(const vpColVector &B) const { @@ -2031,34 +2040,34 @@ vpColVector vpMatrix::solveBySVD(const vpColVector &B) const Here an example of SVD decomposition of a non square Matrix M. -\code -#include + \code + #include -int main() -{ - vpMatrix M(3,2); - M[0][0] = 1; M[0][1] = 6; - M[1][0] = 2; M[1][1] = 8; - M[2][0] = 0.5; M[2][1] = 9; + int main() + { + vpMatrix M(3,2); + M[0][0] = 1; M[0][1] = 6; + M[1][0] = 2; M[1][1] = 8; + M[2][0] = 0.5; M[2][1] = 9; - vpColVector w; - vpMatrix V, Sigma, U = M; + vpColVector w; + vpMatrix V, Sigma, U = M; - U.svd(w, V); + U.svd(w, V); - // Construct the diagonal matrix from the singular values - Sigma.diag(w); + // Construct the diagonal matrix from the singular values + Sigma.diag(w); - // Reconstruct the initial matrix using the decomposition - vpMatrix Mrec = U * Sigma * V.t(); + // Reconstruct the initial matrix using the decomposition + vpMatrix Mrec = U * Sigma * V.t(); - // Here, Mrec is obtained equal to the initial value of M - // Mrec[0][0] = 1; Mrec[0][1] = 6; - // Mrec[1][0] = 2; Mrec[1][1] = 8; - // Mrec[2][0] = 0.5; Mrec[2][1] = 9; + // Here, Mrec is obtained equal to the initial value of M + // Mrec[0][0] = 1; Mrec[0][1] = 6; + // Mrec[1][0] = 2; Mrec[1][1] = 8; + // Mrec[2][0] = 0.5; Mrec[2][1] = 9; - std::cout << "Reconstructed M matrix: \n" << Mrec << std::endl; -} + std::cout << "Reconstructed M matrix: \n" << Mrec << std::endl; + } \endcode \sa svdLapack(), svdEigen3(), svdOpenCV() @@ -2101,35 +2110,35 @@ void vpMatrix::svd(vpColVector &w, vpMatrix &V) Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - unsigned int rank = A.pseudoInverse(A_p); + vpMatrix A_p; + unsigned int rank = A.pseudoInverse(A_p); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank: " << rank << std::endl; + } \endcode Once build, the previous example produces the following output: \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 -Rank: 2 + A: [2,3]= + 2 3 5 + -4 2 3 + A^+ (pseudo-inverse): [3,2]= + 0.117899 -0.190782 + 0.065380 0.039657 + 0.113612 0.052518 + Rank: 2 \endcode */ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, double svThreshold) const @@ -2169,43 +2178,43 @@ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, double svThreshold) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - int rank_in = 2; - int rank_out = A.pseudoInverse(A_p, rank_in); - 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; - } + vpMatrix A_p; + int rank_in = 2; + int rank_out = A.pseudoInverse(A_p, rank_in); + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + } \endcode Once build, the previous example produces the following output: \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 -Rank in : 2 -Rank out: 2 + A: [2,3]= + 2 3 5 + -4 2 3 + A^+ (pseudo-inverse): [3,2]= + 0.117899 -0.190782 + 0.065380 0.039657 + 0.113612 0.052518 + Rank in : 2 + Rank out: 2 \endcode */ int vpMatrix::pseudoInverse(vpMatrix &Ap, int rank_in) const @@ -2245,32 +2254,32 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, int rank_in) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p = A.pseudoInverse(); + vpMatrix A_p = A.pseudoInverse(); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + } \endcode Once build, the previous example produces the following output: \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 + A: [2,3]= + 2 3 5 + -4 2 3 + A^+ (pseudo-inverse): [3,2]= + 0.117899 -0.190782 + 0.065380 0.039657 + 0.113612 0.052518 \endcode */ @@ -2308,34 +2317,34 @@ vpMatrix vpMatrix::pseudoInverse(double svThreshold) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - int rank_in = 2; - vpMatrix A_p = A.pseudoInverseLapack(rank_in); + int rank_in = 2; + vpMatrix A_p = A.pseudoInverseLapack(rank_in); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + } \endcode Once build, the previous example produces the following output: \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 + A: [2,3]= + 2 3 5 + -4 2 3 + A^+ (pseudo-inverse): [3,2]= + 0.117899 -0.190782 + 0.065380 0.039657 + 0.113612 0.052518 \endcode */ @@ -2373,21 +2382,21 @@ vpMatrix vpMatrix::pseudoInverse(int rank_in) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p = A.pseudoInverseLapack(); + vpMatrix A_p = A.pseudoInverseLapack(); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + } \endcode \sa pseudoInverse(double) const @@ -2439,23 +2448,23 @@ vpMatrix vpMatrix::pseudoInverseLapack(double svThreshold) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - unsigned int rank = A.pseudoInverseLapack(A_p); + vpMatrix A_p; + unsigned int rank = A.pseudoInverseLapack(A_p); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank: " << rank << std::endl; + } \endcode \sa pseudoInverse(vpMatrix &, double) const @@ -2510,26 +2519,26 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, double svThreshold) con Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - unsigned int rank = A.pseudoInverseLapack(A_p, sv); + vpMatrix A_p; + vpColVector sv; + unsigned int rank = A.pseudoInverseLapack(A_p, sv); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; -} + std::cout << "Rank: " << rank << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, double) const @@ -2631,43 +2640,43 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpColVector sv; - vpMatrix A_p, imA, imAt, kerAt; - unsigned int rank = A.pseudoInverseLapack(A_p, sv, 1e-6, imA, imAt, kerAt); + vpColVector sv; + vpMatrix A_p, imA, imAt, kerAt; + unsigned int rank = A.pseudoInverseLapack(A_p, sv, 1e-6, imA, imAt, kerAt); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank: " << rank << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); - if (kerAt.size()) { - kerAt.t().print(std::cout, 10, "Ker(A): "); - } - else { - std::cout << "Ker(A) empty " << std::endl; - } + if (kerAt.size()) { + kerAt.t().print(std::cout, 10, "Ker(A): "); + } + else { + std::cout << "Ker(A) empty " << std::endl; + } - // Reconstruct matrix A from ImA, ImAt, KerAt - vpMatrix S(rank, A.getCols()); - for(unsigned int i = 0; i< rank; i++) - S[i][i] = sv[i]; - vpMatrix Vt(A.getCols(), A.getCols()); - Vt.insert(imAt.t(), 0, 0); - Vt.insert(kerAt, rank, 0); - (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); -} + // Reconstruct matrix A from ImA, ImAt, KerAt + vpMatrix S(rank, A.getCols()); + for(unsigned int i = 0; i< rank; i++) + S[i][i] = sv[i]; + vpMatrix Vt(A.getCols(), A.getCols()); + Vt.insert(imAt.t(), 0, 0); + Vt.insert(kerAt, rank, 0); + (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, double, vpMatrix &, vpMatrix &, vpMatrix &) const @@ -2716,24 +2725,24 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - int rank_in = 2; - vpMatrix A_p = A.pseudoInverseLapack(rank_in); + int rank_in = 2; + vpMatrix A_p = A.pseudoInverseLapack(rank_in); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - return 0; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + return 0; + } \endcode \sa pseudoInverse(int) const @@ -2784,31 +2793,31 @@ vpMatrix vpMatrix::pseudoInverseLapack(int rank_in) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - int rank_in = 2; - int rank_out = A.pseudoInverseLapack(A_p, rank_in); - 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; - } + vpMatrix A_p; + int rank_in = 2; + int rank_out = A.pseudoInverseLapack(A_p, rank_in); + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - return 0; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + return 0; + } \endcode \sa pseudoInverse(vpMatrix &, int) const @@ -2863,34 +2872,34 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, int rank_in) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - int rank_in = 2; + vpMatrix A_p; + vpColVector sv; + int rank_in = 2; - int rank_out = A.pseudoInverseLapack(A_p, sv, rank_in); - 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; - } + int rank_out = A.pseudoInverseLapack(A_p, sv, rank_in); + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - return 0; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + return 0; + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, int) const @@ -2991,50 +3000,50 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in) co Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpColVector sv; - vpMatrix A_p, imA, imAt, kerAt; - int rank_in = 2; - int rank_out = A.pseudoInverseLapack(A_p, sv, rank_in, imA, imAt, kerAt); + vpColVector sv; + vpMatrix A_p, imA, imAt, kerAt; + int rank_in = 2; + int rank_out = A.pseudoInverseLapack(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; - } + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); - if (kerAt.size()) { - kerAt.t().print(std::cout, 10, "Ker(A): "); - } - else { - std::cout << "Ker(A) empty " << std::endl; - } + if (kerAt.size()) { + kerAt.t().print(std::cout, 10, "Ker(A): "); + } + else { + std::cout << "Ker(A) empty " << std::endl; + } - // Reconstruct matrix A from ImA, ImAt, KerAt - vpMatrix S(rank_in, A.getCols()); - for(unsigned int i = 0; i< rank_in; i++) - S[i][i] = sv[i]; - vpMatrix Vt(A.getCols(), A.getCols()); - Vt.insert(imAt.t(), 0, 0); - Vt.insert(kerAt, rank_in, 0); - (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); -} + // Reconstruct matrix A from ImA, ImAt, KerAt + vpMatrix S(rank_in, A.getCols()); + for(unsigned int i = 0; i< rank_in; i++) + S[i][i] = sv[i]; + vpMatrix Vt(A.getCols(), A.getCols()); + Vt.insert(imAt.t(), 0, 0); + Vt.insert(kerAt, rank_in, 0); + (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, int, vpMatrix &, vpMatrix &, vpMatrix &) const @@ -3089,21 +3098,21 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in, vp Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p = A.pseudoInverseEigen3(); + vpMatrix A_p = A.pseudoInverseEigen3(); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + } \endcode \sa pseudoInverse(double) @@ -3155,23 +3164,23 @@ vpMatrix vpMatrix::pseudoInverseEigen3(double svThreshold) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - unsigned int rank = A.pseudoInverseEigen3(A_p); + vpMatrix A_p; + unsigned int rank = A.pseudoInverseEigen3(A_p); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank: " << rank << std::endl; + } \endcode \sa pseudoInverse(vpMatrix &, double) const @@ -3226,26 +3235,26 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, double svThreshold) con Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - unsigned int rank = A.pseudoInverseEigen3(A_p, sv); + vpMatrix A_p; + vpColVector sv; + unsigned int rank = A.pseudoInverseEigen3(A_p, sv); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; -} + std::cout << "Rank: " << rank << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, double) const @@ -3347,43 +3356,43 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpColVector sv; - vpMatrix A_p, imA, imAt, kerAt; - unsigned int rank = A.pseudoInverseEigen3(A_p, sv, 1e-6, imA, imAt, kerAt); + vpColVector sv; + vpMatrix A_p, imA, imAt, kerAt; + unsigned int rank = A.pseudoInverseEigen3(A_p, sv, 1e-6, imA, imAt, kerAt); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank: " << rank << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); - if (kerAt.size()) { - kerAt.t().print(std::cout, 10, "Ker(A): "); - } - else { - std::cout << "Ker(A) empty " << std::endl; - } + if (kerAt.size()) { + kerAt.t().print(std::cout, 10, "Ker(A): "); + } + else { + std::cout << "Ker(A) empty " << std::endl; + } - // Reconstruct matrix A from ImA, ImAt, KerAt - vpMatrix S(rank, A.getCols()); - for(unsigned int i = 0; i< rank; i++) - S[i][i] = sv[i]; - vpMatrix Vt(A.getCols(), A.getCols()); - Vt.insert(imAt.t(), 0, 0); - Vt.insert(kerAt, rank, 0); - (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); -} + // Reconstruct matrix A from ImA, ImAt, KerAt + vpMatrix S(rank, A.getCols()); + for(unsigned int i = 0; i< rank; i++) + S[i][i] = sv[i]; + vpMatrix Vt(A.getCols(), A.getCols()); + Vt.insert(imAt.t(), 0, 0); + Vt.insert(kerAt, rank, 0); + (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, double, vpMatrix &, vpMatrix &, vpMatrix &) const @@ -3432,24 +3441,24 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - int rank_in = 2; - vpMatrix A_p = A.pseudoInverseEigen3(rank_in); + int rank_in = 2; + vpMatrix A_p = A.pseudoInverseEigen3(rank_in); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - return 0; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + return 0; + } \endcode \sa pseudoInverse(int) const @@ -3500,31 +3509,31 @@ vpMatrix vpMatrix::pseudoInverseEigen3(int rank_in) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - int rank_in = 2; - int rank_out = A.pseudoInverseEigen3(A_p, rank_in); - 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; - } + vpMatrix A_p; + int rank_in = 2; + int rank_out = A.pseudoInverseEigen3(A_p, rank_in); + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - return 0; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + return 0; + } \endcode \sa pseudoInverse(vpMatrix &, int) const @@ -3579,34 +3588,34 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, int rank_in) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - int rank_in = 2; + vpMatrix A_p; + vpColVector sv; + int rank_in = 2; - int rank_out = A.pseudoInverseEigen3(A_p, sv, rank_in); - 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; - } + int rank_out = A.pseudoInverseEigen3(A_p, sv, rank_in); + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - return 0; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + return 0; + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, int) const @@ -3707,50 +3716,50 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in) co Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpColVector sv; - vpMatrix A_p, imA, imAt, kerAt; - int rank_in = 2; - int rank_out = A.pseudoInverseEigen3(A_p, sv, rank_in, imA, imAt, kerAt); + vpColVector sv; + vpMatrix A_p, imA, imAt, kerAt; + int rank_in = 2; + int rank_out = A.pseudoInverseEigen3(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; - } + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); - if (kerAt.size()) { - kerAt.t().print(std::cout, 10, "Ker(A): "); - } - else { - std::cout << "Ker(A) empty " << std::endl; - } + if (kerAt.size()) { + kerAt.t().print(std::cout, 10, "Ker(A): "); + } + else { + std::cout << "Ker(A) empty " << std::endl; + } - // Reconstruct matrix A from ImA, ImAt, KerAt - vpMatrix S(rank_in, A.getCols()); - for(unsigned int i = 0; i< rank_in; i++) - S[i][i] = sv[i]; - vpMatrix Vt(A.getCols(), A.getCols()); - Vt.insert(imAt.t(), 0, 0); - Vt.insert(kerAt, rank_in, 0); - (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); -} + // Reconstruct matrix A from ImA, ImAt, KerAt + vpMatrix S(rank_in, A.getCols()); + for(unsigned int i = 0; i< rank_in; i++) + S[i][i] = sv[i]; + vpMatrix Vt(A.getCols(), A.getCols()); + Vt.insert(imAt.t(), 0, 0); + Vt.insert(kerAt, rank_in, 0); + (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, int, vpMatrix &, vpMatrix &, vpMatrix &) const @@ -3805,21 +3814,21 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in, vp Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p = A.pseudoInverseEigen3(); + vpMatrix A_p = A.pseudoInverseEigen3(); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + } \endcode \sa pseudoInverse(double) const @@ -3871,23 +3880,23 @@ vpMatrix vpMatrix::pseudoInverseOpenCV(double svThreshold) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - unsigned int rank = A.pseudoInverseOpenCV(A_p); + vpMatrix A_p; + unsigned int rank = A.pseudoInverseOpenCV(A_p); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank: " << rank << std::endl; + } \endcode \sa pseudoInverse(vpMatrix &, double) const @@ -3942,26 +3951,26 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, double svThreshold) con Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - unsigned int rank = A.pseudoInverseOpenCV(A_p, sv); + vpMatrix A_p; + vpColVector sv; + unsigned int rank = A.pseudoInverseOpenCV(A_p, sv); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; -} + std::cout << "Rank: " << rank << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, double) const @@ -4063,43 +4072,43 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpColVector sv; - vpMatrix A_p, imA, imAt, kerAt; - unsigned int rank = A.pseudoInverseOpenCV(A_p, sv, 1e-6, imA, imAt, kerAt); + vpColVector sv; + vpMatrix A_p, imA, imAt, kerAt; + unsigned int rank = A.pseudoInverseOpenCV(A_p, sv, 1e-6, imA, imAt, kerAt); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank: " << rank << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); - if (kerAt.size()) { - kerAt.t().print(std::cout, 10, "Ker(A): "); + if (kerAt.size()) { + kerAt.t().print(std::cout, 10, "Ker(A): "); + } + else { + std::cout << "Ker(A) empty " << std::endl; + } + + // Reconstruct matrix A from ImA, ImAt, KerAt + vpMatrix S(rank, A.getCols()); + for(unsigned int i = 0; i< rank; i++) + S[i][i] = sv[i]; + vpMatrix Vt(A.getCols(), A.getCols()); + Vt.insert(imAt.t(), 0, 0); + Vt.insert(kerAt, rank, 0); + (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); } - else { - std::cout << "Ker(A) empty " << std::endl; - } - - // Reconstruct matrix A from ImA, ImAt, KerAt - vpMatrix S(rank, A.getCols()); - for(unsigned int i = 0; i< rank; i++) - S[i][i] = sv[i]; - vpMatrix Vt(A.getCols(), A.getCols()); - Vt.insert(imAt.t(), 0, 0); - Vt.insert(kerAt, rank, 0); - (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); -} \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, double, vpMatrix &, vpMatrix &, vpMatrix &) const @@ -4148,24 +4157,24 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - int rank_in = 2; - vpMatrix A_p = A.pseudoInverseOpenCV(rank_in); + int rank_in = 2; + vpMatrix A_p = A.pseudoInverseOpenCV(rank_in); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - return 0; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + return 0; + } \endcode \sa pseudoInverse(int) const @@ -4216,31 +4225,31 @@ vpMatrix vpMatrix::pseudoInverseOpenCV(int rank_in) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - int rank_in = 2; - int rank_out = A.pseudoInverseOpenCV(A_p, rank_in); - 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; - } + vpMatrix A_p; + int rank_in = 2; + int rank_out = A.pseudoInverseOpenCV(A_p, rank_in); + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - return 0; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + return 0; + } \endcode \sa pseudoInverse(vpMatrix &, int) const @@ -4295,34 +4304,34 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, int rank_in) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - // This matrix rank is 2 - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + // This matrix rank is 2 + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - int rank_in = 2; + vpMatrix A_p; + vpColVector sv; + int rank_in = 2; - int rank_out = A.pseudoInverseOpenCV(A_p, sv, rank_in); - 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; - } + int rank_out = A.pseudoInverseOpenCV(A_p, sv, rank_in); + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - return 0; -} + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + return 0; + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, int) const @@ -4423,50 +4432,50 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in) co Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpColVector sv; - vpMatrix A_p, imA, imAt, kerAt; - int rank_in = 2; - int rank_out = A.pseudoInverseOpenCV(A_p, sv, rank_in, imA, imAt, kerAt); + vpColVector sv; + vpMatrix A_p, imA, imAt, kerAt; + int rank_in = 2; + int rank_out = A.pseudoInverseOpenCV(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; - } + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); - if (kerAt.size()) { - kerAt.t().print(std::cout, 10, "Ker(A): "); - } - else { - std::cout << "Ker(A) empty " << std::endl; - } + if (kerAt.size()) { + kerAt.t().print(std::cout, 10, "Ker(A): "); + } + else { + std::cout << "Ker(A) empty " << std::endl; + } - // Reconstruct matrix A from ImA, ImAt, KerAt - vpMatrix S(rank_in, A.getCols()); - for(unsigned int i = 0; i< rank_in; i++) - S[i][i] = sv[i]; - vpMatrix Vt(A.getCols(), A.getCols()); - Vt.insert(imAt.t(), 0, 0); - Vt.insert(kerAt, rank_in, 0); - (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); -} + // Reconstruct matrix A from ImA, ImAt, KerAt + vpMatrix S(rank_in, A.getCols()); + for(unsigned int i = 0; i< rank_in; i++) + S[i][i] = sv[i]; + vpMatrix Vt(A.getCols(), A.getCols()); + Vt.insert(imAt.t(), 0, 0); + Vt.insert(kerAt, rank_in, 0); + (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); + } \endcode \sa pseudoInverse(vpMatrix &, vpColVector &, int, vpMatrix &, vpMatrix &, vpMatrix &) const @@ -4531,39 +4540,39 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in, vp Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - unsigned int rank = A.pseudoInverse(A_p, sv); + vpMatrix A_p; + vpColVector sv; + unsigned int rank = A.pseudoInverse(A_p, sv); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; -} + std::cout << "Rank: " << rank << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + } \endcode Once build, the previous example produces the following output: \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 -Rank: 2 -Singular values: 6.874359351 4.443330227 + A: [2,3]= + 2 3 5 + -4 2 3 + A^+ (pseudo-inverse): [3,2]= + 0.117899 -0.190782 + 0.065380 0.039657 + 0.113612 0.052518 + Rank: 2 + Singular values: 6.874359351 4.443330227 \endcode */ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThreshold) const @@ -4607,46 +4616,46 @@ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThr Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - int rank_in = 2; - int rank_out = A.pseudoInverse(A_p, sv, rank_in); - 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; - } + vpMatrix A_p; + vpColVector sv; + int rank_in = 2; + int rank_out = A.pseudoInverse(A_p, sv, rank_in); + 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; + } - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; -} + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + } \endcode Once build, the previous example produces the following output: \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 -Rank in : 2 -Rank out: 2 -Singular values: 6.874359351 4.443330227 + A: [2,3]= + 2 3 5 + -4 2 3 + A^+ (pseudo-inverse): [3,2]= + 0.117899 -0.190782 + 0.065380 0.039657 + 0.113612 0.052518 + Rank in : 2 + Rank out: 2 + Singular values: 6.874359351 4.443330227 \endcode */ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in) const @@ -4695,52 +4704,51 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in) const Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - vpMatrix imA, imAt; - unsigned int rank = A.pseudoInverse(A_p, sv, 1e-6, imA, imAt); - - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); -} + vpMatrix A_p; + vpColVector sv; + vpMatrix imA, imAt; + unsigned int rank = A.pseudoInverse(A_p, sv, 1e-6, imA, imAt); + + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank: " << rank << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); + } \endcode Once build, the previous example produces the following output: \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 -Rank: 2 -Singular values: 6.874359351 4.443330227 -Im(A): [2,2]= - 0.81458 -0.58003 - 0.58003 0.81458 -Im(A^T): [3,2]= - -0.100515 -0.994397 - 0.524244 -0.024967 - 0.845615 -0.102722 + A: [2,3]= + 2 3 5 + -4 2 3 + A^+ (pseudo-inverse): [3,2]= + 0.117899 -0.190782 + 0.065380 0.039657 + 0.113612 0.052518 + Rank: 2 + Singular values: 6.874359351 4.443330227 + Im(A): [2,2]= + 0.81458 -0.58003 + 0.58003 0.81458 + Im(A^T): [3,2]= + -0.100515 -0.994397 + 0.524244 -0.024967 + 0.845615 -0.102722 \endcode */ -unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, - vpMatrix &imAt) const +unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt) const { vpMatrix kerAt; return pseudoInverse(Ap, sv, svThreshold, imA, imAt, kerAt); @@ -4774,54 +4782,54 @@ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThr Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpMatrix A_p; - vpColVector sv; - vpMatrix imA, imAt; - int rank_in = 2; - int rank_out = A.pseudoInverse(A_p, sv, rank_in, imA, imAt); - 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; - } - - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_in << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); -} + vpMatrix A_p; + vpColVector sv; + vpMatrix imA, imAt; + int rank_in = 2; + int rank_out = A.pseudoInverse(A_p, sv, rank_in, imA, imAt); + 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; + } + + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_in << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); + } \endcode Once build, the previous example produces the following output: \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 -Rank: 2 -Singular values: 6.874359351 4.443330227 -Im(A): [2,2]= - 0.81458 -0.58003 - 0.58003 0.81458 -Im(A^T): [3,2]= - -0.100515 -0.994397 - 0.524244 -0.024967 - 0.845615 -0.102722 + A: [2,3]= + 2 3 5 + -4 2 3 + A^+ (pseudo-inverse): [3,2]= + 0.117899 -0.190782 + 0.065380 0.039657 + 0.113612 0.052518 + Rank: 2 + Singular values: 6.874359351 4.443330227 + Im(A): [2,2]= + 0.81458 -0.58003 + 0.58003 0.81458 + Im(A^T): [3,2]= + -0.100515 -0.994397 + 0.524244 -0.024967 + 0.845615 -0.102722 \endcode */ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt) const @@ -4842,126 +4850,93 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix \warning To inverse a square n-by-n matrix, you have to use rather inverseByLU(), inverseByCholesky(), or inverseByQR() that are kwown as faster. - Using singular value decomposition, we have: - - \f[ - {\bf A}_{m\times n} = {\bf U}_{m\times m} \; {\bf S}_{m\times n} \; {\bf - V^\top}_{n\times n} \f] \f[ - {\bf A}_{m\times n} = \left[\begin{array}{ccc}\mbox{Im} ({\bf A}) & | & - \mbox{Ker} ({\bf A}^\top) \end{array} \right] {\bf S}_{m\times n} - \left[ - \begin{array}{c} \left[\mbox{Im} ({\bf A}^\top)\right]^\top \\ - \\ - \hline \\ - \left[\mbox{Ker}({\bf A})\right]^\top \end{array}\right] - \f] - - where the diagonal of \f${\bf S}_{m\times n}\f$ corresponds to the matrix - \f$A\f$ singular values. - - This equation could be reformulated in a minimal way: - \f[ - {\bf A}_{m\times n} = \mbox{Im} ({\bf A}) \; {\bf S}_{r\times n} - \left[ - \begin{array}{c} \left[\mbox{Im} ({\bf A}^\top)\right]^\top \\ - \\ - \hline \\ - \left[\mbox{Ker}({\bf A})\right]^\top \end{array}\right] - \f] - - where the diagonal of \f${\bf S}_{r\times n}\f$ corresponds to the matrix - \f$A\f$ first r singular values. - - The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) - = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. - - \param Ap: The Moore-Penros pseudo inverse \f$ {\bf A}^+ \f$. + \param Ap : The Moore-Penros pseudo inverse \f$ {\bf A}^+ \f$. - \param sv: Vector corresponding to matrix \f$A\f$ singular values. The size - of this vector is equal to min(m, n). + \param sv : Vector corresponding to matrix A singular values. The size of this vector is equal to min(m, n). - \param svThreshold: Threshold used to test the singular values. If + \param svThreshold : Threshold used to test the singular values.If a singular value is lower than this threshold we consider that the matrix is not full rank. - \param imA: \f$\mbox{Im}({\bf A})\f$ that is a m-by-r matrix. + \param imA : \f$\mbox { Im }({ \bf A })\f$ that is a m - by - r matrix. - \param imAt: \f$\mbox{Im}({\bf A}^T)\f$ that is n-by-r matrix. + \param imAt : \f$\mbox { Im }({ \bf A } ^ T)\f$ that is n - by - r matrix. - \param kerAt: The matrix that contains the null space (kernel) of \f$\bf - A\f$ defined by the matrix \f${\bf X}^T\f$. If matrix \f$\bf A\f$ is full - rank, the dimension of \c kerAt is (0, n), otherwise the dimension is (n-r, - n). This matrix is thus the transpose of \f$\mbox{Ker}({\bf A})\f$. + \param kerAt : The matrix that contains the null space(kernel) of \f$\bf + A\f$ defined by the matrix \f$ { \bf X } ^ T\f$.If matrix \f$\bf A\f$ is full + rank, the dimension of \c kerAt is(0, n), otherwise the dimension is (n - r, n). + This matrix is thus the transpose of \f$\mbox { Ker }({ \bf A })\f$. \return The rank of the matrix \f$\bf A\f$. - Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. + Here an example to compute the pseudo - inverse of a 2 - by - 3 matrix that is rank 2. \code -#include + #include -int main() -{ - vpMatrix A(2, 3); + int main() + { + vpMatrix A(2, 3); - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); - vpColVector sv; - vpMatrix A_p, imA, imAt, kerAt; - unsigned int rank = A.pseudoInverse(A_p, sv, 1e-6, imA, imAt, kerAt); + vpColVector sv; + vpMatrix A_p, imA, imAt, kerAt; + unsigned int rank = A.pseudoInverse(A_p, sv, 1e-6, imA, imAt, kerAt); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank: " << rank << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank: " << rank << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); - if (kerAt.size()) { - kerAt.t().print(std::cout, 10, "Ker(A): "); - } - else { - std::cout << "Ker(A) empty " << std::endl; - } + if (kerAt.size()) { + kerAt.t().print(std::cout, 10, "Ker(A): "); + } + else { + std::cout << "Ker(A) empty " << std::endl; + } - // Reconstruct matrix A from ImA, ImAt, KerAt - vpMatrix S(rank, A.getCols()); - for(unsigned int i = 0; i< rank; i++) - S[i][i] = sv[i]; - vpMatrix Vt(A.getCols(), A.getCols()); - Vt.insert(imAt.t(), 0, 0); - Vt.insert(kerAt, rank, 0); - (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); -} + // Reconstruct matrix A from ImA, ImAt, KerAt + vpMatrix S(rank, A.getCols()); + for(unsigned int i = 0; i< rank; i++) + S[i][i] = sv[i]; + vpMatrix Vt(A.getCols(), A.getCols()); + Vt.insert(imAt.t(), 0, 0); + Vt.insert(kerAt, rank, 0); + (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); + } \endcode Once build, the previous example produces the following output: - \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 -Rank: 2 -Singular values: 6.874359351 4.443330227 -Im(A): [2,2]= - 0.81458 -0.58003 - 0.58003 0.81458 -Im(A^T): [3,2]= - -0.100515 -0.994397 - 0.524244 -0.024967 - 0.845615 -0.102722 -Ker(A): [3,1]= - -0.032738 - -0.851202 - 0.523816 -Im(A) * S * [Im(A^T) | Ker(A)]^T:[2,3]= - 2 3 5 - -4 2 3 + + \code{.sh} + A: [2,3]= + 2 3 5 + -4 2 3 + A^+ (pseudo-inverse): [3,2]= + 0.117899 -0.190782 + 0.065380 0.039657 + 0.113612 0.052518 + Rank: 2 + Singular values: 6.874359351 4.443330227 + Im(A): [2,2]= + 0.81458 -0.58003 + 0.58003 0.81458 + Im(A^T): [3,2]= + -0.100515 -0.994397 + 0.524244 -0.024967 + 0.845615 -0.102722 + Ker(A): [3,1]= + -0.032738 + -0.851202 + 0.523816 + Im(A) * S * [Im(A^T) | Ker(A)]^T:[2,3]= + 2 3 5 + -4 2 3 \endcode */ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, @@ -4988,174 +4963,141 @@ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThr /*! Compute the Moore-Penros pseudo inverse \f$A^+\f$ of a m-by-n matrix \f$\bf A\f$ along with singular values, \f$\mbox{Im}(A)\f$, \f$\mbox{Im}(A^T)\f$ and - \f$\mbox{Ker}(A)\f$ and return the rank of the matrix. + \f$\mbox { Ker }(A)\f$ and return the rank of the matrix. - \note By default, this function uses Lapack 3rd party. It is also possible + \note By default, this function uses Lapack 3rd party.It is also possible to use a specific 3rd party suffixing this function name with one of the - following 3rd party names (Lapack, Eigen3 or OpenCV). + following 3rd party names(Lapack, Eigen3 or OpenCV). - \warning To inverse a square n-by-n matrix, you have to use rather + \warning To inverse a square n - by - n matrix, you have to use rather inverseByLU(), inverseByCholesky(), or inverseByQR() that are kwown as faster. - Using singular value decomposition, we have: - -\f[ -{\bf A}_ { m\times n } = { \bf U }_ { m\times m } \; {\bf S}_ { m\times n } \; {\bf -V ^\top}_ { n\times n } \f] \f[ -{\bf A}_ { m\times n } = \left[\begin { array }{ccc}\mbox { Im } ({ \bf A }) &| & -\mbox { Ker } ({ \bf A }^\top) \end { array } \right] {\bf S}_ { m\times n } -\left[ - \begin { array }{c} \left[\mbox { Im } ({ \bf A }^\top)\right]^\top \\ - \\ - \hline \\ - \left[\mbox { Ker }({ \bf A })\right]^\top \end { array }\right] - \f] - - where the diagonal of \f$ { \bf S }_ { m\times n }\f$ corresponds to the matrix - \f$A\f$ singular values. - - This equation could be reformulated in a minimal way : - \f[ - {\bf A}_ { m\times n } = \mbox { Im } ({ \bf A }) \; {\bf S}_ { r\times n } - \left[ - \begin { array }{c} \left[\mbox { Im } ({ \bf A }^\top)\right]^\top \\ - \\ - \hline \\ - \left[\mbox { Ker }({ \bf A })\right]^\top \end { array }\right] - \f] - - where the diagonal of \f$ { \bf S }_ { r\times n }\f$ corresponds to the matrix - \f$A\f$ first r singular values. - - The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox { Ker }({ \bf A }) - = { {\bf X} : {\bf A} *{\bf X} = {\bf 0} }\f$. + \param Ap : The Moore - Penros pseudo inverse \f$ { \bf A } ^ +\f$. - \param Ap : The Moore-Penros pseudo inverse \f$ { \bf A }^+\f$. + \param sv : Vector corresponding to matrix \f$A\f$ singular values.The size + of this vector is equal to min(m, n). - \param sv : Vector corresponding to matrix \f$A\f$ singular values.The size - of this vector is equal to min(m, n). + \param[in] rank_in : Known rank of the matrix. - \param[in] rank_in : Known rank of the matrix. + \param imA : \f$\mbox { Im }({ \bf A })\f$ that is a m - by - r matrix. - \param imA : \f$\mbox { Im }({ \bf A })\f$ that is a m-by-r matrix. + \param imAt : \f$\mbox { Im }({ \bf A } ^T)\f$ that is n - by - r matrix. - \param imAt : \f$\mbox { Im }({ \bf A }^T)\f$ that is n-by-r matrix. + \param kerAt : The matrix that contains the null space(kernel) of \f$\bf + A\f$ defined by the matrix \f$ { \bf X } ^ T\f$.If matrix \f$\bf A\f$ is full + rank, the dimension of \c kerAt is(0, n), otherwise the dimension is(n - r, + n).This matrix is thus the transpose of \f$\mbox { Ker }({ \bf A })\f$. - \param kerAt : The matrix that contains the null space(kernel) of \f$\bf - A\f$ defined by the matrix \f$ { \bf X }^T\f$.If matrix \f$\bf A\f$ is full - rank, the dimension of \c kerAt is(0, n), otherwise the dimension is(n-r, - n).This matrix is thus the transpose of \f$\mbox { Ker }({ \bf A })\f$. + \return The rank of the matrix \f$\bf A\f$. - \return The rank of the matrix \f$\bf A\f$. + Here an example to compute the pseudo - inverse of a 2 - by - 3 matrix that is rank 2. - Here an example to compute the pseudo-inverse of a 2-by-3 matrix that is rank 2. + \code + #include - \code -#include + int main() + { + vpMatrix A(2, 3); - int main() - { - vpMatrix A(2, 3); +A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; +A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; - A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; - A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; +A.print(std::cout, 10, "A: "); - A.print(std::cout, 10, "A: "); +vpColVector sv; +vpMatrix A_p, imA, imAt, kerAt; +int rank_in = 2; +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; +} - vpColVector sv; - vpMatrix A_p, imA, imAt, kerAt; - int rank_in = 2; - 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; - } +A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); +std::cout << "Rank in : " << rank_in << std::endl; +std::cout << "Rank out: " << rank_out << std::endl; +std::cout << "Singular values: " << sv.t() << std::endl; +imA.print(std::cout, 10, "Im(A): "); +imAt.print(std::cout, 10, "Im(A^T): "); - A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); - std::cout << "Rank in : " << rank_in << std::endl; - std::cout << "Rank out: " << rank_out << std::endl; - std::cout << "Singular values: " << sv.t() << std::endl; - imA.print(std::cout, 10, "Im(A): "); - imAt.print(std::cout, 10, "Im(A^T): "); +if (kerAt.size()) { + kerAt.t().print(std::cout, 10, "Ker(A): "); +} +else { + std::cout << "Ker(A) empty " << std::endl; +} - if (kerAt.size()) { - kerAt.t().print(std::cout, 10, "Ker(A): "); - } - else { - std::cout << "Ker(A) empty " << std::endl; - } +// Reconstruct matrix A from ImA, ImAt, KerAt +vpMatrix S(rank, A.getCols()); +for (unsigned int i = 0; i < rank_in; i++) + S[i][i] = sv[i]; +vpMatrix Vt(A.getCols(), A.getCols()); +Vt.insert(imAt.t(), 0, 0); +Vt.insert(kerAt, rank, 0); +(imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); + } + \endcode - // Reconstruct matrix A from ImA, ImAt, KerAt - vpMatrix S(rank, A.getCols()); - for (unsigned int i = 0; i< rank_in; i++) - S[i][i] = sv[i]; - vpMatrix Vt(A.getCols(), A.getCols()); - Vt.insert(imAt.t(), 0, 0); - Vt.insert(kerAt, rank, 0); - (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); - } + Once build, the previous example produces the following output : + \code + A : [2, 3] = + 2 3 5 + - 4 2 3 + A ^ +(pseudo - inverse) : [3, 2] = + 0.117899 - 0.190782 + 0.065380 0.039657 + 0.113612 0.052518 + Rank in : 2 + Rank out : 2 + Singular values : 6.874359351 4.443330227 + Im(A) : [2, 2] = + 0.81458 - 0.58003 + 0.58003 0.81458 + Im(A ^ T) : [3, 2] = + -0.100515 - 0.994397 + 0.524244 - 0.024967 + 0.845615 - 0.102722 + Ker(A) : [3, 1] = + -0.032738 + - 0.851202 + 0.523816 + Im(A) * S *[Im(A ^ T) | Ker(A)] ^ T : [2, 3] = + 2 3 5 + - 4 2 3 \endcode - - Once build, the previous example produces the following output : - \code - A : [2, 3] = - 2 3 5 - -4 2 3 - A^+(pseudo-inverse) : [3, 2] = - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 - Rank in : 2 - Rank out : 2 - Singular values : 6.874359351 4.443330227 - Im(A) : [2, 2] = - 0.81458 -0.58003 - 0.58003 0.81458 - Im(A^T) : [3, 2] = - -0.100515 -0.994397 - 0.524244 -0.024967 - 0.845615 -0.102722 - Ker(A) : [3, 1] = - -0.032738 - -0.851202 - 0.523816 - Im(A) * S *[Im(A^T) | Ker(A)]^T : [2, 3] = - 2 3 5 - -4 2 3 - \endcode - */ - int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, - vpMatrix &kerAt) const - { + */ + int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, + vpMatrix &kerAt) const + { #if defined(VISP_HAVE_LAPACK) - return pseudoInverseLapack(Ap, sv, rank_in, imA, imAt, kerAt); + return pseudoInverseLapack(Ap, sv, rank_in, imA, imAt, kerAt); #elif defined(VISP_HAVE_EIGEN3) - return pseudoInverseEigen3(Ap, sv, rank_in, imA, imAt, kerAt); + return pseudoInverseEigen3(Ap, sv, rank_in, imA, imAt, kerAt); #elif defined(VISP_HAVE_OPENCV) // Require opencv >= 2.1.1 - return pseudoInverseOpenCV(Ap, sv, rank_in, imA, imAt, kerAt); + return pseudoInverseOpenCV(Ap, sv, rank_in, imA, imAt, kerAt); #else - (void)Ap; - (void)sv; - (void)rank_in; - (void)imA; - (void)imAt; - (void)kerAt; - throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + (void)Ap; + (void)sv; + (void)rank_in; + (void)imA; + (void)imAt; + (void)kerAt; + throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif - } + } - /*! - Extract a column vector from a matrix. - \warning All the indexes start from 0 in this function. - \param j : Index of the column to extract. If col=0, the first column is extracted. - \param i_begin : Index of the row that gives the location of the first element - of the column vector to extract. - \param column_size : Size of the column vector to extract. - \return The extracted column vector. + /*! + Extract a column vector from a matrix. + \warning All the indexes start from 0 in this function. + \param j : Index of the column to extract. If col=0, the first column is extracted. + \param i_begin : Index of the row that gives the location of the first element + of the column vector to extract. + \param column_size : Size of the column vector to extract. + \return The extracted column vector. - The following example shows how to use this function: - \code + The following example shows how to use this function: + \code #include #include @@ -5172,39 +5114,39 @@ V ^\top}_ { n\times n } \f] \f[ vpColVector cv = A.getCol(1, 1, 3); std::cout << "Column vector: \n" << cv << std::endl; } - \endcode + \endcode It produces the following output: - \code + \code [4,4]= - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 + 0 1 2 3 + 4 5 6 7 + 8 9 10 11 12 13 14 15 column vector: 5 9 13 - \endcode - */ - vpColVector vpMatrix::getCol(unsigned int j, unsigned int i_begin, unsigned int column_size) const - { - if (i_begin + column_size > getRows() || j >= getCols()) - throw(vpException(vpException::dimensionError, "Unable to extract column %u from the %ux%u matrix", j, getRows(), - getCols())); - vpColVector c(column_size); - for (unsigned int i = 0; i < column_size; i++) - c[i] = (*this)[i_begin + i][j]; - return c; - } - - /*! - Extract a column vector from a matrix. - \warning All the indexes start from 0 in this function. - \param j : Index of the column to extract. If j=0, the first column is extracted. - \return The extracted column vector. - - The following example shows how to use this function: - \code + \endcode + */ + vpColVector vpMatrix::getCol(unsigned int j, unsigned int i_begin, unsigned int column_size) const + { + if (i_begin + column_size > getRows() || j >= getCols()) + throw(vpException(vpException::dimensionError, "Unable to extract column %u from the %ux%u matrix", j, getRows(), + getCols())); + vpColVector c(column_size); + for (unsigned int i = 0; i < column_size; i++) + c[i] = (*this)[i_begin + i][j]; + return c; + } + + /*! + Extract a column vector from a matrix. + \warning All the indexes start from 0 in this function. + \param j : Index of the column to extract. If j=0, the first column is extracted. + \return The extracted column vector. + + The following example shows how to use this function: + \code #include #include @@ -5221,30 +5163,30 @@ V ^\top}_ { n\times n } \f] \f[ vpColVector cv = A.getCol(1); std::cout << "Column vector: \n" << cv << std::endl; } - \endcode + \endcode It produces the following output: - \code + \code [4,4]= - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 + 0 1 2 3 + 4 5 6 7 + 8 9 10 11 12 13 14 15 column vector: 1 5 9 13 - \endcode - */ - vpColVector vpMatrix::getCol(unsigned int j) const { return getCol(j, 0, rowNum); } + \endcode + */ + vpColVector vpMatrix::getCol(unsigned int j) const { return getCol(j, 0, rowNum); } - /*! - Extract a row vector from a matrix. - \warning All the indexes start from 0 in this function. - \param i : Index of the row to extract. If i=0, the first row is extracted. - \return The extracted row vector. + /*! + Extract a row vector from a matrix. + \warning All the indexes start from 0 in this function. + \param i : Index of the row to extract. If i=0, the first row is extracted. + \return The extracted row vector. - The following example shows how to use this function: + The following example shows how to use this function: \code #include #include @@ -5261,31 +5203,32 @@ V ^\top}_ { n\times n } \f] \f[ vpRowVector rv = A.getRow(1); std::cout << "Row vector: \n" << rv << std::endl; - } \endcode + } + \endcode It produces the following output: - \code + \code [4,4]= - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 + 0 1 2 3 + 4 5 6 7 + 8 9 10 11 12 13 14 15 Row vector: 4 5 6 7 - \endcode - */ - vpRowVector vpMatrix::getRow(unsigned int i) const { return getRow(i, 0, colNum); } - - /*! - Extract a row vector from a matrix. - \warning All the indexes start from 0 in this function. - \param i : Index of the row to extract. If i=0, the first row is extracted. - \param j_begin : Index of the column that gives the location of the first + \endcode + */ + vpRowVector vpMatrix::getRow(unsigned int i) const { return getRow(i, 0, colNum); } + + /*! + Extract a row vector from a matrix. + \warning All the indexes start from 0 in this function. + \param i : Index of the row to extract. If i=0, the first row is extracted. + \param j_begin : Index of the column that gives the location of the first element of the row vector to extract. - \param row_size : Size of the row vector to extract. - \return The extracted row vector. + \param row_size : Size of the row vector to extract. + \return The extracted row vector. - The following example shows how to use this function: - \code + The following example shows how to use this function: + \code #include #include @@ -5302,40 +5245,40 @@ V ^\top}_ { n\times n } \f] \f[ vpRowVector rv = A.getRow(1, 1, 3); std::cout << "Row vector: \n" << rv << std::endl; } - \endcode + \endcode It produces the following output: \code [4,4]= - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 + 0 1 2 3 + 4 5 6 7 + 8 9 10 11 12 13 14 15 Row vector: 5 6 7 - \endcode - */ - vpRowVector vpMatrix::getRow(unsigned int i, unsigned int j_begin, unsigned int row_size) const - { - if (j_begin + row_size > colNum || i >= rowNum) - throw(vpException(vpException::dimensionError, "Unable to extract a row vector from the matrix")); - - vpRowVector r(row_size); - if (r.data != nullptr && data != nullptr) { - memcpy(r.data, (*this)[i] + j_begin, row_size * sizeof(double)); - } - - return r; + \endcode + */ + vpRowVector vpMatrix::getRow(unsigned int i, unsigned int j_begin, unsigned int row_size) const + { + if (j_begin + row_size > colNum || i >= rowNum) + throw(vpException(vpException::dimensionError, "Unable to extract a row vector from the matrix")); + + vpRowVector r(row_size); + if (r.data != nullptr && data != nullptr) { + memcpy(r.data, (*this)[i] + j_begin, row_size * sizeof(double)); } - /*! - Extract a diagonal vector from a matrix. + return r; + } + + /*! + Extract a diagonal vector from a matrix. - \return The diagonal of the matrix. + \return The diagonal of the matrix. - \warning An empty vector is returned if the matrix is empty. + \warning An empty vector is returned if the matrix is empty. - The following example shows how to use this function: - \code + The following example shows how to use this function: + \code #include int main() @@ -5351,384 +5294,384 @@ V ^\top}_ { n\times n } \f] \f[ vpColVector diag = A.getDiag(); std::cout << "Diag vector: \n" << diag.t() << std::endl; } - \endcode + \endcode It produces the following output: - \code + \code [3,4]= - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 + 0 1 2 3 + 4 5 6 7 + 8 9 10 11 Diag vector: 0 5 10 - \endcode - */ - vpColVector vpMatrix::getDiag() const - { - unsigned int min_size = std::min(rowNum, colNum); - vpColVector diag; + \endcode + */ + vpColVector vpMatrix::getDiag() const + { + unsigned int min_size = std::min(rowNum, colNum); + vpColVector diag; - if (min_size > 0) { - diag.resize(min_size, false); + if (min_size > 0) { + diag.resize(min_size, false); - for (unsigned int i = 0; i < min_size; i++) { - diag[i] = (*this)[i][i]; - } + for (unsigned int i = 0; i < min_size; i++) { + diag[i] = (*this)[i][i]; } - - return diag; } - /*! - Stack matrix \e B to the end of matrix \e A and return the resulting matrix - [ A B ]^T - - \param A : Upper matrix. - \param B : Lower matrix. - \return Stacked matrix [ A B ]^T + return diag; + } - \warning A and B must have the same number of columns. - */ - vpMatrix vpMatrix::stack(const vpMatrix &A, const vpMatrix &B) - { - vpMatrix C; + /*! + Stack matrix \e B to the end of matrix \e A and return the resulting matrix + [ A B ]^T - vpMatrix::stack(A, B, C); + \param A : Upper matrix. + \param B : Lower matrix. + \return Stacked matrix [ A B ]^T - return C; - } + \warning A and B must have the same number of columns. + */ + vpMatrix vpMatrix::stack(const vpMatrix &A, const vpMatrix &B) + { + vpMatrix C; - /*! - Stack matrix \e B to the end of matrix \e A and return the resulting matrix - in \e C. + vpMatrix::stack(A, B, C); - \param A : Upper matrix. - \param B : Lower matrix. - \param C : Stacked matrix C = [ A B ]^T + return C; + } - \warning A and B must have the same number of columns. A and C, B and C must - be two different objects. - */ - void vpMatrix::stack(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) - { - unsigned int nra = A.getRows(); - unsigned int nrb = B.getRows(); + /*! + Stack matrix \e B to the end of matrix \e A and return the resulting matrix + in \e C. - if (nra != 0) { - if (A.getCols() != B.getCols()) { - throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx%d) matrix", A.getRows(), - A.getCols(), B.getRows(), B.getCols())); - } - } + \param A : Upper matrix. + \param B : Lower matrix. + \param C : Stacked matrix C = [ A B ]^T - if (A.data != nullptr && A.data == C.data) { - std::cerr << "A and C must be two different objects!" << std::endl; - return; + \warning A and B must have the same number of columns. A and C, B and C must + be two different objects. + */ + void vpMatrix::stack(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) + { + unsigned int nra = A.getRows(); + unsigned int nrb = B.getRows(); + + if (nra != 0) { + if (A.getCols() != B.getCols()) { + throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx%d) matrix", A.getRows(), + A.getCols(), B.getRows(), B.getCols())); } + } - if (B.data != nullptr && B.data == C.data) { - std::cerr << "B and C must be two different objects!" << std::endl; - return; - } + if (A.data != nullptr && A.data == C.data) { + std::cerr << "A and C must be two different objects!" << std::endl; + return; + } - C.resize(nra + nrb, B.getCols(), false, false); + if (B.data != nullptr && B.data == C.data) { + std::cerr << "B and C must be two different objects!" << std::endl; + return; + } - if (C.data != nullptr && A.data != nullptr && A.size() > 0) { - // Copy A in C - memcpy(C.data, A.data, sizeof(double) * A.size()); - } + C.resize(nra + nrb, B.getCols(), false, false); - if (C.data != nullptr && B.data != nullptr && B.size() > 0) { - // Copy B in C - memcpy(C.data + A.size(), B.data, sizeof(double) * B.size()); - } + if (C.data != nullptr && A.data != nullptr && A.size() > 0) { + // Copy A in C + memcpy(C.data, A.data, sizeof(double) * A.size()); } - /*! - Stack row vector \e r to matrix \e A and return the resulting matrix [ A r ]^T + if (C.data != nullptr && B.data != nullptr && B.size() > 0) { + // Copy B in C + memcpy(C.data + A.size(), B.data, sizeof(double) * B.size()); + } + } - \param A : Upper matrix. - \param r : Lower row vector. - \return Stacked matrix [ A r ]^T + /*! + Stack row vector \e r to matrix \e A and return the resulting matrix [ A r ]^T - \warning \e A and \e r must have the same number of columns. - */ - vpMatrix vpMatrix::stack(const vpMatrix &A, const vpRowVector &r) - { - vpMatrix C; - vpMatrix::stack(A, r, C); + \param A : Upper matrix. + \param r : Lower row vector. + \return Stacked matrix [ A r ]^T - return C; - } + \warning \e A and \e r must have the same number of columns. + */ + vpMatrix vpMatrix::stack(const vpMatrix &A, const vpRowVector &r) + { + vpMatrix C; + vpMatrix::stack(A, r, C); - /*! - Stack row vector \e r to the end of matrix \e A and return the resulting - matrix in \e C. + return C; + } - \param A : Upper matrix. - \param r : Lower row vector. - \param C : Stacked matrix C = [ A r ]^T + /*! + Stack row vector \e r to the end of matrix \e A and return the resulting + matrix in \e C. - \warning A and r must have the same number of columns. A and C must be two - different objects. - */ - void vpMatrix::stack(const vpMatrix &A, const vpRowVector &r, vpMatrix &C) - { - if (A.data != nullptr && A.data == C.data) { - std::cerr << "A and C must be two different objects!" << std::endl; - return; - } + \param A : Upper matrix. + \param r : Lower row vector. + \param C : Stacked matrix C = [ A r ]^T - C = A; - C.stack(r); + \warning A and r must have the same number of columns. A and C must be two + different objects. + */ + void vpMatrix::stack(const vpMatrix &A, const vpRowVector &r, vpMatrix &C) + { + if (A.data != nullptr && A.data == C.data) { + std::cerr << "A and C must be two different objects!" << std::endl; + return; } - /*! - Stack column vector \e c to matrix \e A and return the resulting matrix [ A c ] + C = A; + C.stack(r); + } - \param A : Left matrix. - \param c : Right column vector. - \return Stacked matrix [ A c ] + /*! + Stack column vector \e c to matrix \e A and return the resulting matrix [ A c ] - \warning \e A and \e c must have the same number of rows. - */ - vpMatrix vpMatrix::stack(const vpMatrix &A, const vpColVector &c) - { - vpMatrix C; - vpMatrix::stack(A, c, C); + \param A : Left matrix. + \param c : Right column vector. + \return Stacked matrix [ A c ] - return C; - } + \warning \e A and \e c must have the same number of rows. + */ + vpMatrix vpMatrix::stack(const vpMatrix &A, const vpColVector &c) + { + vpMatrix C; + vpMatrix::stack(A, c, C); - /*! - Stack column vector \e c to the end of matrix \e A and return the resulting - matrix in \e C. + return C; + } - \param A : Left matrix. - \param c : Right column vector. - \param C : Stacked matrix C = [ A c ] + /*! + Stack column vector \e c to the end of matrix \e A and return the resulting + matrix in \e C. - \warning A and c must have the same number of rows. A and C must be two - different objects. - */ - void vpMatrix::stack(const vpMatrix &A, const vpColVector &c, vpMatrix &C) - { - if (A.data != nullptr && A.data == C.data) { - std::cerr << "A and C must be two different objects!" << std::endl; - return; - } + \param A : Left matrix. + \param c : Right column vector. + \param C : Stacked matrix C = [ A c ] - C = A; - C.stack(c); + \warning A and c must have the same number of rows. A and C must be two + different objects. + */ + void vpMatrix::stack(const vpMatrix &A, const vpColVector &c, vpMatrix &C) + { + if (A.data != nullptr && A.data == C.data) { + std::cerr << "A and C must be two different objects!" << std::endl; + return; } - /*! - Insert matrix B in matrix A at the given position. - - \param A : Main matrix. - \param B : Matrix to insert. - \param r : Index of the row where to add the matrix. - \param c : Index of the column where to add the matrix. - \return Matrix with B insert in A. + C = A; + C.stack(c); + } - \warning Throw exception if the sizes of the matrices do not allow the - insertion. - */ - vpMatrix vpMatrix::insert(const vpMatrix &A, const vpMatrix &B, unsigned int r, unsigned int c) - { - vpArray2D C; + /*! + Insert matrix B in matrix A at the given position. - vpArray2D::insert(A, B, C, r, c); + \param A : Main matrix. + \param B : Matrix to insert. + \param r : Index of the row where to add the matrix. + \param c : Index of the column where to add the matrix. + \return Matrix with B insert in A. - return vpMatrix(C); - } + \warning Throw exception if the sizes of the matrices do not allow the + insertion. + */ + vpMatrix vpMatrix::insert(const vpMatrix &A, const vpMatrix &B, unsigned int r, unsigned int c) + { + vpArray2D C; - /*! - \relates vpMatrix - Insert matrix B in matrix A at the given position. + vpArray2D::insert(A, B, C, r, c); - \param A : Main matrix. - \param B : Matrix to insert. - \param C : Result matrix. - \param r : Index of the row where to insert matrix B. - \param c : Index of the column where to insert matrix B. + return vpMatrix(C); + } - \warning Throw exception if the sizes of the matrices do not - allow the insertion. - */ - void vpMatrix::insert(const vpMatrix &A, const vpMatrix &B, vpMatrix &C, unsigned int r, unsigned int c) - { - vpArray2D C_array; + /*! + \relates vpMatrix + Insert matrix B in matrix A at the given position. - vpArray2D::insert(A, B, C_array, r, c); + \param A : Main matrix. + \param B : Matrix to insert. + \param C : Result matrix. + \param r : Index of the row where to insert matrix B. + \param c : Index of the column where to insert matrix B. - C = C_array; - } + \warning Throw exception if the sizes of the matrices do not + allow the insertion. + */ + void vpMatrix::insert(const vpMatrix &A, const vpMatrix &B, vpMatrix &C, unsigned int r, unsigned int c) + { + vpArray2D C_array; - /*! - Juxtapose to matrices C = [ A B ]. + vpArray2D::insert(A, B, C_array, r, c); - \f$ C = \left( \begin{array}{cc} A & B \end{array}\right) \f$ + C = C_array; + } - \param A : Left matrix. - \param B : Right matrix. - \return Juxtaposed matrix C = [ A B ] + /*! + Juxtapose to matrices C = [ A B ]. - \warning A and B must have the same number of rows. - */ - vpMatrix vpMatrix::juxtaposeMatrices(const vpMatrix &A, const vpMatrix &B) - { - vpMatrix C; + \f$ C = \left( \begin{array}{cc} A & B \end{array}\right) \f$ - juxtaposeMatrices(A, B, C); + \param A : Left matrix. + \param B : Right matrix. + \return Juxtaposed matrix C = [ A B ] - return C; - } + \warning A and B must have the same number of rows. + */ + vpMatrix vpMatrix::juxtaposeMatrices(const vpMatrix &A, const vpMatrix &B) + { + vpMatrix C; - /*! - \relates vpMatrix - Juxtapose to matrices C = [ A B ]. + juxtaposeMatrices(A, B, C); - \f$ C = \left( \begin{array}{cc} A & B \end{array}\right) \f$ + return C; + } - \param A : Left matrix. - \param B : Right matrix. - \param C : Juxtaposed matrix C = [ A B ] + /*! + \relates vpMatrix + Juxtapose to matrices C = [ A B ]. - \warning A and B must have the same number of rows. - */ - void vpMatrix::juxtaposeMatrices(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) - { - unsigned int nca = A.getCols(); - unsigned int ncb = B.getCols(); + \f$ C = \left( \begin{array}{cc} A & B \end{array}\right) \f$ - if (nca != 0) { - if (A.getRows() != B.getRows()) { - throw(vpException(vpException::dimensionError, "Cannot juxtapose (%dx%d) matrix with (%dx%d) matrix", A.getRows(), - A.getCols(), B.getRows(), B.getCols())); - } - } + \param A : Left matrix. + \param B : Right matrix. + \param C : Juxtaposed matrix C = [ A B ] - if (B.getRows() == 0 || nca + ncb == 0) { - std::cerr << "B.getRows() == 0 || nca+ncb == 0" << std::endl; - return; + \warning A and B must have the same number of rows. + */ + void vpMatrix::juxtaposeMatrices(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) + { + unsigned int nca = A.getCols(); + unsigned int ncb = B.getCols(); + + if (nca != 0) { + if (A.getRows() != B.getRows()) { + throw(vpException(vpException::dimensionError, "Cannot juxtapose (%dx%d) matrix with (%dx%d) matrix", A.getRows(), + A.getCols(), B.getRows(), B.getCols())); } + } - C.resize(B.getRows(), nca + ncb, false, false); - - C.insert(A, 0, 0); - C.insert(B, 0, nca); + if (B.getRows() == 0 || nca + ncb == 0) { + std::cerr << "B.getRows() == 0 || nca+ncb == 0" << std::endl; + return; } - //-------------------------------------------------------------------- - // Output - //-------------------------------------------------------------------- + C.resize(B.getRows(), nca + ncb, false, false); - /*! + C.insert(A, 0, 0); + C.insert(B, 0, nca); + } - Pretty print a matrix. The data are tabulated. - The common widths before and after the decimal point - are set with respect to the parameter `length`. + //-------------------------------------------------------------------- + // Output + //-------------------------------------------------------------------- - \param s : Stream used for the printing. + /*! - \param length : The suggested width of each matrix element. - If needed, the used `length` grows in order to accommodate the whole integral part, - and shrinks the decimal part to print only `length` digits. - \param intro : The introduction which is printed before the matrix. - Can be set to zero (or omitted), in which case - the introduction is not printed. + Pretty print a matrix. The data are tabulated. + The common widths before and after the decimal point + are set with respect to the parameter `length`. - \return Returns the common total width for all matrix elements. + \param s : Stream used for the printing. - \sa std::ostream &operator<<(std::ostream &s, const vpArray2D &A) - */ - int vpMatrix::print(std::ostream &s, unsigned int length, const std::string &intro) const - { - typedef std::string::size_type size_type; - - unsigned int m = getRows(); - unsigned int n = getCols(); - - std::vector values(m * n); - std::ostringstream oss; - std::ostringstream ossFixed; - std::ios_base::fmtflags original_flags = oss.flags(); - - ossFixed.setf(std::ios::fixed, std::ios::floatfield); - - size_type maxBefore = 0; // the length of the integral part - size_type maxAfter = 0; // number of decimals plus - // one place for the decimal point - for (unsigned int i = 0; i < m; ++i) { - for (unsigned int j = 0; j < n; ++j) { - oss.str(""); - oss << (*this)[i][j]; - if (oss.str().find("e") != std::string::npos) { - ossFixed.str(""); - ossFixed << (*this)[i][j]; - oss.str(ossFixed.str()); - } + \param length : The suggested width of each matrix element. + If needed, the used `length` grows in order to accommodate the whole integral part, + and shrinks the decimal part to print only `length` digits. + \param intro : The introduction which is printed before the matrix. + Can be set to zero (or omitted), in which case + the introduction is not printed. - values[i * n + j] = oss.str(); - size_type thislen = values[i * n + j].size(); - size_type p = values[i * n + j].find('.'); + \return Returns the common total width for all matrix elements. - if (p == std::string::npos) { - maxBefore = vpMath::maximum(maxBefore, thislen); - // maxAfter remains the same - } - else { - maxBefore = vpMath::maximum(maxBefore, p); - maxAfter = vpMath::maximum(maxAfter, thislen - p); - } + \sa std::ostream &operator<<(std::ostream &s, const vpArray2D &A) + */ + int vpMatrix::print(std::ostream &s, unsigned int length, const std::string &intro) const + { + typedef std::string::size_type size_type; + + unsigned int m = getRows(); + unsigned int n = getCols(); + + std::vector values(m * n); + std::ostringstream oss; + std::ostringstream ossFixed; + std::ios_base::fmtflags original_flags = oss.flags(); + + ossFixed.setf(std::ios::fixed, std::ios::floatfield); + + size_type maxBefore = 0; // the length of the integral part + size_type maxAfter = 0; // number of decimals plus + // one place for the decimal point + for (unsigned int i = 0; i < m; ++i) { + for (unsigned int j = 0; j < n; ++j) { + oss.str(""); + oss << (*this)[i][j]; + if (oss.str().find("e") != std::string::npos) { + ossFixed.str(""); + ossFixed << (*this)[i][j]; + oss.str(ossFixed.str()); } - } - size_type totalLength = length; - // increase totalLength according to maxBefore - totalLength = vpMath::maximum(totalLength, maxBefore); - // decrease maxAfter according to totalLength - maxAfter = std::min(maxAfter, totalLength - maxBefore); - - if (!intro.empty()) - s << intro; - s << "[" << m << "," << n << "]=\n"; - - for (unsigned int i = 0; i < m; i++) { - s << " "; - for (unsigned int j = 0; j < n; j++) { - size_type p = values[i * n + j].find('.'); - s.setf(std::ios::right, std::ios::adjustfield); - s.width((std::streamsize)maxBefore); - s << values[i * n + j].substr(0, p).c_str(); - - if (maxAfter > 0) { - s.setf(std::ios::left, std::ios::adjustfield); - if (p != std::string::npos) { - s.width((std::streamsize)maxAfter); - s << values[i * n + j].substr(p, maxAfter).c_str(); - } - else { - s.width((std::streamsize)maxAfter); - s << ".0"; - } - } + values[i * n + j] = oss.str(); + size_type thislen = values[i * n + j].size(); + size_type p = values[i * n + j].find('.'); - s << ' '; + if (p == std::string::npos) { + maxBefore = vpMath::maximum(maxBefore, thislen); + // maxAfter remains the same + } + else { + maxBefore = vpMath::maximum(maxBefore, p); + maxAfter = vpMath::maximum(maxAfter, thislen - p); } - s << std::endl; } + } - s.flags(original_flags); // restore s to standard state + size_type totalLength = length; + // increase totalLength according to maxBefore + totalLength = vpMath::maximum(totalLength, maxBefore); + // decrease maxAfter according to totalLength + maxAfter = std::min(maxAfter, totalLength - maxBefore); + + if (!intro.empty()) + s << intro; + s << "[" << m << "," << n << "]=\n"; + + for (unsigned int i = 0; i < m; i++) { + s << " "; + for (unsigned int j = 0; j < n; j++) { + size_type p = values[i * n + j].find('.'); + s.setf(std::ios::right, std::ios::adjustfield); + s.width((std::streamsize)maxBefore); + s << values[i * n + j].substr(0, p).c_str(); + + if (maxAfter > 0) { + s.setf(std::ios::left, std::ios::adjustfield); + if (p != std::string::npos) { + s.width((std::streamsize)maxAfter); + s << values[i * n + j].substr(p, maxAfter).c_str(); + } + else { + s.width((std::streamsize)maxAfter); + s << ".0"; + } + } - return (int)(maxBefore + maxAfter); + s << ' '; + } + s << std::endl; } - /*! - Print using Matlab syntax, to copy/paste in Matlab later. + s.flags(original_flags); // restore s to standard state - The following code - \code + return (int)(maxBefore + maxAfter); + } + + /*! + Print using Matlab syntax, to copy/paste in Matlab later. + + The following code + \code #include int main() @@ -5741,14 +5684,14 @@ V ^\top}_ { n\times n } \f] \f[ std::cout << "M = "; M.matlabPrint(std::cout); } - \endcode - produces this output: - \code + \endcode + produces this output: + \code M = [ 0, 1, 2, ; 3, 4, 5, ] - \endcode - that could be copy/paste in Matlab: - \code + \endcode + that could be copy/paste in Matlab: + \code >> M = [ 0, 1, 2, ; 3, 4, 5, ] @@ -5758,30 +5701,30 @@ V ^\top}_ { n\times n } \f] \f[ 3 4 5 >> - \endcode - */ - std::ostream &vpMatrix::matlabPrint(std::ostream &os) const - { - os << "[ "; - for (unsigned int i = 0; i < this->getRows(); ++i) { - for (unsigned int j = 0; j < this->getCols(); ++j) { - os << (*this)[i][j] << ", "; - } - if (this->getRows() != i + 1) { - os << ";" << std::endl; - } - else { - os << "]" << std::endl; - } + \endcode + */ + std::ostream &vpMatrix::matlabPrint(std::ostream &os) const + { + os << "[ "; + for (unsigned int i = 0; i < this->getRows(); ++i) { + for (unsigned int j = 0; j < this->getCols(); ++j) { + os << (*this)[i][j] << ", "; + } + if (this->getRows() != i + 1) { + os << ";" << std::endl; + } + else { + os << "]" << std::endl; } - return os; } + return os; + } - /*! - Print using Maple syntax, to copy/paste in Maple later. + /*! + Print using Maple syntax, to copy/paste in Maple later. - The following code - \code + The following code + \code #include int main() @@ -5794,36 +5737,36 @@ V ^\top}_ { n\times n } \f] \f[ std::cout << "M = "; M.maplePrint(std::cout); } - \endcode - produces this output: - \code + \endcode + produces this output: + \code M = ([ [0, 1, 2, ], [3, 4, 5, ], ]) - \endcode - that could be copy/paste in Maple. + \endcode + that could be copy/paste in Maple. - */ - std::ostream &vpMatrix::maplePrint(std::ostream &os) const - { - os << "([ " << std::endl; - for (unsigned int i = 0; i < this->getRows(); ++i) { - os << "["; - for (unsigned int j = 0; j < this->getCols(); ++j) { - os << (*this)[i][j] << ", "; - } - os << "]," << std::endl; + */ + std::ostream &vpMatrix::maplePrint(std::ostream &os) const + { + os << "([ " << std::endl; + for (unsigned int i = 0; i < this->getRows(); ++i) { + os << "["; + for (unsigned int j = 0; j < this->getCols(); ++j) { + os << (*this)[i][j] << ", "; } - os << "])" << std::endl; - return os; + os << "]," << std::endl; } + os << "])" << std::endl; + return os; + } - /*! - Print/save a matrix in csv format. + /*! + Print/save a matrix in csv format. - The following code - \code + The following code + \code #include int main() @@ -5839,36 +5782,36 @@ V ^\top}_ { n\times n } \f] \f[ ofs.close(); } - \endcode - produces log.csv file that contains: - \code + \endcode + produces log.csv file that contains: + \code 0, 1, 2 3, 4, 5 - \endcode - */ - std::ostream &vpMatrix::csvPrint(std::ostream &os) const - { - for (unsigned int i = 0; i < this->getRows(); ++i) { - for (unsigned int j = 0; j < this->getCols(); ++j) { - os << (*this)[i][j]; - if (!(j == (this->getCols() - 1))) - os << ", "; - } - os << std::endl; + \endcode + */ + std::ostream &vpMatrix::csvPrint(std::ostream &os) const + { + for (unsigned int i = 0; i < this->getRows(); ++i) { + for (unsigned int j = 0; j < this->getCols(); ++j) { + os << (*this)[i][j]; + if (!(j == (this->getCols() - 1))) + os << ", "; } - return os; + os << std::endl; } + return os; + } - /*! - Print to be used as part of a C++ code later. + /*! + Print to be used as part of a C++ code later. - \param os : the stream to be printed in. - \param matrixName : name of the matrix, "A" by default. - \param octet : if false, print using double, if true, print byte per byte - each bytes of the double array. + \param os : the stream to be printed in. + \param matrixName : name of the matrix, "A" by default. + \param octet : if false, print using double, if true, print byte per byte + each bytes of the double array. - The following code shows how to use this function: - \code + The following code shows how to use this function: + \code #include int main() @@ -5881,9 +5824,9 @@ V ^\top}_ { n\times n } \f] \f[ M.cppPrint(std::cout, "M"); } - \endcode - It produces the following output that could be copy/paste in a C++ code: - \code + \endcode + It produces the following output that could be copy/paste in a C++ code: + \code vpMatrix M (2, 3); M[0][0] = 0; M[0][1] = 1; @@ -5892,56 +5835,55 @@ V ^\top}_ { n\times n } \f] \f[ M[1][0] = 3; M[1][1] = 4; M[1][2] = 5; - - \endcode - */ - std::ostream &vpMatrix::cppPrint(std::ostream &os, const std::string &matrixName, bool octet) const - { - os << "vpMatrix " << matrixName << " (" << this->getRows() << ", " << this->getCols() << "); " << std::endl; - - for (unsigned int i = 0; i < this->getRows(); ++i) { - for (unsigned int j = 0; j < this->getCols(); ++j) { - if (!octet) { - os << matrixName << "[" << i << "][" << j << "] = " << (*this)[i][j] << "; " << std::endl; - } - else { - for (unsigned int k = 0; k < sizeof(double); ++k) { - os << "((unsigned char*)&(" << matrixName << "[" << i << "][" << j << "]) )[" << k << "] = 0x" << std::hex - << (unsigned int)((unsigned char *)&((*this)[i][j]))[k] << "; " << std::endl; - } + \endcode + */ + std::ostream &vpMatrix::cppPrint(std::ostream &os, const std::string &matrixName, bool octet) const + { + os << "vpMatrix " << matrixName << " (" << this->getRows() << ", " << this->getCols() << "); " << std::endl; + + for (unsigned int i = 0; i < this->getRows(); ++i) { + for (unsigned int j = 0; j < this->getCols(); ++j) { + if (!octet) { + os << matrixName << "[" << i << "][" << j << "] = " << (*this)[i][j] << "; " << std::endl; + } + else { + for (unsigned int k = 0; k < sizeof(double); ++k) { + os << "((unsigned char*)&(" << matrixName << "[" << i << "][" << j << "]) )[" << k << "] = 0x" << std::hex + << (unsigned int)((unsigned char *)&((*this)[i][j]))[k] << "; " << std::endl; } } - os << std::endl; } - return os; + os << std::endl; } + return os; + } - /*! - Stack A at the end of the current matrix, or copy if the matrix has no - dimensions : this = [ this A ]^T. - */ - void vpMatrix::stack(const vpMatrix &A) - { - if (rowNum == 0) { - *this = A; + /*! + Stack A at the end of the current matrix, or copy if the matrix has no + dimensions : this = [ this A ]^T. + */ + void vpMatrix::stack(const vpMatrix &A) + { + if (rowNum == 0) { + *this = A; + } + else if (A.getRows() > 0) { + if (colNum != A.getCols()) { + throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx%d) matrix", rowNum, colNum, + A.getRows(), A.getCols())); } - else if (A.getRows() > 0) { - if (colNum != A.getCols()) { - throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx%d) matrix", rowNum, colNum, - A.getRows(), A.getCols())); - } - unsigned int rowNumOld = rowNum; - resize(rowNum + A.getRows(), colNum, false, false); - insert(A, rowNumOld, 0); - } + unsigned int rowNumOld = rowNum; + resize(rowNum + A.getRows(), colNum, false, false); + insert(A, rowNumOld, 0); } + } - /*! - Stack row vector \e r at the end of the current matrix, or copy if the + /*! + Stack row vector \e r at the end of the current matrix, or copy if the matrix has no dimensions: this = [ this r ]^T. - Here an example for a robot velocity log : + Here an example for a robot velocity log : \code vpMatrix A; vpColVector v(6); @@ -5951,37 +5893,37 @@ V ^\top}_ { n\times n } \f] \f[ Velocities.stack(v.t()); } \endcode - */ - void vpMatrix::stack(const vpRowVector &r) - { - if (rowNum == 0) { - *this = r; + */ + void vpMatrix::stack(const vpRowVector &r) + { + if (rowNum == 0) { + *this = r; + } + else { + if (colNum != r.getCols()) { + throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (1x%d) row vector", rowNum, + colNum, r.getCols())); } - else { - if (colNum != r.getCols()) { - throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (1x%d) row vector", rowNum, - colNum, r.getCols())); - } - if (r.size() == 0) { - return; - } + if (r.size() == 0) { + return; + } - unsigned int oldSize = size(); - resize(rowNum + 1, colNum, false, false); + unsigned int oldSize = size(); + resize(rowNum + 1, colNum, false, false); - if (data != nullptr && r.data != nullptr && data != r.data) { - // Copy r in data - memcpy(data + oldSize, r.data, sizeof(double) * r.size()); - } + if (data != nullptr && r.data != nullptr && data != r.data) { + // Copy r in data + memcpy(data + oldSize, r.data, sizeof(double) * r.size()); } } + } - /*! - Stack column vector \e c at the right of the current matrix, or copy if the + /*! + Stack column vector \e c at the right of the current matrix, or copy if the matrix has no dimensions: this = [ this c ]. - Here an example for a robot velocity log matrix: + Here an example for a robot velocity log matrix: \code vpMatrix log; vpColVector v(6); @@ -5992,76 +5934,76 @@ V ^\top}_ { n\times n } \f] \f[ } \endcode Here the log matrix has size 6 rows by 100 columns. - */ - void vpMatrix::stack(const vpColVector &c) - { - if (colNum == 0) { - *this = c; + */ + void vpMatrix::stack(const vpColVector &c) + { + if (colNum == 0) { + *this = c; + } + else { + if (rowNum != c.getRows()) { + throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx1) column vector", rowNum, + colNum, c.getRows())); } - else { - if (rowNum != c.getRows()) { - throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx1) column vector", rowNum, - colNum, c.getRows())); - } - if (c.size() == 0) { - return; - } + if (c.size() == 0) { + return; + } - vpMatrix tmp = *this; - unsigned int oldColNum = colNum; - resize(rowNum, colNum + 1, false, false); + vpMatrix tmp = *this; + unsigned int oldColNum = colNum; + resize(rowNum, colNum + 1, false, false); - if (data != nullptr && tmp.data != nullptr && data != tmp.data) { - // Copy c in data - for (unsigned int i = 0; i < rowNum; i++) { - memcpy(data + i * colNum, tmp.data + i * oldColNum, sizeof(double) * oldColNum); - rowPtrs[i][oldColNum] = c[i]; - } + if (data != nullptr && tmp.data != nullptr && data != tmp.data) { + // Copy c in data + for (unsigned int i = 0; i < rowNum; i++) { + memcpy(data + i * colNum, tmp.data + i * oldColNum, sizeof(double) * oldColNum); + rowPtrs[i][oldColNum] = c[i]; } } } + } - /*! - Insert matrix A at the given position in the current matrix. + /*! + Insert matrix A at the given position in the current matrix. - \warning Throw vpException::dimensionError if the - dimensions of the matrices do not allow the operation. + \warning Throw vpException::dimensionError if the + dimensions of the matrices do not allow the operation. - \param A : The matrix to insert. - \param r : The index of the row to begin to insert data. - \param c : The index of the column to begin to insert data. - */ - void vpMatrix::insert(const vpMatrix &A, unsigned int r, unsigned int c) - { - if ((r + A.getRows()) <= rowNum && (c + A.getCols()) <= colNum) { - if (A.colNum == colNum && data != nullptr && A.data != nullptr && A.data != data) { - memcpy(data + r * colNum, A.data, sizeof(double) * A.size()); - } - else if (data != nullptr && A.data != nullptr && A.data != data) { - for (unsigned int i = r; i < (r + A.getRows()); i++) { - memcpy(data + i * colNum + c, A.data + (i - r) * A.colNum, sizeof(double) * A.colNum); - } - } + \param A : The matrix to insert. + \param r : The index of the row to begin to insert data. + \param c : The index of the column to begin to insert data. + */ + void vpMatrix::insert(const vpMatrix &A, unsigned int r, unsigned int c) + { + if ((r + A.getRows()) <= rowNum && (c + A.getCols()) <= colNum) { + if (A.colNum == colNum && data != nullptr && A.data != nullptr && A.data != data) { + memcpy(data + r * colNum, A.data, sizeof(double) * A.size()); } - else { - throw vpException(vpException::dimensionError, "Cannot insert (%dx%d) matrix in (%dx%d) matrix at position (%d,%d)", - A.getRows(), A.getCols(), rowNum, colNum, r, c); + else if (data != nullptr && A.data != nullptr && A.data != data) { + for (unsigned int i = r; i < (r + A.getRows()); i++) { + memcpy(data + i * colNum + c, A.data + (i - r) * A.colNum, sizeof(double) * A.colNum); + } } } + else { + throw vpException(vpException::dimensionError, "Cannot insert (%dx%d) matrix in (%dx%d) matrix at position (%d,%d)", + A.getRows(), A.getCols(), rowNum, colNum, r, c); + } + } - /*! - Compute the eigenvalues of a n-by-n real symmetric matrix using - Lapack 3rd party. + /*! + Compute the eigenvalues of a n-by-n real symmetric matrix using + Lapack 3rd party. - \return The eigenvalues of a n-by-n real symmetric matrix, sorted in ascending order. + \return The eigenvalues of a n-by-n real symmetric matrix, sorted in ascending order. - \exception vpException::dimensionError If the matrix is not square. - \exception vpException::fatalError If the matrix is not symmetric. - \exception vpException::functionNotImplementedError If the Lapack 3rd party - is not detected. + \exception vpException::dimensionError If the matrix is not square. + \exception vpException::fatalError If the matrix is not symmetric. + \exception vpException::functionNotImplementedError If the Lapack 3rd party + is not detected. - Here an example: + Here an example: \code #include @@ -6083,95 +6025,95 @@ V ^\top}_ { n\times n } \f] \f[ } \endcode - \sa eigenValues(vpColVector &, vpMatrix &) + \sa eigenValues(vpColVector &, vpMatrix &) - */ - vpColVector vpMatrix::eigenValues() const - { - vpColVector evalue(rowNum); // Eigen values + */ + vpColVector vpMatrix::eigenValues() const + { + vpColVector evalue(rowNum); // Eigen values - if (rowNum != colNum) { - throw(vpException(vpException::dimensionError, "Cannot compute eigen values on a non square matrix (%dx%d)", rowNum, - colNum)); - } + if (rowNum != colNum) { + throw(vpException(vpException::dimensionError, "Cannot compute eigen values on a non square matrix (%dx%d)", rowNum, + colNum)); + } - // Check if the matrix is symmetric: At - A = 0 - vpMatrix At_A = (*this).t() - (*this); - for (unsigned int i = 0; i < rowNum; i++) { - for (unsigned int j = 0; j < rowNum; j++) { - // if (At_A[i][j] != 0) { - if (std::fabs(At_A[i][j]) > std::numeric_limits::epsilon()) { - throw(vpException(vpException::fatalError, "Cannot compute eigen values on a non symmetric matrix")); - } + // Check if the matrix is symmetric: At - A = 0 + vpMatrix At_A = (*this).t() - (*this); + for (unsigned int i = 0; i < rowNum; i++) { + for (unsigned int j = 0; j < rowNum; j++) { + // if (At_A[i][j] != 0) { + if (std::fabs(At_A[i][j]) > std::numeric_limits::epsilon()) { + throw(vpException(vpException::fatalError, "Cannot compute eigen values on a non symmetric matrix")); } } + } #if defined(VISP_HAVE_LAPACK) #if defined(VISP_HAVE_GSL) /* be careful of the copy below */ - { - gsl_vector *eval = gsl_vector_alloc(rowNum); - gsl_matrix *evec = gsl_matrix_alloc(rowNum, colNum); + { + gsl_vector *eval = gsl_vector_alloc(rowNum); + gsl_matrix *evec = gsl_matrix_alloc(rowNum, colNum); - gsl_eigen_symmv_workspace *w = gsl_eigen_symmv_alloc(rowNum); - gsl_matrix *m = gsl_matrix_alloc(rowNum, colNum); + gsl_eigen_symmv_workspace *w = gsl_eigen_symmv_alloc(rowNum); + gsl_matrix *m = gsl_matrix_alloc(rowNum, colNum); - unsigned int Atda = (unsigned int)m->tda; - for (unsigned int i = 0; i < rowNum; i++) { - unsigned int k = i * Atda; - for (unsigned int j = 0; j < colNum; j++) - m->data[k + j] = (*this)[i][j]; - } - gsl_eigen_symmv(m, eval, evec, w); - - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_ABS_ASC); + unsigned int Atda = (unsigned int)m->tda; + for (unsigned int i = 0; i < rowNum; i++) { + unsigned int k = i * Atda; + for (unsigned int j = 0; j < colNum; j++) + m->data[k + j] = (*this)[i][j]; + } + gsl_eigen_symmv(m, eval, evec, w); - for (unsigned int i = 0; i < rowNum; i++) { - evalue[i] = gsl_vector_get(eval, i); - } + gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_ABS_ASC); - gsl_eigen_symmv_free(w); - gsl_vector_free(eval); - gsl_matrix_free(m); - gsl_matrix_free(evec); + for (unsigned int i = 0; i < rowNum; i++) { + evalue[i] = gsl_vector_get(eval, i); } + + gsl_eigen_symmv_free(w); + gsl_vector_free(eval); + gsl_matrix_free(m); + gsl_matrix_free(evec); + } #else - { - const char jobz = 'N'; - const char uplo = 'U'; - vpMatrix A = (*this); - vpColVector WORK; - int lwork = -1; - int info = 0; - double wkopt; - vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, &wkopt, lwork, info); - lwork = static_cast(wkopt); - WORK.resize(lwork); - vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, WORK.data, lwork, info); - } + { + const char jobz = 'N'; + const char uplo = 'U'; + vpMatrix A = (*this); + vpColVector WORK; + int lwork = -1; + int info = 0; + double wkopt; + vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, &wkopt, lwork, info); + lwork = static_cast(wkopt); + WORK.resize(lwork); + vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, WORK.data, lwork, info); + } #endif #else - { - throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " - "You should install Lapack 3rd party")); - } -#endif - return evalue; + { + throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " + "You should install Lapack 3rd party")); } +#endif + return evalue; + } - /*! - Compute the eigenvalues of a n-by-n real symmetric matrix using - Lapack 3rd party. + /*! + Compute the eigenvalues of a n-by-n real symmetric matrix using + Lapack 3rd party. - \param evalue : Eigenvalues of the matrix, sorted in ascending order. + \param evalue : Eigenvalues of the matrix, sorted in ascending order. - \param evector : Corresponding eigenvectors of the matrix. + \param evector : Corresponding eigenvectors of the matrix. - \exception vpException::dimensionError If the matrix is not square. - \exception vpException::fatalError If the matrix is not symmetric. - \exception vpException::functionNotImplementedError If Lapack 3rd party is - not detected. + \exception vpException::dimensionError If the matrix is not square. + \exception vpException::fatalError If the matrix is not symmetric. + \exception vpException::functionNotImplementedError If Lapack 3rd party is + not detected. - Here an example: + Here an example: \code #include @@ -6206,297 +6148,297 @@ V ^\top}_ { n\times n } \f] \f[ \endcode \sa eigenValues() - */ - void vpMatrix::eigenValues(vpColVector &evalue, vpMatrix &evector) const - { - if (rowNum != colNum) { - throw(vpException(vpException::dimensionError, "Cannot compute eigen values on a non square matrix (%dx%d)", rowNum, - colNum)); - } + */ + void vpMatrix::eigenValues(vpColVector &evalue, vpMatrix &evector) const + { + if (rowNum != colNum) { + throw(vpException(vpException::dimensionError, "Cannot compute eigen values on a non square matrix (%dx%d)", rowNum, + colNum)); + } - // Check if the matrix is symmetric: At - A = 0 - vpMatrix At_A = (*this).t() - (*this); - for (unsigned int i = 0; i < rowNum; i++) { - for (unsigned int j = 0; j < rowNum; j++) { - // if (At_A[i][j] != 0) { - if (std::fabs(At_A[i][j]) > std::numeric_limits::epsilon()) { - throw(vpException(vpException::fatalError, "Cannot compute eigen values on a non symmetric matrix")); - } + // Check if the matrix is symmetric: At - A = 0 + vpMatrix At_A = (*this).t() - (*this); + for (unsigned int i = 0; i < rowNum; i++) { + for (unsigned int j = 0; j < rowNum; j++) { + // if (At_A[i][j] != 0) { + if (std::fabs(At_A[i][j]) > std::numeric_limits::epsilon()) { + throw(vpException(vpException::fatalError, "Cannot compute eigen values on a non symmetric matrix")); } } + } - // Resize the output matrices - evalue.resize(rowNum); - evector.resize(rowNum, colNum); + // Resize the output matrices + evalue.resize(rowNum); + evector.resize(rowNum, colNum); #if defined(VISP_HAVE_LAPACK) #if defined(VISP_HAVE_GSL) /* be careful of the copy below */ - { - gsl_vector *eval = gsl_vector_alloc(rowNum); - gsl_matrix *evec = gsl_matrix_alloc(rowNum, colNum); + { + gsl_vector *eval = gsl_vector_alloc(rowNum); + gsl_matrix *evec = gsl_matrix_alloc(rowNum, colNum); - gsl_eigen_symmv_workspace *w = gsl_eigen_symmv_alloc(rowNum); - gsl_matrix *m = gsl_matrix_alloc(rowNum, colNum); + gsl_eigen_symmv_workspace *w = gsl_eigen_symmv_alloc(rowNum); + gsl_matrix *m = gsl_matrix_alloc(rowNum, colNum); - unsigned int Atda = (unsigned int)m->tda; - for (unsigned int i = 0; i < rowNum; i++) { - unsigned int k = i * Atda; - for (unsigned int j = 0; j < colNum; j++) - m->data[k + j] = (*this)[i][j]; - } - gsl_eigen_symmv(m, eval, evec, w); + unsigned int Atda = (unsigned int)m->tda; + for (unsigned int i = 0; i < rowNum; i++) { + unsigned int k = i * Atda; + for (unsigned int j = 0; j < colNum; j++) + m->data[k + j] = (*this)[i][j]; + } + gsl_eigen_symmv(m, eval, evec, w); - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_ABS_ASC); + gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_ABS_ASC); - for (unsigned int i = 0; i < rowNum; i++) { - evalue[i] = gsl_vector_get(eval, i); - } - Atda = (unsigned int)evec->tda; - for (unsigned int i = 0; i < rowNum; i++) { - unsigned int k = i * Atda; - for (unsigned int j = 0; j < rowNum; j++) { - evector[i][j] = evec->data[k + j]; - } + for (unsigned int i = 0; i < rowNum; i++) { + evalue[i] = gsl_vector_get(eval, i); + } + Atda = (unsigned int)evec->tda; + for (unsigned int i = 0; i < rowNum; i++) { + unsigned int k = i * Atda; + for (unsigned int j = 0; j < rowNum; j++) { + evector[i][j] = evec->data[k + j]; } - - gsl_eigen_symmv_free(w); - gsl_vector_free(eval); - gsl_matrix_free(m); - gsl_matrix_free(evec); } + + gsl_eigen_symmv_free(w); + gsl_vector_free(eval); + gsl_matrix_free(m); + gsl_matrix_free(evec); + } #else // defined(VISP_HAVE_GSL) - { - const char jobz = 'V'; - const char uplo = 'U'; - vpMatrix A = (*this); - vpColVector WORK; - int lwork = -1; - int info = 0; - double wkopt; - vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, &wkopt, lwork, info); - lwork = static_cast(wkopt); - WORK.resize(lwork); - vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, WORK.data, lwork, info); - evector = A.t(); - } + { + const char jobz = 'V'; + const char uplo = 'U'; + vpMatrix A = (*this); + vpColVector WORK; + int lwork = -1; + int info = 0; + double wkopt; + vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, &wkopt, lwork, info); + lwork = static_cast(wkopt); + WORK.resize(lwork); + vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, WORK.data, lwork, info); + evector = A.t(); + } #endif // defined(VISP_HAVE_GSL) #else - { - throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " - "You should install Lapack 3rd party")); - } -#endif - } - - /*! - Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf - A\f$. - - The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) - = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. - - \param kerAt: The matrix that contains the null space (kernel) of \f$\bf - A\f$ defined by the matrix \f${\bf X}^T\f$. If matrix \f$\bf A\f$ is full - rank, the dimension of \c kerAt is (0, n), otherwise the dimension is (n-r, - n). This matrix is thus the transpose of \f$\mbox{Ker}({\bf A})\f$. - - \param svThreshold: Threshold used to test the singular values. If - a singular value is lower than this threshold we consider that the - matrix is not full rank. - - \return The rank of the matrix. - */ - unsigned int vpMatrix::kernel(vpMatrix &kerAt, double svThreshold) const { - unsigned int nbline = getRows(); - unsigned int nbcol = getCols(); + throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " + "You should install Lapack 3rd party")); + } +#endif + } - vpMatrix U, V; // Copy of the matrix, SVD function is destructive - vpColVector sv; - sv.resize(nbcol, false); // singular values - V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + /*! + Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf + A\f$. - // Copy and resize matrix to have at least as many rows as columns - // kernel is computed in svd method only if the matrix has more rows than - // columns + The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) + = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. - if (nbline < nbcol) - U.resize(nbcol, nbcol, true); - else - U.resize(nbline, nbcol, false); + \param kerAt: The matrix that contains the null space (kernel) of \f$\bf + A\f$ defined by the matrix \f${\bf X}^T\f$. If matrix \f$\bf A\f$ is full + rank, the dimension of \c kerAt is (0, n), otherwise the dimension is (n-r, + n). This matrix is thus the transpose of \f$\mbox{Ker}({\bf A})\f$. - U.insert(*this, 0, 0); + \param svThreshold: Threshold used to test the singular values. If + a singular value is lower than this threshold we consider that the + matrix is not full rank. - U.svd(sv, V); - - // Compute the highest singular value and rank of the matrix - double maxsv = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv) { - maxsv = sv[i]; - } + \return The rank of the matrix. + */ + unsigned int vpMatrix::kernel(vpMatrix &kerAt, double svThreshold) const + { + unsigned int nbline = getRows(); + unsigned int nbcol = getCols(); + + vpMatrix U, V; // Copy of the matrix, SVD function is destructive + vpColVector sv; + sv.resize(nbcol, false); // singular values + V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + + // Copy and resize matrix to have at least as many rows as columns + // kernel is computed in svd method only if the matrix has more rows than + // columns + + if (nbline < nbcol) + U.resize(nbcol, nbcol, true); + else + U.resize(nbline, nbcol, false); + + U.insert(*this, 0, 0); + + U.svd(sv, V); + + // Compute the highest singular value and rank of the matrix + double maxsv = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv) { + maxsv = sv[i]; } + } - unsigned int rank = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv * svThreshold) { - rank++; - } + unsigned int rank = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv * svThreshold) { + rank++; } + } - kerAt.resize(nbcol - rank, nbcol); - if (rank != nbcol) { - for (unsigned int j = 0, k = 0; j < nbcol; j++) { - // if( v.col(j) in kernel and non zero ) - if ((sv[j] <= maxsv * svThreshold) && - (std::fabs(V.getCol(j).sumSquare()) > std::numeric_limits::epsilon())) { - for (unsigned int i = 0; i < V.getRows(); i++) { - kerAt[k][i] = V[i][j]; - } - k++; + kerAt.resize(nbcol - rank, nbcol); + if (rank != nbcol) { + for (unsigned int j = 0, k = 0; j < nbcol; j++) { + // if( v.col(j) in kernel and non zero ) + if ((sv[j] <= maxsv * svThreshold) && + (std::fabs(V.getCol(j).sumSquare()) > std::numeric_limits::epsilon())) { + for (unsigned int i = 0; i < V.getRows(); i++) { + kerAt[k][i] = V[i][j]; } + k++; } } - - return rank; } - /*! - Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf - A\f$. + return rank; + } - The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) - = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. + /*! + Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf + A\f$. - \param kerA: The matrix that contains the null space (kernel) of \f$\bf - A\f$. If matrix \f$\bf A\f$ is full rank, the dimension of \c kerA is (n, 0), - otherwise its dimension is (n, n-r). + The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) + = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. - \param svThreshold: Threshold used to test the singular values. The dimension - of kerA corresponds to the number of singular values lower than this threshold + \param kerA: The matrix that contains the null space (kernel) of \f$\bf + A\f$. If matrix \f$\bf A\f$ is full rank, the dimension of \c kerA is (n, 0), + otherwise its dimension is (n, n-r). - \return The dimension of the nullspace, that is \f$ n - r \f$. - */ - unsigned int vpMatrix::nullSpace(vpMatrix &kerA, double svThreshold) const - { - unsigned int nbrow = getRows(); - unsigned int nbcol = getCols(); + \param svThreshold: Threshold used to test the singular values. The dimension + of kerA corresponds to the number of singular values lower than this threshold - vpMatrix U, V; // Copy of the matrix, SVD function is destructive - vpColVector sv; - sv.resize(nbcol, false); // singular values - V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + \return The dimension of the nullspace, that is \f$ n - r \f$. + */ + unsigned int vpMatrix::nullSpace(vpMatrix &kerA, double svThreshold) const + { + unsigned int nbrow = getRows(); + unsigned int nbcol = getCols(); - // Copy and resize matrix to have at least as many rows as columns - // kernel is computed in svd method only if the matrix has more rows than - // columns + vpMatrix U, V; // Copy of the matrix, SVD function is destructive + vpColVector sv; + sv.resize(nbcol, false); // singular values + V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition - if (nbrow < nbcol) - U.resize(nbcol, nbcol, true); - else - U.resize(nbrow, nbcol, false); + // Copy and resize matrix to have at least as many rows as columns + // kernel is computed in svd method only if the matrix has more rows than + // columns - U.insert(*this, 0, 0); + if (nbrow < nbcol) + U.resize(nbcol, nbcol, true); + else + U.resize(nbrow, nbcol, false); - U.svd(sv, V); + U.insert(*this, 0, 0); - // Compute the highest singular value and rank of the matrix - double maxsv = sv[0]; + U.svd(sv, V); - unsigned int rank = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv * svThreshold) { - rank++; - } + // Compute the highest singular value and rank of the matrix + double maxsv = sv[0]; + + unsigned int rank = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv * svThreshold) { + rank++; } + } - kerA.resize(nbcol, nbcol - rank); - if (rank != nbcol) { - for (unsigned int j = 0, k = 0; j < nbcol; j++) { - // if( v.col(j) in kernel and non zero ) - if (sv[j] <= maxsv * svThreshold) { - for (unsigned int i = 0; i < nbcol; i++) { - kerA[i][k] = V[i][j]; - } - k++; + kerA.resize(nbcol, nbcol - rank); + if (rank != nbcol) { + for (unsigned int j = 0, k = 0; j < nbcol; j++) { + // if( v.col(j) in kernel and non zero ) + if (sv[j] <= maxsv * svThreshold) { + for (unsigned int i = 0; i < nbcol; i++) { + kerA[i][k] = V[i][j]; } + k++; } } - - return (nbcol - rank); } - /*! - Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf - A\f$. - - The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) - = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. - - \param kerA: The matrix that contains the null space (kernel) of \f$\bf - A\f$. If matrix \f$\bf A\f$ is full rank, the dimension of \c kerA is (n, 0), - otherwise its dimension is (n, n-r). - - \param dim: the dimension of the null space when it is known a priori - - \return The estimated dimension of the nullspace, that is \f$ n - r \f$, by - using 1e-6 as threshold for the sigular values. - */ - unsigned int vpMatrix::nullSpace(vpMatrix &kerA, int dim) const - { - unsigned int nbrow = getRows(); - unsigned int nbcol = getCols(); - unsigned int dim_ = static_cast(dim); - - vpMatrix U, V; // Copy of the matrix, SVD function is destructive - vpColVector sv; - sv.resize(nbcol, false); // singular values - V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + return (nbcol - rank); + } - // Copy and resize matrix to have at least as many rows as columns - // kernel is computed in svd method only if the matrix has more rows than - // columns + /*! + Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf + A\f$. - if (nbrow < nbcol) - U.resize(nbcol, nbcol, true); - else - U.resize(nbrow, nbcol, false); + The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) + = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. - U.insert(*this, 0, 0); + \param kerA: The matrix that contains the null space (kernel) of \f$\bf + A\f$. If matrix \f$\bf A\f$ is full rank, the dimension of \c kerA is (n, 0), + otherwise its dimension is (n, n-r). - U.svd(sv, V); + \param dim: the dimension of the null space when it is known a priori - kerA.resize(nbcol, dim_); - if (dim_ != 0) { - unsigned int rank = nbcol - dim_; - for (unsigned int k = 0; k < dim_; k++) { - unsigned int j = k + rank; - for (unsigned int i = 0; i < nbcol; i++) { - kerA[i][k] = V[i][j]; - } + \return The estimated dimension of the nullspace, that is \f$ n - r \f$, by + using 1e-6 as threshold for the sigular values. + */ + unsigned int vpMatrix::nullSpace(vpMatrix &kerA, int dim) const + { + unsigned int nbrow = getRows(); + unsigned int nbcol = getCols(); + unsigned int dim_ = static_cast(dim); + + vpMatrix U, V; // Copy of the matrix, SVD function is destructive + vpColVector sv; + sv.resize(nbcol, false); // singular values + V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + + // Copy and resize matrix to have at least as many rows as columns + // kernel is computed in svd method only if the matrix has more rows than + // columns + + if (nbrow < nbcol) + U.resize(nbcol, nbcol, true); + else + U.resize(nbrow, nbcol, false); + + U.insert(*this, 0, 0); + + U.svd(sv, V); + + kerA.resize(nbcol, dim_); + if (dim_ != 0) { + unsigned int rank = nbcol - dim_; + for (unsigned int k = 0; k < dim_; k++) { + unsigned int j = k + rank; + for (unsigned int i = 0; i < nbcol; i++) { + kerA[i][k] = V[i][j]; } } + } - double maxsv = sv[0]; - unsigned int rank = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv * 1e-6) { - rank++; - } + double maxsv = sv[0]; + unsigned int rank = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv * 1e-6) { + rank++; } - return (nbcol - rank); } + return (nbcol - rank); + } - /*! - Compute the determinant of a n-by-n matrix. + /*! + Compute the determinant of a n-by-n matrix. - \param method : Method used to compute the determinant. Default LU - decomposition method is faster than the method based on Gaussian - elimination. + \param method : Method used to compute the determinant. Default LU + decomposition method is faster than the method based on Gaussian + elimination. - \return Determinant of the matrix. + \return Determinant of the matrix. - \code + \code #include #include @@ -6517,112 +6459,112 @@ V ^\top}_ { n\times n } \f] \f[ std:: cout << "Determinant by LU decomposition (Eigen3): " << A.detByLUEigen3() << std::endl; } \endcode - */ - double vpMatrix::det(vpDetMethod method) const - { - double det = 0.; - - if (method == LU_DECOMPOSITION) { - det = this->detByLU(); - } + */ + double vpMatrix::det(vpDetMethod method) const + { + double det = 0.; - return (det); + if (method == LU_DECOMPOSITION) { + det = this->detByLU(); } - /*! + return (det); + } - Compute the exponential matrix of a square matrix. + /*! - \return Return the exponential matrix. + Compute the exponential matrix of a square matrix. - */ - vpMatrix vpMatrix::expm() const - { - if (colNum != rowNum) { - throw(vpException(vpException::dimensionError, "Cannot compute the exponential of a non square (%dx%d) matrix", - rowNum, colNum)); - } - else { + \return Return the exponential matrix. + + */ + vpMatrix vpMatrix::expm() const + { + if (colNum != rowNum) { + throw(vpException(vpException::dimensionError, "Cannot compute the exponential of a non square (%dx%d) matrix", + rowNum, colNum)); + } + else { #ifdef VISP_HAVE_GSL - size_t size_ = rowNum * colNum; - double *b = new double[size_]; - for (size_t i = 0; i < size_; i++) - b[i] = 0.; - gsl_matrix_view m = gsl_matrix_view_array(this->data, rowNum, colNum); - gsl_matrix_view em = gsl_matrix_view_array(b, rowNum, colNum); - gsl_linalg_exponential_ss(&m.matrix, &em.matrix, 0); - // gsl_matrix_fprintf(stdout, &em.matrix, "%g"); - vpMatrix expA; - expA.resize(rowNum, colNum, false); - memcpy(expA.data, b, size_ * sizeof(double)); - - delete[] b; - return expA; + size_t size_ = rowNum * colNum; + double *b = new double[size_]; + for (size_t i = 0; i < size_; i++) + b[i] = 0.; + gsl_matrix_view m = gsl_matrix_view_array(this->data, rowNum, colNum); + gsl_matrix_view em = gsl_matrix_view_array(b, rowNum, colNum); + gsl_linalg_exponential_ss(&m.matrix, &em.matrix, 0); + // gsl_matrix_fprintf(stdout, &em.matrix, "%g"); + vpMatrix expA; + expA.resize(rowNum, colNum, false); + memcpy(expA.data, b, size_ * sizeof(double)); + + delete[] b; + return expA; #else - vpMatrix _expE(rowNum, colNum, false); - vpMatrix _expD(rowNum, colNum, false); - vpMatrix _expX(rowNum, colNum, false); - vpMatrix _expcX(rowNum, colNum, false); - vpMatrix _eye(rowNum, colNum, false); - - _eye.eye(); - vpMatrix exp(*this); - - // double f; - int e; - double c = 0.5; - int q = 6; - int p = 1; - - double nA = 0; - for (unsigned int i = 0; i < rowNum; i++) { - double sum = 0; - for (unsigned int j = 0; j < colNum; j++) { - sum += fabs((*this)[i][j]); - } - if (sum > nA || i == 0) { - nA = sum; - } - } - - /* f = */ frexp(nA, &e); - // double s = (0 > e+1)?0:e+1; - double s = e + 1; - - double sca = 1.0 / pow(2.0, s); - exp = sca * exp; - _expX = *this; - _expE = c * exp + _eye; - _expD = -c * exp + _eye; - for (int k = 2; k <= q; k++) { - c = c * ((double)(q - k + 1)) / ((double)(k * (2 * q - k + 1))); - _expcX = exp * _expX; - _expX = _expcX; - _expcX = c * _expX; - _expE = _expE + _expcX; - if (p) - _expD = _expD + _expcX; - else - _expD = _expD - _expcX; - p = !p; + vpMatrix _expE(rowNum, colNum, false); + vpMatrix _expD(rowNum, colNum, false); + vpMatrix _expX(rowNum, colNum, false); + vpMatrix _expcX(rowNum, colNum, false); + vpMatrix _eye(rowNum, colNum, false); + + _eye.eye(); + vpMatrix exp(*this); + + // double f; + int e; + double c = 0.5; + int q = 6; + int p = 1; + + double nA = 0; + for (unsigned int i = 0; i < rowNum; i++) { + double sum = 0; + for (unsigned int j = 0; j < colNum; j++) { + sum += fabs((*this)[i][j]); } - _expX = _expD.inverseByLU(); - exp = _expX * _expE; - for (int k = 1; k <= s; k++) { - _expE = exp * exp; - exp = _expE; + if (sum > nA || i == 0) { + nA = sum; } - return exp; -#endif } + + /* f = */ frexp(nA, &e); + // double s = (0 > e+1)?0:e+1; + double s = e + 1; + + double sca = 1.0 / pow(2.0, s); + exp = sca * exp; + _expX = *this; + _expE = c * exp + _eye; + _expD = -c * exp + _eye; + for (int k = 2; k <= q; k++) { + c = c * ((double)(q - k + 1)) / ((double)(k * (2 * q - k + 1))); + _expcX = exp * _expX; + _expX = _expcX; + _expcX = c * _expX; + _expE = _expE + _expcX; + if (p) + _expD = _expD + _expcX; + else + _expD = _expD - _expcX; + p = !p; + } + _expX = _expD.inverseByLU(); + exp = _expX * _expE; + for (int k = 1; k <= s; k++) { + _expE = exp * exp; + exp = _expE; + } + return exp; +#endif } + } - /**************************************************************************************************************/ - /**************************************************************************************************************/ + /**************************************************************************************************************/ + /**************************************************************************************************************/ - // Specific functions + // Specific functions - /* + /* input:: matrix M(nCols,nRows), nCols > 3, nRows > 3 , nCols == nRows. output:: the complement matrix of the element (rowNo,colNo). @@ -6635,212 +6577,212 @@ V ^\top}_ { n\times n } \f] \f[ 7 8 9 1 3 subblock(M, 1, 1) give the matrix 7 9 - */ - vpMatrix subblock(const vpMatrix &M, unsigned int col, unsigned int row) - { - vpMatrix M_comp; - M_comp.resize(M.getRows() - 1, M.getCols() - 1, false); - - for (unsigned int i = 0; i < col; i++) { - for (unsigned int j = 0; j < row; j++) - M_comp[i][j] = M[i][j]; - for (unsigned int j = row + 1; j < M.getRows(); j++) - M_comp[i][j - 1] = M[i][j]; - } - for (unsigned int i = col + 1; i < M.getCols(); i++) { - for (unsigned int j = 0; j < row; j++) - M_comp[i - 1][j] = M[i][j]; - for (unsigned int j = row + 1; j < M.getRows(); j++) - M_comp[i - 1][j - 1] = M[i][j]; - } - return M_comp; + */ + vpMatrix subblock(const vpMatrix &M, unsigned int col, unsigned int row) + { + vpMatrix M_comp; + M_comp.resize(M.getRows() - 1, M.getCols() - 1, false); + + for (unsigned int i = 0; i < col; i++) { + for (unsigned int j = 0; j < row; j++) + M_comp[i][j] = M[i][j]; + for (unsigned int j = row + 1; j < M.getRows(); j++) + M_comp[i][j - 1] = M[i][j]; } + for (unsigned int i = col + 1; i < M.getCols(); i++) { + for (unsigned int j = 0; j < row; j++) + M_comp[i - 1][j] = M[i][j]; + for (unsigned int j = row + 1; j < M.getRows(); j++) + M_comp[i - 1][j - 1] = M[i][j]; + } + return M_comp; + } - /*! - \return The condition number, the ratio of the largest singular value of - the matrix to the smallest. - - \param svThreshold: Threshold used to test the singular values. If - a singular value is lower than this threshold we consider that the - matrix is not full rank. + /*! + \return The condition number, the ratio of the largest singular value of + the matrix to the smallest. - */ - double vpMatrix::cond(double svThreshold) const - { - unsigned int nbline = getRows(); - unsigned int nbcol = getCols(); + \param svThreshold: Threshold used to test the singular values. If + a singular value is lower than this threshold we consider that the + matrix is not full rank. - vpMatrix U, V; // Copy of the matrix, SVD function is destructive - vpColVector sv; - sv.resize(nbcol); // singular values - V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + */ + double vpMatrix::cond(double svThreshold) const + { + unsigned int nbline = getRows(); + unsigned int nbcol = getCols(); - // Copy and resize matrix to have at least as many rows as columns - // kernel is computed in svd method only if the matrix has more rows than - // columns + vpMatrix U, V; // Copy of the matrix, SVD function is destructive + vpColVector sv; + sv.resize(nbcol); // singular values + V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition - if (nbline < nbcol) - U.resize(nbcol, nbcol, true); - else - U.resize(nbline, nbcol, false); + // Copy and resize matrix to have at least as many rows as columns + // kernel is computed in svd method only if the matrix has more rows than + // columns - U.insert(*this, 0, 0); + if (nbline < nbcol) + U.resize(nbcol, nbcol, true); + else + U.resize(nbline, nbcol, false); - U.svd(sv, V); + U.insert(*this, 0, 0); - // Compute the highest singular value - double maxsv = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv) { - maxsv = sv[i]; - } - } + U.svd(sv, V); - // Compute the rank of the matrix - unsigned int rank = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv * svThreshold) { - rank++; - } + // Compute the highest singular value + double maxsv = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv) { + maxsv = sv[i]; } + } - // Compute the lowest singular value - double minsv = maxsv; - for (unsigned int i = 0; i < rank; i++) { - if (sv[i] < minsv) { - minsv = sv[i]; - } + // Compute the rank of the matrix + unsigned int rank = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv * svThreshold) { + rank++; } + } - if (std::fabs(minsv) > std::numeric_limits::epsilon()) { - return maxsv / minsv; - } - else { - return std::numeric_limits::infinity(); + // Compute the lowest singular value + double minsv = maxsv; + for (unsigned int i = 0; i < rank; i++) { + if (sv[i] < minsv) { + minsv = sv[i]; } } - /*! - Compute \f${\bf H} + \alpha * diag({\bf H})\f$ - \param H : input Matrix \f${\bf H}\f$. This matrix should be square. - \param alpha : Scalar \f$\alpha\f$ - \param HLM : Resulting operation. - */ - void vpMatrix::computeHLM(const vpMatrix &H, const double &alpha, vpMatrix &HLM) - { - if (H.getCols() != H.getRows()) { - throw(vpException(vpException::dimensionError, "Cannot compute HLM on a non square matrix (%dx%d)", H.getRows(), - H.getCols())); - } + if (std::fabs(minsv) > std::numeric_limits::epsilon()) { + return maxsv / minsv; + } + else { + return std::numeric_limits::infinity(); + } + } - HLM = H; - for (unsigned int i = 0; i < H.getCols(); i++) { - HLM[i][i] += alpha * H[i][i]; - } + /*! + Compute \f${\bf H} + \alpha * diag({\bf H})\f$ + \param H : input Matrix \f${\bf H}\f$. This matrix should be square. + \param alpha : Scalar \f$\alpha\f$ + \param HLM : Resulting operation. + */ + void vpMatrix::computeHLM(const vpMatrix &H, const double &alpha, vpMatrix &HLM) + { + if (H.getCols() != H.getRows()) { + throw(vpException(vpException::dimensionError, "Cannot compute HLM on a non square matrix (%dx%d)", H.getRows(), + H.getCols())); } - /*! - Compute and return the Frobenius norm (also called Euclidean norm) \f$||A|| = \sqrt{ \sum{A_{ij}^2}}\f$. + HLM = H; + for (unsigned int i = 0; i < H.getCols(); i++) { + HLM[i][i] += alpha * H[i][i]; + } + } - \return The Frobenius norm (also called Euclidean norm) if the matrix is initialized, 0 otherwise. + /*! + Compute and return the Frobenius norm (also called Euclidean norm) \f$||A|| = \sqrt{ \sum{A_{ij}^2}}\f$. - \sa infinityNorm(), inducedL2Norm() - */ - double vpMatrix::frobeniusNorm() const - { - double norm = 0.0; - for (unsigned int i = 0; i < dsize; i++) { - double x = *(data + i); - norm += x * x; - } + \return The Frobenius norm (also called Euclidean norm) if the matrix is initialized, 0 otherwise. - return sqrt(norm); + \sa infinityNorm(), inducedL2Norm() + */ + double vpMatrix::frobeniusNorm() const + { + double norm = 0.0; + for (unsigned int i = 0; i < dsize; i++) { + double x = *(data + i); + norm += x * x; } - /*! - Compute and return the induced L2 norm \f$||A|| = \Sigma_{max}(A)\f$ which is equal to - the maximum singular value of the matrix. + return sqrt(norm); + } - \return The induced L2 norm if the matrix is initialized, 0 otherwise. + /*! + Compute and return the induced L2 norm \f$||A|| = \Sigma_{max}(A)\f$ which is equal to + the maximum singular value of the matrix. - \sa infinityNorm(), frobeniusNorm() - */ - double vpMatrix::inducedL2Norm() const - { - if (this->dsize != 0) { - vpMatrix v; - vpColVector w; - - vpMatrix M = *this; - - M.svd(w, v); - - double max = w[0]; - unsigned int maxRank = std::min(this->getCols(), this->getRows()); - // The maximum reachable rank is either the number of columns or the number of rows - // of the matrix. - unsigned int boundary = std::min(maxRank, w.size()); - // boundary is here to ensure that the number of singular values used for the com- - // putation of the euclidean norm of the matrix is not greater than the maximum - // reachable rank. Indeed, some svd library pad the singular values vector with 0s - // if the input matrix is non-square. - for (unsigned int i = 0; i < boundary; i++) { - if (max < w[i]) { - max = w[i]; - } + \return The induced L2 norm if the matrix is initialized, 0 otherwise. + + \sa infinityNorm(), frobeniusNorm() + */ + double vpMatrix::inducedL2Norm() const + { + if (this->dsize != 0) { + vpMatrix v; + vpColVector w; + + vpMatrix M = *this; + + M.svd(w, v); + + double max = w[0]; + unsigned int maxRank = std::min(this->getCols(), this->getRows()); + // The maximum reachable rank is either the number of columns or the number of rows + // of the matrix. + unsigned int boundary = std::min(maxRank, w.size()); + // boundary is here to ensure that the number of singular values used for the com- + // putation of the euclidean norm of the matrix is not greater than the maximum + // reachable rank. Indeed, some svd library pad the singular values vector with 0s + // if the input matrix is non-square. + for (unsigned int i = 0; i < boundary; i++) { + if (max < w[i]) { + max = w[i]; } - return max; - } - else { - return 0.; } + return max; + } + else { + return 0.; } + } - /*! + /*! - Compute and return the infinity norm \f$ {||A||}_{\infty} = - max\left(\sum_{j=0}^{n}{\mid A_{ij} \mid}\right) \f$ with \f$i \in - \{0, ..., m\}\f$ where \f$(m,n)\f$ is the matrix size. + Compute and return the infinity norm \f$ {||A||}_{\infty} = + max\left(\sum_{j=0}^{n}{\mid A_{ij} \mid}\right) \f$ with \f$i \in + \{0, ..., m\}\f$ where \f$(m,n)\f$ is the matrix size. - \return The infinity norm if the matrix is initialized, 0 otherwise. + \return The infinity norm if the matrix is initialized, 0 otherwise. - \sa frobeniusNorm(), inducedL2Norm() - */ - double vpMatrix::infinityNorm() const - { - double norm = 0.0; - for (unsigned int i = 0; i < rowNum; i++) { - double x = 0; - for (unsigned int j = 0; j < colNum; j++) { - x += fabs(*(*(rowPtrs + i) + j)); - } - if (x > norm) { - norm = x; - } + \sa frobeniusNorm(), inducedL2Norm() + */ + double vpMatrix::infinityNorm() const + { + double norm = 0.0; + for (unsigned int i = 0; i < rowNum; i++) { + double x = 0; + for (unsigned int j = 0; j < colNum; j++) { + x += fabs(*(*(rowPtrs + i) + j)); + } + if (x > norm) { + norm = x; } - return norm; } + return norm; + } - /*! - Return the sum square of all the \f$A_{ij}\f$ elements of the matrix \f$A(m, - n)\f$. + /*! + Return the sum square of all the \f$A_{ij}\f$ elements of the matrix \f$A(m, + n)\f$. - \return The value \f$\sum A_{ij}^{2}\f$. - */ - double vpMatrix::sumSquare() const - { - double sum_square = 0.0; - double x; + \return The value \f$\sum A_{ij}^{2}\f$. + */ + double vpMatrix::sumSquare() const + { + double sum_square = 0.0; + double x; - for (unsigned int i = 0; i < rowNum; i++) { - for (unsigned int j = 0; j < colNum; j++) { - x = rowPtrs[i][j]; - sum_square += x * x; - } + for (unsigned int i = 0; i < rowNum; i++) { + for (unsigned int j = 0; j < colNum; j++) { + x = rowPtrs[i][j]; + sum_square += x * x; } - - return sum_square; } + + return sum_square; + } #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) /*! \deprecated This function is deprecated. You should rather use frobeniusNorm(). @@ -6851,89 +6793,89 @@ V ^\top}_ { n\times n } \f] \f[ \sa frobeniusNorm(), infinityNorm(), inducedL2Norm() */ - double vpMatrix::euclideanNorm() const { return frobeniusNorm(); } + double vpMatrix::euclideanNorm() const { return frobeniusNorm(); } - vpMatrix vpMatrix::stackMatrices(const vpColVector &A, const vpColVector &B) - { - return (vpMatrix)(vpColVector::stack(A, B)); - } + vpMatrix vpMatrix::stackMatrices(const vpColVector &A, const vpColVector &B) + { + return (vpMatrix)(vpColVector::stack(A, B)); + } - void vpMatrix::stackMatrices(const vpColVector &A, const vpColVector &B, vpColVector &C) - { - vpColVector::stack(A, B, C); - } + void vpMatrix::stackMatrices(const vpColVector &A, const vpColVector &B, vpColVector &C) + { + vpColVector::stack(A, B, C); + } - vpMatrix vpMatrix::stackMatrices(const vpMatrix &A, const vpRowVector &B) { return vpMatrix::stack(A, B); } + vpMatrix vpMatrix::stackMatrices(const vpMatrix &A, const vpRowVector &B) { return vpMatrix::stack(A, B); } - void vpMatrix::stackMatrices(const vpMatrix &A, const vpRowVector &B, vpMatrix &C) { vpMatrix::stack(A, B, C); } + void vpMatrix::stackMatrices(const vpMatrix &A, const vpRowVector &B, vpMatrix &C) { vpMatrix::stack(A, B, C); } - /*! - \deprecated This method is deprecated. You should rather use getRow(). - More precisely, the following code: - \code - vpMatrix L; - unsigned int row_index = ...; - ... = L.row(row_index); - \endcode - should be replaced with: - \code - ... = L.getRow(row_index - 1); - \endcode + /*! + \deprecated This method is deprecated. You should rather use getRow(). + More precisely, the following code: + \code + vpMatrix L; + unsigned int row_index = ...; + ... = L.row(row_index); + \endcode + should be replaced with: + \code + ... = L.getRow(row_index - 1); + \endcode - \warning Notice row(1) is the 0th row. - This function returns the i-th row of the matrix. - \param i : Index of the row to extract noting that row index start at 1 to get the first row. + \warning Notice row(1) is the 0th row. + This function returns the i-th row of the matrix. + \param i : Index of the row to extract noting that row index start at 1 to get the first row. - */ - vpRowVector vpMatrix::row(unsigned int i) - { - vpRowVector c(getCols()); + */ + vpRowVector vpMatrix::row(unsigned int i) + { + vpRowVector c(getCols()); - for (unsigned int j = 0; j < getCols(); j++) - c[j] = (*this)[i - 1][j]; - return c; - } + for (unsigned int j = 0; j < getCols(); j++) + c[j] = (*this)[i - 1][j]; + return c; + } - /*! - \deprecated This method is deprecated. You should rather use getCol(). - More precisely, the following code: - \code - vpMatrix L; - unsigned int column_index = ...; - ... = L.column(column_index); - \endcode - should be replaced with: - \code - ... = L.getCol(column_index - 1); - \endcode + /*! + \deprecated This method is deprecated. You should rather use getCol(). + More precisely, the following code: + \code + vpMatrix L; + unsigned int column_index = ...; + ... = L.column(column_index); + \endcode + should be replaced with: + \code + ... = L.getCol(column_index - 1); + \endcode - \warning Notice column(1) is the 0-th column. - This function returns the j-th columns of the matrix. - \param j : Index of the column to extract noting that column index start at 1 to get the first column. - */ - vpColVector vpMatrix::column(unsigned int j) - { - vpColVector c(getRows()); + \warning Notice column(1) is the 0-th column. + This function returns the j-th columns of the matrix. + \param j : Index of the column to extract noting that column index start at 1 to get the first column. + */ + vpColVector vpMatrix::column(unsigned int j) + { + vpColVector c(getRows()); - for (unsigned int i = 0; i < getRows(); i++) - c[i] = (*this)[i][j - 1]; - return c; - } + for (unsigned int i = 0; i < getRows(); i++) + c[i] = (*this)[i][j - 1]; + return c; + } - /*! - \deprecated You should rather use diag(const double &) + /*! + \deprecated You should rather use diag(const double &) - Set the matrix diagonal elements to \e val. - More generally set M[i][i] = val. - */ - void vpMatrix::setIdentity(const double &val) - { - for (unsigned int i = 0; i < rowNum; i++) - for (unsigned int j = 0; j < colNum; j++) - if (i == j) - (*this)[i][j] = val; - else - (*this)[i][j] = 0; - } + Set the matrix diagonal elements to \e val. + More generally set M[i][i] = val. + */ + void vpMatrix::setIdentity(const double &val) + { + for (unsigned int i = 0; i < rowNum; i++) + for (unsigned int j = 0; j < colNum; j++) + if (i == j) + (*this)[i][j] = val; + else + (*this)[i][j] = 0; + } #endif //#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) diff --git a/modules/core/src/math/matrix/vpMatrix_qr.cpp b/modules/core/src/math/matrix/vpMatrix_qr.cpp index 3a76d556e3..a172a21ed3 100644 --- a/modules/core/src/math/matrix/vpMatrix_qr.cpp +++ b/modules/core/src/math/matrix/vpMatrix_qr.cpp @@ -868,8 +868,9 @@ unsigned int vpMatrix::qrPivot(vpMatrix &Q, vpMatrix &R, vpMatrix &P, bool full, } integer dimWork = -1; + integer min_q_m = std::min(q, m); double *qrdata = new double[m * na]; - double *tau = new double[std::min(q, m)]; + double *tau = new double[min_q_m]; double *work = new double[1]; integer *p = new integer[na]; for (int i = 0; i < na; ++i) diff --git a/modules/core/src/math/matrix/vpRowVector.cpp b/modules/core/src/math/matrix/vpRowVector.cpp index 080859de62..a3a88349d4 100644 --- a/modules/core/src/math/matrix/vpRowVector.cpp +++ b/modules/core/src/math/matrix/vpRowVector.cpp @@ -122,6 +122,7 @@ vpRowVector &vpRowVector::operator=(double x) return *this; } +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpRowVector &vpRowVector::operator=(vpRowVector &&other) { if (this != &other) { @@ -168,6 +169,7 @@ 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 { @@ -576,6 +578,7 @@ 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; @@ -590,6 +593,7 @@ vpRowVector::vpRowVector(vpRowVector &&v) : vpArray2D() v.dsize = 0; v.data = nullptr; } +#endif /*! Normalize the vector given as input parameter and return the normalized @@ -1150,10 +1154,12 @@ void vpRowVector::init(const vpRowVector &v, unsigned int c, unsigned int ncols) throw(vpException(vpException::dimensionError, "Bad column dimension (%d > %d) used to initialize vpRowVector", cncols, v.getCols())); resize(ncols); - if (this->rowPtrs == nullptr) // Fix coverity scan: explicit null dereferenced + if (this->rowPtrs == nullptr) { // Fix coverity scan: explicit null dereferenced return; // Noting to do - for (unsigned int i = 0; i < ncols; i++) + } + for (unsigned int i = 0; i < ncols; i++) { (*this)[i] = v[i + c]; + } } /*! diff --git a/modules/core/src/math/matrix/vpSubMatrix.cpp b/modules/core/src/math/matrix/vpSubMatrix.cpp index da9e7c7b7c..517450f790 100644 --- a/modules/core/src/math/matrix/vpSubMatrix.cpp +++ b/modules/core/src/math/matrix/vpSubMatrix.cpp @@ -42,7 +42,7 @@ #include #include -vpSubMatrix::vpSubMatrix() : pRowNum(0), pColNum(0), parent(nullptr) {} +vpSubMatrix::vpSubMatrix() : pRowNum(0), pColNum(0), parent(nullptr) { } /*! \brief Constructor @@ -91,9 +91,10 @@ void vpSubMatrix::init(vpMatrix &m, const unsigned int &row_offset, const unsign rowPtrs[r] = m.data + col_offset + (r + row_offset) * pColNum; dsize = pRowNum * pColNum; - } else { + } + else { throw( - vpMatrixException(vpMatrixException::incorrectMatrixSizeError, "Submatrix cannot be contain in parent matrix")); + vpMatrixException(vpMatrixException::incorrectMatrixSizeError, "Submatrix cannot be contain in parent matrix")); } } diff --git a/modules/core/src/math/misc/vpMath.cpp b/modules/core/src/math/misc/vpMath.cpp index 7c3855cc15..661039251c 100644 --- a/modules/core/src/math/misc/vpMath.cpp +++ b/modules/core/src/math/misc/vpMath.cpp @@ -351,7 +351,11 @@ 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(); @@ -576,7 +580,11 @@ 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; @@ -613,7 +621,7 @@ std::vector > vpMath::computeRegularPointsOnSphere(uns \sa enu2ecef(), ned2ecef() */ std::vector vpMath::getLocalTangentPlaneTransformations(const std::vector > &lonlatVec, double radius, - vpHomogeneousMatrix(*toECEF)(double lonDeg_, double latDeg_, double radius_)) + vpHomogeneousMatrix(*toECEF)(double lonDeg_, double latDeg_, double radius_)) { std::vector ecef_M_local_vec; ecef_M_local_vec.reserve(lonlatVec.size()); diff --git a/modules/core/src/math/robust/vpRobust.cpp b/modules/core/src/math/robust/vpRobust.cpp index 14fcf12cf6..7a87b9df87 100644 --- a/modules/core/src/math/robust/vpRobust.cpp +++ b/modules/core/src/math/robust/vpRobust.cpp @@ -87,6 +87,7 @@ vpRobust &vpRobust::operator=(const vpRobust &other) return *this; } +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Move operator. */ @@ -103,6 +104,7 @@ vpRobust &vpRobust::operator=(const vpRobust &&other) m_size = std::move(other.m_size); return *this; } +#endif /*! Resize containers. @@ -441,7 +443,7 @@ vpColVector vpRobust::simultMEstimator(vpColVector &residues) m_mad = 1.4826 * normmedian; // Median Absolute Deviation } else { - // compute simultaneous scale estimate + // compute simultaneous scale estimate m_mad = simultscale(residues); } @@ -591,7 +593,7 @@ double vpRobust::simult_chi_huber(double x) sct = vpMath::sqr(u); } else { - // sct = 0.5*vpMath::sqr(c); + // sct = 0.5*vpMath::sqr(c); sct = vpMath::sqr(c); } diff --git a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp index ddc87caa35..d2f2329020 100644 --- a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp @@ -148,6 +148,7 @@ 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. @@ -240,6 +241,7 @@ 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 64268a6617..22eb0687c5 100644 --- a/modules/core/src/math/transformation/vpQuaternionVector.cpp +++ b/modules/core/src/math/transformation/vpQuaternionVector.cpp @@ -338,6 +338,7 @@ double &vpQuaternionVector::z() { return data[2]; } //! Returns a reference to the w-component of the quaternion. 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 @@ -366,6 +367,7 @@ vpQuaternionVector &vpQuaternionVector::operator=(const std::initializer_list= VISP_CXX_STANDARD_11) /*! Set a rotation matrix from a list of 9 double values. \param list : List of double. @@ -134,6 +135,7 @@ 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. @@ -570,6 +573,7 @@ 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 d4c48da25d..4eb17b8b43 100644 --- a/modules/core/src/math/transformation/vpRxyzVector.cpp +++ b/modules/core/src/math/transformation/vpRxyzVector.cpp @@ -226,6 +226,7 @@ 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 @@ -254,3 +255,4 @@ vpRxyzVector &vpRxyzVector::operator=(const std::initializer_list &list) 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 69dbae4959..523e917e93 100644 --- a/modules/core/src/math/transformation/vpRzyxVector.cpp +++ b/modules/core/src/math/transformation/vpRzyxVector.cpp @@ -232,6 +232,7 @@ 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 @@ -260,3 +261,4 @@ vpRzyxVector &vpRzyxVector::operator=(const std::initializer_list &list) 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 50fd92dab4..e396fb5fdb 100644 --- a/modules/core/src/math/transformation/vpRzyzVector.cpp +++ b/modules/core/src/math/transformation/vpRzyzVector.cpp @@ -223,6 +223,7 @@ 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 @@ -251,3 +252,4 @@ vpRzyzVector &vpRzyzVector::operator=(const std::initializer_list &list) 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 04731f48e7..d9738d6dba 100644 --- a/modules/core/src/math/transformation/vpThetaUVector.cpp +++ b/modules/core/src/math/transformation/vpThetaUVector.cpp @@ -467,6 +467,7 @@ vpThetaUVector vpThetaUVector::operator*(const vpThetaUVector &tu_b) const return vpThetaUVector(d); } +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! Set vector from a list of 3 double angle values in radians. \code @@ -495,3 +496,4 @@ vpThetaUVector &vpThetaUVector::operator=(const std::initializer_list &l 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 2f1babf15e..19767242a8 100644 --- a/modules/core/src/math/transformation/vpTranslationVector.cpp +++ b/modules/core/src/math/transformation/vpTranslationVector.cpp @@ -506,6 +506,7 @@ 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 @@ -534,6 +535,7 @@ 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 e228872ce8..a8ec675203 100644 --- a/modules/core/src/tools/file/vpIoTools.cpp +++ b/modules/core/src/tools/file/vpIoTools.cpp @@ -329,6 +329,7 @@ visp::cnpy::NpyArray load_the_npz_array(FILE *fp, uint32_t compr_bytes, uint32_t return array; } +#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 /*! Load the specified \p fname filepath as arrays of data. This function is similar to the numpy.load function. @@ -386,6 +387,7 @@ visp::cnpy::npz_t visp::cnpy::npz_load(std::string fname) fclose(fp); return arrays; } +#endif /*! Load the specified \p varname array of data from the \p fname npz file. This function is similar to the @@ -499,18 +501,21 @@ void replaceAll(std::string &str, const std::string &search, const std::string & std::string <rim(std::string &s) { - s.erase(s.begin(), std::find_if(s.begin(), s.end(), [](int c) { - return !std::isspace(c); - })); - +#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) { - s.erase(std::find_if(s.rbegin(), s.rend(), [](int c) { - return !std::isspace(c); - }).base(), s.end()); +#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 diff --git a/modules/core/src/tools/geometry/vpPolygon.cpp b/modules/core/src/tools/geometry/vpPolygon.cpp index 0cbca328a0..90c3e61198 100644 --- a/modules/core/src/tools/geometry/vpPolygon.cpp +++ b/modules/core/src/tools/geometry/vpPolygon.cpp @@ -63,15 +63,18 @@ template std::vector convexHull(const IpCon // Visp -> CV std::vector cv_pts; - // Check if std:c++14 or higher -#if ((__cplusplus >= 201402L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201402L))) +#if ((__cplusplus >= 201402L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201402L))) // Check if cxx14 or higher 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())); - }); -#else + }); +#elif ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher 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 // cxx98 + 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 @@ -80,17 +83,21 @@ template std::vector convexHull(const IpCon // CV -> Visp std::vector conv_hull_corners; - // Check if std:c++14 or higher -#if ((__cplusplus >= 201402L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201402L))) +#if ((__cplusplus >= 201402L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201402L))) // Check if cxx14 or higher 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) }; }); -#else +#elif ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher 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) }; }); +#else // cxx98 + 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; @@ -177,7 +184,7 @@ vpPolygon &vpPolygon::operator=(const vpPolygon &poly) \warning the corners must be ordered (either clockwise or counter clockwise). - \param corners : The corners of the polyon. + \param corners : The corners of the polygon. \param create_convex_hull: Create a convex hull from the given corners. */ void vpPolygon::buildFrom(const std::vector &corners, const bool create_convex_hull) @@ -200,7 +207,7 @@ void vpPolygon::buildFrom(const std::vector &corners, const bool c \warning the corners must be ordered (either clockwise or counter clockwise). - \param corners : The corners of the polyon. + \param corners : The corners of the polygon. \param create_convex_hull: Create a convex hull from the given corners. */ void vpPolygon::buildFrom(const std::list &corners, const bool create_convex_hull) @@ -225,9 +232,8 @@ void vpPolygon::buildFrom(const std::list &corners, const bool cre \warning the corners must be ordered (either clockwise or counter clockwise). - \param corners : The corners of the polyon. - \param cam : The camera parameters used to convert the coordinates from - meter to pixel. + \param corners : The corners of the polygon. + \param cam : The camera parameters used to convert the coordinates from meter to pixel. \param create_convex_hull: Create a convex hull from the given corners. */ void vpPolygon::buildFrom(const std::vector &corners, const vpCameraParameters &cam, @@ -245,9 +251,9 @@ void vpPolygon::buildFrom(const std::vector &corners, const vpCameraPar A right click is used to stop the addition of new corners. \param I : The image where to click to initialise the corners. - \param size : Cross size in terms of number of pixels that is displayed over - a polygon corner. \param color : Color used to display the cross over the - polygon corner. \param thickness : Thickness used to display the cross. + \param size : Cross size in terms of number of pixels that is displayed over a polygon corner. + \param color : Color used to display the cross over the polygon corner. + \param thickness : Thickness used to display the cross. */ void vpPolygon::initClick(const vpImage &I, unsigned int size, const vpColor &color, unsigned int thickness) @@ -274,10 +280,9 @@ void vpPolygon::initClick(const vpImage &I, unsigned int size, co A right click is used to stop the addition of new corners. \param I : The image where to click to initialise the corners. - \param size : Size of the cross in terms of number of pixels that is - displayed over a polygon corner. \param color : Color used to display the - cross over the polygon corner. \param thickness : Thickness used to display - the cross. + \param size : Size of the cross in terms of number of pixels that is displayed over a polygon corner. + \param color : Color used to display the cross over the polygon corner. + \param thickness : Thickness used to display the cross. */ void vpPolygon::initClick(const vpImage &I, unsigned int size, const vpColor &color, unsigned int thickness) { @@ -395,13 +400,11 @@ bool vpPolygon::isInside(const vpImagePoint &ip, const PointInPolygonMethod &met switch (method) { case PnPolySegmentIntersection: { vpImagePoint infPoint(100000, 100000); // take a point at 'infinity' + // we add random since it appears that sometimes infPoint may cause a degenerated case (so relaunch and + // hope that result will be different). vpUniRand generator; infPoint.set_i(infPoint.get_i() + 1000 * generator()); - infPoint.set_j(infPoint.get_j() + 1000 * generator()); // we add random since it appears that - // sometimes infPoint may cause a - // degenerated case (so relaunch and - // hope that result will be - // different). + infPoint.set_j(infPoint.get_j() + 1000 * generator()); bool oddNbIntersections = false; for (unsigned int i = 0; i < _corners.size(); ++i) { @@ -429,7 +432,7 @@ bool vpPolygon::isInside(const vpImagePoint &ip, const PointInPolygonMethod &met test = oddNbIntersections; } break; - // Reference: http://alienryderflex.com/polygon/ + // Reference: http://alienryderflex.com/polygon/ case PnPolyRayCasting: default: { bool oddNodes = false; @@ -524,12 +527,12 @@ void vpPolygon::updateCenter() double i_tmp = 0; double j_tmp = 0; #if 0 - 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()); + 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()); - 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()); + 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()); } #else for (unsigned int i = 0; i < _corners.size(); ++i) { @@ -623,4 +626,7 @@ bool vpPolygon::isInside(const std::vector &roi, const double &i, /*! Return number of corners belonging to the polygon. */ -unsigned int vpPolygon::getSize() const { return ((unsigned int)_corners.size()); } +unsigned int vpPolygon::getSize() const +{ + return ((unsigned int)_corners.size()); +} diff --git a/modules/core/src/tools/geometry/vpRectOriented.cpp b/modules/core/src/tools/geometry/vpRectOriented.cpp index 480e5fe6fb..b64d5a615f 100644 --- a/modules/core/src/tools/geometry/vpRectOriented.cpp +++ b/modules/core/src/tools/geometry/vpRectOriented.cpp @@ -82,6 +82,29 @@ 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 + /** Assignment operator from vpRect. * @param rect Rectangle to copy. */ diff --git a/modules/core/src/tools/optimization/vpLinProg.cpp b/modules/core/src/tools/optimization/vpLinProg.cpp index a3c5e698fc..fea24cea8f 100644 --- a/modules/core/src/tools/optimization/vpLinProg.cpp +++ b/modules/core/src/tools/optimization/vpLinProg.cpp @@ -277,6 +277,7 @@ 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 @@ -287,7 +288,7 @@ bool vpLinProg::rowReduction(vpMatrix &A, vpColVector &b, const double &tol) & \text{s.t.}& \mathbf{x}_i \geq \mathbf{l}_i \text{~for some i}\\ & \text{s.t.}& \mathbf{x}_j \leq \mathbf{u}_j \text{~for some j} \end{array} -\f$ + \f$ \param c : cost vector (dimension n) \param A : equality matrix (dimension m x n) \param b : equality vector (dimension m) @@ -302,6 +303,9 @@ 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} @@ -349,7 +353,7 @@ bool vpLinProg::solveLP(const vpColVector &c, vpMatrix A, vpColVector b, const v (find_if(l.begin(), l.end(), [&](BoundedIndex &i) { return x[i.first] < i.second - tol; }) == l.end()) && (find_if(u.begin(), u.end(), [&](BoundedIndex &i) { return x[i.first] > i.second + tol; }) == u.end()); -// shortcut for unbounded variables with equality + // shortcut for unbounded variables with equality if (!feasible && m && l.size() == 0 && u.size() == 0) { // changes A.x = b to x = b + A.z if (colReduction(A, b, false, tol)) { @@ -723,3 +727,5 @@ 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 a7feb40b91..fdac7be8f2 100644 --- a/modules/core/src/tools/optimization/vpQuadProg.cpp +++ b/modules/core/src/tools/optimization/vpQuadProg.cpp @@ -40,6 +40,8 @@ #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$. @@ -676,3 +678,7 @@ 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 f1c58f4d91..408f0c87ab 100644 --- a/modules/core/src/tools/time/vpTime.cpp +++ b/modules/core/src/tools/time/vpTime.cpp @@ -39,7 +39,8 @@ #include // https://devblogs.microsoft.com/cppblog/c14-stl-features-fixes-and-breaking-changes-in-visual-studio-14-ctp1/ -#if (defined(_MSC_VER) && _MSC_VER >= 1900 /* VS2015 */ || !defined(_MSC_VER)) +#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 && \ + (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/camera/testJsonCamera.cpp b/modules/core/test/camera/testJsonCamera.cpp index 61207109a5..2d406d2674 100644 --- a/modules/core/test/camera/testJsonCamera.cpp +++ b/modules/core/test/camera/testJsonCamera.cpp @@ -65,13 +65,13 @@ class vpRandomCamGenerator : public Catch::Generators::IGenerator(next()); } - const vpCameraParameters &get() const override { return current; } - bool next() override + const vpCameraParameters &get() const vp_override { return current; } + bool next() vp_override { const double px = m_dist(m_rand); const double py = m_dist(m_rand); @@ -149,7 +149,7 @@ SCENARIO("Serializing two cameras", "[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/core/test/math/testJsonArrayConversion.cpp b/modules/core/test/math/testJsonArrayConversion.cpp index 4a0c9195c7..152836a9b0 100644 --- a/modules/core/test/math/testJsonArrayConversion.cpp +++ b/modules/core/test/math/testJsonArrayConversion.cpp @@ -66,12 +66,12 @@ class vpExceptionMatcher : public Catch::Matchers::Impl::MatcherBase(next()); } - vpArray2D const &get() const override { return current; } - bool next() override + vpArray2D const &get() const vp_override { return current; } + bool next() vp_override { const unsigned nCols = m_dim_dist(m_rand); const unsigned nRows = m_dim_dist(m_rand); @@ -127,8 +127,8 @@ class vpRandomColVectorGenerator : public Catch::Generators::IGenerator(next()); } - const vpColVector &get() const override { return current; } - bool next() override + const vpColVector &get() const vp_override { return current; } + bool next() vp_override { const unsigned nRows = m_dim_dist(m_rand); current.resize(nRows); diff --git a/modules/core/test/math/testMath.cpp b/modules/core/test/math/testMath.cpp index 8fedb34bd7..75e10d2215 100644 --- a/modules/core/test/math/testMath.cpp +++ b/modules/core/test/math/testMath.cpp @@ -601,12 +601,12 @@ int main() std::cout << "vpMath::getMedian() is Ok !" << std::endl; // Test clamp +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { const double lower { -10. }, upper { +10. }; 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); if (!vpMath::equal(clamp_val, expected_values.at(i), 0.001)) { @@ -616,6 +616,7 @@ int main() } std::cout << "vpMath::clamp() is Ok !" << std::endl; } +#endif // Test vpMath::deg() and vpMath::rad() { diff --git a/modules/core/test/math/testMatrixInitialization.cpp b/modules/core/test/math/testMatrixInitialization.cpp index d7d9e4e0fe..a4f0f4dd53 100644 --- a/modules/core/test/math/testMatrixInitialization.cpp +++ b/modules/core/test/math/testMatrixInitialization.cpp @@ -106,6 +106,8 @@ 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 }; std::cout << "a:\n" << a << std::endl; @@ -158,6 +160,7 @@ int main() // m6 = {m2}; // Fails on travis // std::cout << "m6:\n" << m6 << std::endl; } +#endif { vpMatrix m1; @@ -187,6 +190,7 @@ 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 }; std::cout << "c: " << c.t() << std::endl; @@ -218,6 +222,7 @@ int main() return EXIT_FAILURE; } } +#endif { vpColVector c; c << 1, 2, 3, 4; @@ -250,6 +255,7 @@ 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 }; std::cout << "r: " << r << std::endl; @@ -281,6 +287,7 @@ int main() return EXIT_FAILURE; } } +#endif { vpRowVector r; r << 1, 2, 3; @@ -303,6 +310,7 @@ 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 }; std::cout << "tu: " << tu.t() << std::endl; @@ -310,6 +318,7 @@ int main() return EXIT_FAILURE; } } +#endif { vpThetaUVector tu; tu << 0, M_PI_2, M_PI; @@ -330,6 +339,7 @@ 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 }; std::cout << "rxyz: " << rxyz.t() << std::endl; @@ -337,6 +347,7 @@ int main() return EXIT_FAILURE; } } +#endif { vpRxyzVector rxyz; rxyz << 0, M_PI_2, M_PI; @@ -357,6 +368,7 @@ 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 }; std::cout << "rzyx: " << rzyx.t() << std::endl; @@ -364,6 +376,7 @@ int main() return EXIT_FAILURE; } } +#endif { vpRzyxVector rzyx; rzyx << 0, M_PI_2, M_PI; @@ -384,6 +397,7 @@ 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 }; std::cout << "rzyz: " << rzyz.t() << std::endl; @@ -391,6 +405,7 @@ int main() return EXIT_FAILURE; } } +#endif { vpRzyzVector rzyz; rzyz << 0, M_PI_2, M_PI; @@ -412,6 +427,7 @@ 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] }; std::cout << "q: " << q.t() << std::endl; @@ -419,6 +435,7 @@ int main() return EXIT_FAILURE; } } +#endif { vpQuaternionVector q; q << q_ref[0], q_ref[1], q_ref[2], q_ref[3]; @@ -439,6 +456,7 @@ 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] }; std::cout << "t: " << t.t() << std::endl; @@ -446,6 +464,7 @@ int main() return EXIT_FAILURE; } } +#endif { vpTranslationVector t; t << 0, 0.1, 0.5; @@ -466,6 +485,7 @@ 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 }); std::cout << "R:\n" << R << std::endl; @@ -481,6 +501,7 @@ int main() return EXIT_FAILURE; } } +#endif { vpRotationMatrix R; R << 0, 0, -1, 0, -1, 0, -1, 0, 0; diff --git a/modules/detection/include/visp3/detection/vpDetectorAprilTag.h b/modules/detection/include/visp3/detection/vpDetectorAprilTag.h index 964dd4a0de..3967392a98 100644 --- a/modules/detection/include/visp3/detection/vpDetectorAprilTag.h +++ b/modules/detection/include/visp3/detection/vpDetectorAprilTag.h @@ -250,9 +250,10 @@ class VISP_EXPORT vpDetectorAprilTag : public vpDetectorBase const vpPoseEstimationMethod &poseEstimationMethod = HOMOGRAPHY_VIRTUAL_VS); vpDetectorAprilTag(const vpDetectorAprilTag &o); vpDetectorAprilTag &operator=(vpDetectorAprilTag o); - virtual ~vpDetectorAprilTag() override; + virtual ~vpDetectorAprilTag() vp_override; + bool detect(const vpImage &I) vp_override; + - bool detect(const vpImage &I) override; bool detect(const vpImage &I, double tagSize, const vpCameraParameters &cam, std::vector &cMo_vec, std::vector *cMo_vec2 = nullptr, std::vector *projErrors = nullptr, std::vector *projErrors2 = nullptr); diff --git a/modules/detection/include/visp3/detection/vpDetectorDataMatrixCode.h b/modules/detection/include/visp3/detection/vpDetectorDataMatrixCode.h index a7005566e3..89b814aaa3 100644 --- a/modules/detection/include/visp3/detection/vpDetectorDataMatrixCode.h +++ b/modules/detection/include/visp3/detection/vpDetectorDataMatrixCode.h @@ -110,7 +110,7 @@ class VISP_EXPORT vpDetectorDataMatrixCode : public vpDetectorBase { public: vpDetectorDataMatrixCode(); - bool detect(const vpImage &I) override; + bool detect(const vpImage &I) vp_override; }; #endif diff --git a/modules/detection/include/visp3/detection/vpDetectorFace.h b/modules/detection/include/visp3/detection/vpDetectorFace.h index 313aab4d9a..392e67ff73 100644 --- a/modules/detection/include/visp3/detection/vpDetectorFace.h +++ b/modules/detection/include/visp3/detection/vpDetectorFace.h @@ -92,7 +92,7 @@ class VISP_EXPORT vpDetectorFace : public vpDetectorBase public: vpDetectorFace(); - bool detect(const vpImage &I) override; + bool detect(const vpImage &I) vp_override; bool detect(const cv::Mat &frame_gray); void setCascadeClassifierFile(const std::string &filename); }; diff --git a/modules/detection/include/visp3/detection/vpDetectorQRCode.h b/modules/detection/include/visp3/detection/vpDetectorQRCode.h index a2942cee5a..2369dc3ffe 100644 --- a/modules/detection/include/visp3/detection/vpDetectorQRCode.h +++ b/modules/detection/include/visp3/detection/vpDetectorQRCode.h @@ -113,7 +113,11 @@ class VISP_EXPORT vpDetectorQRCode : public vpDetectorBase public: vpDetectorQRCode(); - bool detect(const vpImage &I) override; +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + bool detect(const vpImage &I) vp_override; +#else + bool detect(const vpImage &I); +#endif }; #endif diff --git a/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h b/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h index f708605cd4..55b8e091b5 100755 --- a/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h +++ b/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h @@ -40,6 +40,7 @@ #include #include +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) /** * \brief Class that furnishes a set of colors that color blind people * should be able to distinguish one from another. @@ -191,4 +192,5 @@ 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/vpD3DRenderer.h b/modules/gui/include/visp3/gui/vpD3DRenderer.h index 06dcb884fc..e3629d060c 100644 --- a/modules/gui/include/visp3/gui/vpD3DRenderer.h +++ b/modules/gui/include/visp3/gui/vpD3DRenderer.h @@ -94,7 +94,7 @@ class VISP_EXPORT vpD3DRenderer : public vpWin32Renderer bool render(); vpD3DRenderer(); - virtual ~vpD3DRenderer() override; + virtual ~vpD3DRenderer() vp_override; void setImg(const vpImage &im); void setImg(const vpImage &im); @@ -121,7 +121,7 @@ class VISP_EXPORT vpD3DRenderer : public vpWin32Renderer void drawArrow(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int w, unsigned int h, unsigned int thickness = 1); - void getImage(vpImage &I) override; + void getImage(vpImage &I) vp_override; private: void initView(float, float); diff --git a/modules/gui/include/visp3/gui/vpDisplayGTK.h b/modules/gui/include/visp3/gui/vpDisplayGTK.h index c03b668dff..9813f6a01c 100644 --- a/modules/gui/include/visp3/gui/vpDisplayGTK.h +++ b/modules/gui/include/visp3/gui/vpDisplayGTK.h @@ -160,67 +160,67 @@ class VISP_EXPORT vpDisplayGTK : public vpDisplay vpDisplayGTK(vpImage &I, int win_x = -1, int win_y = -1, const std::string &win_title = "", vpScaleType type = SCALE_DEFAULT); - virtual ~vpDisplayGTK() override; + virtual ~vpDisplayGTK() vp_override; - void getImage(vpImage &I) override; + void getImage(vpImage &I) vp_override; unsigned int getScreenDepth(); - unsigned int getScreenHeight() override; - void getScreenSize(unsigned int &screen_width, unsigned int &screen_height) override; - unsigned int getScreenWidth() override; + unsigned int getScreenHeight() vp_override; + void getScreenSize(unsigned int &screen_width, unsigned int &screen_height) vp_override; + unsigned int getScreenWidth() vp_override; - void init(vpImage &I, int win_x = -1, int win_y = -1, const std::string &win_title = "") override; - void init(vpImage &I, int win_x = -1, int win_y = -1, const std::string &win_title = "") override; + void init(vpImage &I, int win_x = -1, int win_y = -1, const std::string &win_title = "") vp_override; + void init(vpImage &I, int win_x = -1, int win_y = -1, const std::string &win_title = "") vp_override; void init(unsigned int win_width, unsigned int win_height, int win_x = -1, int win_y = -1, - const std::string &win_title = "") override; + const std::string &win_title = "") vp_override; protected: - void setFont(const std::string &fontname) override; - void setTitle(const std::string &win_title) override; - void setWindowPosition(int win_x, int win_y) override; + void setFont(const std::string &fontname) vp_override; + void setTitle(const std::string &win_title) vp_override; + void setWindowPosition(int win_x, int win_y) vp_override; - void clearDisplay(const vpColor &color = vpColor::white) override; + void clearDisplay(const vpColor &color = vpColor::white) vp_override; - void closeDisplay() override; + void closeDisplay() vp_override; void displayArrow(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color = vpColor::white, - unsigned int w = 4, unsigned int h = 2, unsigned int thickness = 1) override; + unsigned int w = 4, unsigned int h = 2, unsigned int thickness = 1) vp_override; void displayCircle(const vpImagePoint ¢er, unsigned int radius, const vpColor &color, bool fill = false, - unsigned int thickness = 1) override; - void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; + void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness = 1) vp_override; void displayDotLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; - void displayImage(const vpImage &I) override; - void displayImage(const vpImage &I) override; + void displayImage(const vpImage &I) vp_override; + void displayImage(const vpImage &I) vp_override; void displayImage(const unsigned char *I); void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, - unsigned int height) override; - void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height) override; + unsigned int height) vp_override; + void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height) vp_override; - void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness = 1) override; + void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness = 1) vp_override; - void displayPoint(const vpImagePoint &ip, const vpColor &color, unsigned int thickness = 1) override; + void displayPoint(const vpImagePoint &ip, const vpColor &color, unsigned int thickness = 1) vp_override; void displayRectangle(const vpImagePoint &topLeft, unsigned int width, unsigned int height, const vpColor &color, - bool fill = false, unsigned int thickness = 1) override; + bool fill = false, unsigned int thickness = 1) vp_override; void displayRectangle(const vpImagePoint &topLeft, const vpImagePoint &bottomRight, const vpColor &color, - bool fill = false, unsigned int thickness = 1) override; - void displayRectangle(const vpRect &rectangle, const vpColor &color, bool fill = false, unsigned int thickness = 1) override; - - void displayText(const vpImagePoint &ip, const std::string &text, const vpColor &color = vpColor::green) override; - - void flushDisplay() override; - void flushDisplayROI(const vpImagePoint &iP, unsigned int width, unsigned int height) override; - - bool getClick(bool blocking = true) override; - bool getClick(vpImagePoint &ip, bool blocking = true) override; - bool getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) override; - bool getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) override; - bool getKeyboardEvent(bool blocking = true) override; - bool getKeyboardEvent(std::string &key, bool blocking = true) override; - bool getPointerMotionEvent(vpImagePoint &ip) override; - bool getPointerPosition(vpImagePoint &ip) override; + bool fill = false, unsigned int thickness = 1) vp_override; + void displayRectangle(const vpRect &rectangle, const vpColor &color, bool fill = false, unsigned int thickness = 1) vp_override; + + void displayText(const vpImagePoint &ip, const std::string &text, const vpColor &color = vpColor::green) vp_override; + + void flushDisplay() vp_override; + void flushDisplayROI(const vpImagePoint &iP, unsigned int width, unsigned int height) vp_override; + + bool getClick(bool blocking = true) vp_override; + bool getClick(vpImagePoint &ip, bool blocking = true) vp_override; + bool getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) vp_override; + bool getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) vp_override; + bool getKeyboardEvent(bool blocking = true) vp_override; + bool getKeyboardEvent(std::string &key, bool blocking = true) vp_override; + bool getPointerMotionEvent(vpImagePoint &ip) vp_override; + bool getPointerPosition(vpImagePoint &ip) vp_override; private: // Implementation diff --git a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h index d7616526a6..ca9ce797d9 100644 --- a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h +++ b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h @@ -202,66 +202,66 @@ class VISP_EXPORT vpDisplayOpenCV : public vpDisplay vpDisplayOpenCV(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "", vpScaleType type = SCALE_DEFAULT); - virtual ~vpDisplayOpenCV() override; + virtual ~vpDisplayOpenCV() vp_override; - void getImage(vpImage &I) override; - unsigned int getScreenHeight() override; - void getScreenSize(unsigned int &width, unsigned int &height) override; - unsigned int getScreenWidth() override; + void getImage(vpImage &I) vp_override; + unsigned int getScreenHeight() vp_override; + void getScreenSize(unsigned int &width, unsigned int &height) vp_override; + unsigned int getScreenWidth() vp_override; - void init(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") override; - void init(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") override; - void init(unsigned int width, unsigned int height, int winx = -1, int winy = -1, const std::string &title = "") override; + void init(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") vp_override; + void init(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") vp_override; + void init(unsigned int width, unsigned int height, int winx = -1, int winy = -1, const std::string &title = "") vp_override; protected: - void setFont(const std::string &font) override; - void setTitle(const std::string &title) override; - void setWindowPosition(int winx, int winy) override; + void setFont(const std::string &font) vp_override; + void setTitle(const std::string &title) vp_override; + void setWindowPosition(int winx, int winy) vp_override; - void clearDisplay(const vpColor &color = vpColor::white) override; + void clearDisplay(const vpColor &color = vpColor::white) vp_override; - void closeDisplay() override; + void closeDisplay() vp_override; void displayArrow(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color = vpColor::white, - unsigned int w = 4, unsigned int h = 2, unsigned int thickness = 1) override; + unsigned int w = 4, unsigned int h = 2, unsigned int thickness = 1) vp_override; void displayCircle(const vpImagePoint ¢er, unsigned int radius, const vpColor &color, bool fill = false, - unsigned int thickness = 1) override; - void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; + void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness = 1) vp_override; void displayDotLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; - void displayImage(const vpImage &I) override; - void displayImage(const vpImage &I) override; + void displayImage(const vpImage &I) vp_override; + void displayImage(const vpImage &I) vp_override; void displayImage(const unsigned char *I); void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, - unsigned int height) override; - void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height) override; + unsigned int height) vp_override; + void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height) vp_override; - void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness = 1) override; - void displayPoint(const vpImagePoint &ip, const vpColor &color, unsigned int thickness = 1) override; + void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness = 1) vp_override; + void displayPoint(const vpImagePoint &ip, const vpColor &color, unsigned int thickness = 1) vp_override; void displayRectangle(const vpImagePoint &topLeft, unsigned int width, unsigned int height, const vpColor &color, - bool fill = false, unsigned int thickness = 1) override; + bool fill = false, unsigned int thickness = 1) vp_override; void displayRectangle(const vpImagePoint &topLeft, const vpImagePoint &bottomRight, const vpColor &color, - bool fill = false, unsigned int thickness = 1) override; - void displayRectangle(const vpRect &rectangle, const vpColor &color, bool fill = false, unsigned int thickness = 1) override; + bool fill = false, unsigned int thickness = 1) vp_override; + void displayRectangle(const vpRect &rectangle, const vpColor &color, bool fill = false, unsigned int thickness = 1) vp_override; - void displayText(const vpImagePoint &ip, const std::string &text, const vpColor &color = vpColor::green) override; + void displayText(const vpImagePoint &ip, const std::string &text, const vpColor &color = vpColor::green) vp_override; - void flushDisplay() override; - void flushDisplayROI(const vpImagePoint &iP, unsigned int width, unsigned int height) override; + void flushDisplay() vp_override; + void flushDisplayROI(const vpImagePoint &iP, unsigned int width, unsigned int height) vp_override; - bool getClick(bool blocking = true) override; - bool getClick(vpImagePoint &ip, bool blocking = true) override; - bool getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) override; - bool getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) override; + bool getClick(bool blocking = true) vp_override; + bool getClick(vpImagePoint &ip, bool blocking = true) vp_override; + bool getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) vp_override; + bool getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) vp_override; - bool getKeyboardEvent(bool blocking = true) override; - bool getKeyboardEvent(std::string &key, bool blocking = true) override; - bool getPointerMotionEvent(vpImagePoint &ip) override; - bool getPointerPosition(vpImagePoint &ip) override; + bool getKeyboardEvent(bool blocking = true) vp_override; + bool getKeyboardEvent(std::string &key, bool blocking = true) vp_override; + bool getPointerMotionEvent(vpImagePoint &ip) vp_override; + bool getPointerPosition(vpImagePoint &ip) vp_override; static void on_mouse(int event, int x, int y, int flags, void *param); diff --git a/modules/gui/include/visp3/gui/vpDisplayWin32.h b/modules/gui/include/visp3/gui/vpDisplayWin32.h index d78d0f2f1d..958a3fbd96 100644 --- a/modules/gui/include/visp3/gui/vpDisplayWin32.h +++ b/modules/gui/include/visp3/gui/vpDisplayWin32.h @@ -57,7 +57,7 @@ */ struct threadParam { -//! Pointer to the display associated with the window. + //! Pointer to the display associated with the window. vpDisplayWin32 *vpDisp; //! X position of the window. @@ -118,72 +118,72 @@ class VISP_EXPORT vpDisplayWin32 : public vpDisplay vpDisplayWin32(vpImage &I, int winx = -1, int winy = -1, const std::string &title = ""); - virtual ~vpDisplayWin32() override; + virtual ~vpDisplayWin32() vp_override; - void clearDisplay(const vpColor &color = vpColor::white) override; - void closeDisplay() override; - void displayImage(const vpImage &I) override; - void displayImage(const vpImage &I) override; + void clearDisplay(const vpColor &color = vpColor::white) vp_override; + void closeDisplay() vp_override; + void displayImage(const vpImage &I) vp_override; + void displayImage(const vpImage &I) vp_override; void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, - unsigned int height) override; - void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height) override; + unsigned int height) vp_override; + void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height) vp_override; - void flushDisplay() override; - void flushDisplayROI(const vpImagePoint &iP, unsigned int width, unsigned int height) override; + void flushDisplay() vp_override; + void flushDisplayROI(const vpImagePoint &iP, unsigned int width, unsigned int height) vp_override; - void getImage(vpImage &I) override; - unsigned int getScreenHeight() override; - void getScreenSize(unsigned int &width, unsigned int &height) override; - unsigned int getScreenWidth() override; + void getImage(vpImage &I) vp_override; + unsigned int getScreenHeight() vp_override; + void getScreenSize(unsigned int &width, unsigned int &height) vp_override; + unsigned int getScreenWidth() vp_override; - void init(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") override; - void init(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") override; - void init(unsigned int width, unsigned int height, int winx = -1, int winy = -1, const std::string &title = "") override; + void init(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") vp_override; + void init(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") vp_override; + void init(unsigned int width, unsigned int height, int winx = -1, int winy = -1, const std::string &title = "") vp_override; - void setFont(const std::string &fontname) override; + void setFont(const std::string &fontname) vp_override; void setDownScalingFactor(unsigned int scale) { window.setScale(scale); m_scale = scale; } void setDownScalingFactor(vpScaleType scaleType) { m_scaleType = scaleType; } - void setTitle(const std::string &windowtitle) override; - void setWindowPosition(int winx, int winy) override; + void setTitle(const std::string &windowtitle) vp_override; + void setWindowPosition(int winx, int winy) vp_override; protected: void displayArrow(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color = vpColor::white, - unsigned int w = 4, unsigned int h = 2, unsigned int thickness = 1) override; + unsigned int w = 4, unsigned int h = 2, unsigned int thickness = 1) vp_override; void displayCircle(const vpImagePoint ¢er, unsigned int radius, const vpColor &color, bool fill = false, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; - void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness = 1) override; + void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness = 1) vp_override; void displayDotLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; - void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness = 1) override; + void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness = 1) vp_override; - void displayPoint(const vpImagePoint &ip, const vpColor &color, unsigned int thickness = 1) override; + void displayPoint(const vpImagePoint &ip, const vpColor &color, unsigned int thickness = 1) vp_override; void displayRectangle(const vpImagePoint &topLeft, unsigned int width, unsigned int height, const vpColor &color, - bool fill = false, unsigned int thickness = 1) override; + bool fill = false, unsigned int thickness = 1) vp_override; void displayRectangle(const vpImagePoint &topLeft, const vpImagePoint &bottomRight, const vpColor &color, - bool fill = false, unsigned int thickness = 1) override; - void displayRectangle(const vpRect &rectangle, const vpColor &color, bool fill = false, unsigned int thickness = 1) override; + bool fill = false, unsigned int thickness = 1) vp_override; + void displayRectangle(const vpRect &rectangle, const vpColor &color, bool fill = false, unsigned int thickness = 1) vp_override; - void displayText(const vpImagePoint &ip, const std::string &text, const vpColor &color = vpColor::green) override; + void displayText(const vpImagePoint &ip, const std::string &text, const vpColor &color = vpColor::green) vp_override; - bool getClick(bool blocking = true) override; - bool getClick(vpImagePoint &ip, bool blocking = true) override; - bool getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) override; - bool getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) override; + bool getClick(bool blocking = true) vp_override; + bool getClick(vpImagePoint &ip, bool blocking = true) vp_override; + bool getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) vp_override; + bool getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) vp_override; - bool getKeyboardEvent(bool blocking = true) override; - bool getKeyboardEvent(std::string &key, bool blocking) override; - bool getPointerMotionEvent(vpImagePoint &ip) override; - bool getPointerPosition(vpImagePoint &ip) override; + bool getKeyboardEvent(bool blocking = true) vp_override; + bool getKeyboardEvent(std::string &key, bool blocking) vp_override; + bool getPointerMotionEvent(vpImagePoint &ip) vp_override; + bool getPointerPosition(vpImagePoint &ip) vp_override; void waitForInit(); }; diff --git a/modules/gui/include/visp3/gui/vpDisplayX.h b/modules/gui/include/visp3/gui/vpDisplayX.h index 947064f680..cc843b4e3f 100644 --- a/modules/gui/include/visp3/gui/vpDisplayX.h +++ b/modules/gui/include/visp3/gui/vpDisplayX.h @@ -154,69 +154,69 @@ class VISP_EXPORT vpDisplayX : public vpDisplay vpDisplayX(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "", vpScaleType type = SCALE_DEFAULT); - virtual ~vpDisplayX() override; + virtual ~vpDisplayX() vp_override; - void getImage(vpImage &I) override; + void getImage(vpImage &I) vp_override; unsigned int getScreenDepth(); - unsigned int getScreenHeight() override; - void getScreenSize(unsigned int &width, unsigned int &height) override; - unsigned int getScreenWidth() override; + unsigned int getScreenHeight() vp_override; + void getScreenSize(unsigned int &width, unsigned int &height) vp_override; + unsigned int getScreenWidth() vp_override; - void init(vpImage &I, int win_x = -1, int win_y = -1, const std::string &win_title = "") override; - void init(vpImage &I, int win_x = -1, int win_y = -1, const std::string &win_title = "") override; + void init(vpImage &I, int win_x = -1, int win_y = -1, const std::string &win_title = "") vp_override; + void init(vpImage &I, int win_x = -1, int win_y = -1, const std::string &win_title = "") vp_override; void init(unsigned int win_width, unsigned int win_height, int win_x = -1, int win_y = -1, - const std::string &win_title = "") override; + const std::string &win_title = "") vp_override; protected: - void clearDisplay(const vpColor &color = vpColor::white) override; + void clearDisplay(const vpColor &color = vpColor::white) vp_override; - void closeDisplay() override; + void closeDisplay() vp_override; void displayArrow(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color = vpColor::white, - unsigned int w = 4, unsigned int h = 2, unsigned int thickness = 1) override; + unsigned int w = 4, unsigned int h = 2, unsigned int thickness = 1) vp_override; void displayCircle(const vpImagePoint ¢er, unsigned int radius, const vpColor &color, bool fill = false, - unsigned int thickness = 1) override; - void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; + void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness = 1) vp_override; void displayDotLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, - unsigned int thickness = 1) override; + unsigned int thickness = 1) vp_override; - void displayImage(const vpImage &I) override; - void displayImage(const vpImage &I) override; + void displayImage(const vpImage &I) vp_override; + void displayImage(const vpImage &I) vp_override; void displayImage(const unsigned char *I); void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, - unsigned int height) override; - void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height) override; + unsigned int height) vp_override; + void displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height) vp_override; - void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness = 1) override; - void displayPoint(const vpImagePoint &ip, const vpColor &color, unsigned int thickness = 1) override; + void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness = 1) vp_override; + void displayPoint(const vpImagePoint &ip, const vpColor &color, unsigned int thickness = 1) vp_override; void displayRectangle(const vpImagePoint &topLeft, unsigned int width, unsigned int height, const vpColor &color, - bool fill = false, unsigned int thickness = 1) override; + bool fill = false, unsigned int thickness = 1) vp_override; void displayRectangle(const vpImagePoint &topLeft, const vpImagePoint &bottomRight, const vpColor &color, - bool fill = false, unsigned int thickness = 1) override; - void displayRectangle(const vpRect &rectangle, const vpColor &color, bool fill = false, unsigned int thickness = 1) override; + bool fill = false, unsigned int thickness = 1) vp_override; + void displayRectangle(const vpRect &rectangle, const vpColor &color, bool fill = false, unsigned int thickness = 1) vp_override; - void displayText(const vpImagePoint &ip, const std::string &text, const vpColor &color = vpColor::green) override; + void displayText(const vpImagePoint &ip, const std::string &text, const vpColor &color = vpColor::green) vp_override; - void flushDisplay() override; - void flushDisplayROI(const vpImagePoint &iP, unsigned int width, unsigned int height) override; + void flushDisplay() vp_override; + void flushDisplayROI(const vpImagePoint &iP, unsigned int width, unsigned int height) vp_override; - bool getClick(bool blocking = true) override; - bool getClick(vpImagePoint &ip, bool blocking = true) override; - bool getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) override; - bool getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) override; + bool getClick(bool blocking = true) vp_override; + bool getClick(vpImagePoint &ip, bool blocking = true) vp_override; + bool getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) vp_override; + bool getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonType &button, bool blocking = true) vp_override; - bool getKeyboardEvent(bool blocking = true) override; - bool getKeyboardEvent(std::string &key, bool blocking = true) override; + bool getKeyboardEvent(bool blocking = true) vp_override; + bool getKeyboardEvent(std::string &key, bool blocking = true) vp_override; - bool getPointerMotionEvent(vpImagePoint &ip) override; - bool getPointerPosition(vpImagePoint &ip) override; + bool getPointerMotionEvent(vpImagePoint &ip) vp_override; + bool getPointerPosition(vpImagePoint &ip) vp_override; - void setFont(const std::string &font) override; - void setTitle(const std::string &title) override; - void setWindowPosition(int win_x, int win_y) override; + void setFont(const std::string &font) vp_override; + void setTitle(const std::string &title) vp_override; + void setWindowPosition(int win_x, int win_y) vp_override; private: // Implementation diff --git a/modules/gui/include/visp3/gui/vpGDIRenderer.h b/modules/gui/include/visp3/gui/vpGDIRenderer.h index 203cc6d065..ea195e1e9f 100644 --- a/modules/gui/include/visp3/gui/vpGDIRenderer.h +++ b/modules/gui/include/visp3/gui/vpGDIRenderer.h @@ -110,7 +110,7 @@ class VISP_EXPORT vpGDIRenderer : public vpWin32Renderer void drawArrow(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int w, unsigned int h, unsigned int thickness = 1); - void getImage(vpImage &I) override; + void getImage(vpImage &I) vp_override; private: // updates the renderer hbitmaps. diff --git a/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp b/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp index c0874dfdf4..a28a934eba 100755 --- a/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp +++ b/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp @@ -35,12 +35,13 @@ #include #include +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::vector vpColorBlindFriendlyPalette::s_paletteNames = { "black" , "orange" , - "sky-blue" , + "sky-blue" , "green" , "yellow" , "blue" , @@ -205,3 +206,7 @@ std::istream &operator>>(std::istream &is, vpColorBlindFriendlyPalette &color) color.set_fromString(nameColor); return is; } + +#else +void dummy_vpColorBlindFriendlyPalette() { } +#endif diff --git a/modules/imgproc/src/vpRetinex.cpp b/modules/imgproc/src/vpRetinex.cpp index c05b4c0555..12340ff9ec 100644 --- a/modules/imgproc/src/vpRetinex.cpp +++ b/modules/imgproc/src/vpRetinex.cpp @@ -215,8 +215,11 @@ 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/src/image/vpImageIo.cpp b/modules/io/src/image/vpImageIo.cpp index 1c7ef72892..9d388879e8 100644 --- a/modules/io/src/image/vpImageIo.cpp +++ b/modules/io/src/image/vpImageIo.cpp @@ -418,7 +418,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": no backend available"; + const std::string message = "Cannot read file \"" + filename + "\": no backend available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -429,7 +429,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": jpeg library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": jpeg library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -439,7 +439,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": OpenCV library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": OpenCV library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -449,7 +449,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": stb_image backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": stb_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -459,7 +459,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": Simd library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": Simd library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -479,17 +479,13 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, int ba { if (backend == IO_SYSTEM_LIB_BACKEND) { #if !defined(VISP_HAVE_JPEG) - const std::string message = - "Libjpeg backend is not available to read file \"" + filename + "\": switch to stb_image backend"; - std::cerr << message << std::endl; + // 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) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) - const std::string message = - "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; - std::cerr << message << std::endl; + // OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif } @@ -505,7 +501,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, int ba #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": no backend available"; + const std::string message = "Cannot read file \"" + filename + "\": no backend available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -516,7 +512,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, int ba #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": jpeg library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": jpeg library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -526,7 +522,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, int ba #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": OpenCV library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": OpenCV library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -536,7 +532,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, int ba #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": stb_image backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": stb_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -546,7 +542,7 @@ void vpImageIo::readJPEG(vpImage &I, const std::string &filename, int ba #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": Simd library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": Simd library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -566,17 +562,13 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, { if (backend == IO_SYSTEM_LIB_BACKEND) { #if !defined(VISP_HAVE_PNG) - const std::string message = - "Libpng backend is not available to read file \"" + filename + "\": switch to stb_image backend"; - std::cerr << message << std::endl; + // 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) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) - const std::string message = - "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; - std::cerr << message << std::endl; + // OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif } @@ -592,7 +584,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": no backend available"; + const std::string message = "Cannot read file \"" + filename + "\": no backend available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -603,7 +595,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": png library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": png library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -613,7 +605,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": OpenCV library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": OpenCV library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -623,7 +615,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": stb_image backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": stb_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -633,7 +625,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": Simd library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": Simd library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -653,17 +645,13 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, int bac { if (backend == IO_SYSTEM_LIB_BACKEND) { #if !defined(VISP_HAVE_PNG) - const std::string message = - "Libpng backend is not available to read file \"" + filename + "\": switch to stb_image backend"; - std::cerr << message << std::endl; + // 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) { #if !(defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS)) - const std::string message = - "OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; - std::cerr << message << std::endl; + // OpenCV backend is not available to read file \"" + filename + "\": switch to stb_image backend"; backend = IO_STB_IMAGE_BACKEND; #endif } @@ -677,7 +665,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, int bac #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": no backend available"; + const std::string message = "Cannot read file \"" + filename + "\": no backend available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -688,7 +676,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, int bac #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": png library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": png library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -698,7 +686,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, int bac #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": OpenCV library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": OpenCV library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -708,7 +696,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, int bac #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": stb_image backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": stb_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -718,7 +706,7 @@ void vpImageIo::readPNG(vpImage &I, const std::string &filename, int bac #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": Simd library backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": Simd library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -757,7 +745,7 @@ void vpImageIo::readEXR(vpImage &I, const std::string &filename, int back #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": OpenCV backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": OpenCV backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -767,7 +755,7 @@ void vpImageIo::readEXR(vpImage &I, const std::string &filename, int back #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": Default TinyEXR backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": Default TinyEXR backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -806,7 +794,7 @@ void vpImageIo::readEXR(vpImage &I, const std::string &filename, int bac #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": OpenCV backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": OpenCV backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -816,7 +804,7 @@ void vpImageIo::readEXR(vpImage &I, const std::string &filename, int bac #else (void)I; (void)filename; - std::string message = "Cannot read file \"" + filename + "\": TinyEXR backend is not available"; + const std::string message = "Cannot read file \"" + filename + "\": TinyEXR backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -869,7 +857,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &fi #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": no available backend"; + const std::string message = "Cannot save file \"" + filename + "\": no available backend"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -881,7 +869,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &fi (void)I; (void)filename; (void)quality; - std::string message = "Cannot save file \"" + filename + "\": jpeg backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": jpeg backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -893,7 +881,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &fi (void)I; (void)filename; (void)quality; - std::string message = "Cannot save file \"" + filename + "\": OpenCV backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": OpenCV backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -904,7 +892,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &fi (void)I; (void)filename; (void)quality; - std::string message = "Cannot save file \"" + filename + "\": Simd library backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": Simd library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -915,7 +903,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &fi (void)I; (void)filename; (void)quality; - std::string message = "Cannot save file \"" + filename + "\": stb_image backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": stb_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -968,7 +956,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": no backend available"; + const std::string message = "Cannot save file \"" + filename + "\": no backend available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -980,7 +968,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &filename, (void)I; (void)filename; (void)quality; - std::string message = "Cannot save file \"" + filename + "\": jpeg library backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": jpeg library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -991,7 +979,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &filename, (void)I; (void)filename; (void)quality; - std::string message = "Cannot save file \"" + filename + "\": OpenCV library backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": OpenCV library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1002,7 +990,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &filename, (void)I; (void)filename; (void)quality; - std::string message = "Cannot save file \"" + filename + "\": Simd library backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": Simd library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1013,7 +1001,7 @@ void vpImageIo::writeJPEG(const vpImage &I, const std::string &filename, (void)I; (void)filename; (void)quality; - std::string message = "Cannot save file \"" + filename + "\": stb_image backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": stb_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1063,7 +1051,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &fil #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": no backend available"; + const std::string message = "Cannot save file \"" + filename + "\": no backend available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1074,7 +1062,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &fil #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": OpenCV library backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": OpenCV library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1084,7 +1072,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &fil #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": Simd library backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": Simd library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1094,7 +1082,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &fil #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": stb_image backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": stb_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1104,7 +1092,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &fil #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": png library backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": png library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1154,7 +1142,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": no backend available"; + const std::string message = "Cannot save file \"" + filename + "\": no backend available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1165,7 +1153,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": OpenCV backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": OpenCV backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1175,7 +1163,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": Simd library backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": Simd library backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1185,7 +1173,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": stb_image backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": stb_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1195,7 +1183,7 @@ void vpImageIo::writePNG(const vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": libpng backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": libpng backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1235,7 +1223,7 @@ void vpImageIo::writeEXR(const vpImage &I, const std::string &filename, i #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": OpenCV backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": OpenCV backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1245,7 +1233,7 @@ void vpImageIo::writeEXR(const vpImage &I, const std::string &filename, i #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": TinyEXR backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": TinyEXR backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1284,7 +1272,7 @@ void vpImageIo::writeEXR(const vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": OpenCV backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": OpenCV backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1294,7 +1282,7 @@ void vpImageIo::writeEXR(const vpImage &I, const std::string &filename, #else (void)I; (void)filename; - std::string message = "Cannot save file \"" + filename + "\": TinyEXR backend is not available"; + const std::string message = "Cannot save file \"" + filename + "\": TinyEXR backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1432,7 +1420,7 @@ void vpImageIo::readPNGfromMem(const std::vector &buffer, vpImage #else (void)I; (void)buffer; - std::string message = "Cannot in-memory png read: OpenCV or std_image backend are not available"; + const std::string message = "Cannot in-memory png read: OpenCV or std_image backend are not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1446,7 +1434,7 @@ void vpImageIo::readPNGfromMem(const std::vector &buffer, vpImage (void)buffer; (void)I; (void)backend; - std::string message = "Cannot in-memory png read: OpenCV backend is not available"; + const std::string message = "Cannot in-memory png read: OpenCV backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1458,7 +1446,7 @@ void vpImageIo::readPNGfromMem(const std::vector &buffer, vpImage (void)buffer; (void)I; (void)backend; - std::string message = "Cannot in-memory png read: std_image backend is not available"; + const std::string message = "Cannot in-memory png read: std_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1489,7 +1477,7 @@ void vpImageIo::readPNGfromMem(const std::vector &buffer, vpImage #else (void)I; (void)buffer; - std::string message = "Cannot in-memory png read: OpenCV or std_image backend are not available"; + const std::string message = "Cannot in-memory png read: OpenCV or std_image backend are not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1503,7 +1491,7 @@ void vpImageIo::readPNGfromMem(const std::vector &buffer, vpImage (void)buffer; (void)I; (void)backend; - std::string message = "Cannot in-memory png read: OpenCV backend is not available"; + const std::string message = "Cannot in-memory png read: OpenCV backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1515,7 +1503,7 @@ void vpImageIo::readPNGfromMem(const std::vector &buffer, vpImage (void)buffer; (void)I; (void)backend; - std::string message = "Cannot in-memory png read: std_image backend is not available"; + const std::string message = "Cannot in-memory png read: std_image backend is not available"; throw(vpImageException(vpImageException::ioError, message)); #endif } @@ -1547,7 +1535,7 @@ void vpImageIo::writePNGtoMem(const vpImage &I, std::vector &I, std::vector &I, std::vector &I, std::vector &I, std::vector &I, std::vector &I); void getCameraParameters(vpCameraParameters &cam, const vpImage &I); - void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement) override; - void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) override; + void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement) vp_override; + void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) vp_override; void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q, double ×tamp); void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position); void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double ×tamp); @@ -205,8 +205,8 @@ class VISP_EXPORT vpSimulatorAfma6 : public vpRobotWireFrameSimulator, public vp void get_cMe(vpHomogeneousMatrix &cMe); void get_cVe(vpVelocityTwistMatrix &cVe); - void get_eJe(vpMatrix &eJe) override; - void get_fJe(vpMatrix &fJe) override; + void get_eJe(vpMatrix &eJe) vp_override; + void get_fJe(vpMatrix &fJe) vp_override; void init(vpAfma6::vpAfma6ToolType tool, @@ -221,26 +221,26 @@ class VISP_EXPORT vpSimulatorAfma6 : public vpRobotWireFrameSimulator, public vp void setCameraParameters(const vpCameraParameters &cam); void setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax); - void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) override; + void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) vp_override; void setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3, double pos4, double pos5, double pos6); void setPosition(const char *filename); void setPositioningVelocity(double vel) { positioningVelocity = vel; } bool setPosition(const vpHomogeneousMatrix &cdMo, vpImage *Iint = nullptr, const double &errMax = 0.001); - vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState) override; + vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState) vp_override; - void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) override; + void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) vp_override; void stopMotion(); protected: /** @name Protected Member Functions Inherited from vpSimulatorAfma6 */ //@{ - void computeArticularVelocity() override; + void computeArticularVelocity() vp_override; void compute_fMi(); void findHighestPositioningSpeed(vpColVector &q); void getExternalImage(vpImage &I); - inline void get_fMi(vpHomogeneousMatrix *fMit) override + inline void get_fMi(vpHomogeneousMatrix *fMit) vp_override { m_mutex_fMi.lock(); for (int i = 0; i < 8; i++) { @@ -249,12 +249,12 @@ class VISP_EXPORT vpSimulatorAfma6 : public vpRobotWireFrameSimulator, public vp m_mutex_fMi.unlock(); } - void init() override; - void initArms() override; + void init() vp_override; + void initArms() vp_override; void initDisplay(); - int isInJointLimit() override; + int isInJointLimit() vp_override; bool singularityTest(const vpColVector &q, vpMatrix &J); - void updateArticularPosition() override; + void updateArticularPosition() vp_override; //@} }; diff --git a/modules/robot/include/visp3/robot/vpSimulatorCamera.h b/modules/robot/include/visp3/robot/vpSimulatorCamera.h index a3f474f4e3..e5d33592a4 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorCamera.h +++ b/modules/robot/include/visp3/robot/vpSimulatorCamera.h @@ -111,22 +111,22 @@ class VISP_EXPORT vpSimulatorCamera : public vpRobotSimulator /** @name Inherited functionalities from vpSimulatorCamera */ //@{ void get_cVe(vpVelocityTwistMatrix &cVe) const; - void get_eJe(vpMatrix &eJe) override; + void get_eJe(vpMatrix &eJe) vp_override; vpHomogeneousMatrix getPosition() const; void getPosition(vpHomogeneousMatrix &wMc) const; - void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) override; + void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) vp_override; void setPosition(const vpHomogeneousMatrix &wMc); - void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) override; + void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) vp_override; //@} private: - void init() override; + void init() vp_override; // Non implemented virtual pure functions - void get_fJe(vpMatrix & /*_fJe */) override { }; - void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) override { }; - void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) override { }; + void get_fJe(vpMatrix & /*_fJe */) vp_override { }; + void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) vp_override { }; + void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) vp_override { }; }; #endif diff --git a/modules/robot/include/visp3/robot/vpSimulatorPioneer.h b/modules/robot/include/visp3/robot/vpSimulatorPioneer.h index e58064e504..7df272f7b4 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorPioneer.h +++ b/modules/robot/include/visp3/robot/vpSimulatorPioneer.h @@ -115,20 +115,20 @@ class VISP_EXPORT vpSimulatorPioneer : public vpPioneer, public vpRobotSimulator public: /** @name Inherited functionalities from vpSimulatorPioneer */ //@{ - void get_eJe(vpMatrix &eJe) override; + void get_eJe(vpMatrix &eJe) vp_override; void getPosition(vpHomogeneousMatrix &wMc) const; - void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) override; - void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) override; + void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) vp_override; + void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) vp_override; //@} private: - void init() override; + void init() vp_override; // Non implemented virtual pure functions - void get_fJe(vpMatrix & /*_fJe */) override { }; - void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) override { }; - void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) override { }; + void get_fJe(vpMatrix & /*_fJe */) vp_override { }; + void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) vp_override { }; + void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) vp_override { }; }; #endif diff --git a/modules/robot/include/visp3/robot/vpSimulatorPioneerPan.h b/modules/robot/include/visp3/robot/vpSimulatorPioneerPan.h index 25c8e2ac59..5af9d8d45c 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorPioneerPan.h +++ b/modules/robot/include/visp3/robot/vpSimulatorPioneerPan.h @@ -116,20 +116,20 @@ class VISP_EXPORT vpSimulatorPioneerPan : public vpPioneerPan, public vpRobotSim public: /** @name Inherited functionalities from vpSimulatorPioneerPan */ //@{ - void get_eJe(vpMatrix &eJe) override; + void get_eJe(vpMatrix &eJe) vp_override; void getPosition(vpHomogeneousMatrix &wMc) const; - void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) override; - void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) override; + void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) vp_override; + void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) vp_override; //@} private: - void init() override; + void init() vp_override; // Non implemented virtual pure functions - void get_fJe(vpMatrix & /*_fJe */) override { }; - void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) override { }; - void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) override { }; + void get_fJe(vpMatrix & /*_fJe */) vp_override { }; + void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) vp_override { }; + void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) vp_override { }; }; #endif diff --git a/modules/robot/include/visp3/robot/vpSimulatorViper850.h b/modules/robot/include/visp3/robot/vpSimulatorViper850.h index 627b4dd7ab..fe39abee69 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorViper850.h +++ b/modules/robot/include/visp3/robot/vpSimulatorViper850.h @@ -212,15 +212,15 @@ class VISP_EXPORT vpSimulatorViper850 : public vpRobotWireFrameSimulator, public public: vpSimulatorViper850(); explicit vpSimulatorViper850(bool display); - virtual ~vpSimulatorViper850() override; + virtual ~vpSimulatorViper850() vp_override; void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height); void getCameraParameters(vpCameraParameters &cam, const vpImage &I); void getCameraParameters(vpCameraParameters &cam, const vpImage &I); - void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement) override; + void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement) vp_override; - void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) override; + void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) vp_override; void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q, double ×tamp); void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position); void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double ×tamp); @@ -233,8 +233,8 @@ class VISP_EXPORT vpSimulatorViper850 : public vpRobotWireFrameSimulator, public void get_cMe(vpHomogeneousMatrix &cMe); void get_cVe(vpVelocityTwistMatrix &cVe); - void get_eJe(vpMatrix &eJe) override; - void get_fJe(vpMatrix &fJe) override; + void get_eJe(vpMatrix &eJe) vp_override; + void get_fJe(vpMatrix &fJe) vp_override; void init(vpViper850::vpToolType tool, @@ -249,26 +249,26 @@ class VISP_EXPORT vpSimulatorViper850 : public vpRobotWireFrameSimulator, public void setCameraParameters(const vpCameraParameters &cam); void setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax); - void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) override; + void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) vp_override; void setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3, double pos4, double pos5, double pos6); void setPosition(const char *filename); void setPositioningVelocity(double vel) { positioningVelocity = vel; } - vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState) override; + vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState) vp_override; - void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) override; + void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) vp_override; void stopMotion(); protected: /** @name Protected Member Functions Inherited from vpSimulatorViper850 */ //@{ - void computeArticularVelocity() override; + void computeArticularVelocity() vp_override; void compute_fMi(); void findHighestPositioningSpeed(vpColVector &q); void getExternalImage(vpImage &I); - inline void get_fMi(vpHomogeneousMatrix *fMit) override + inline void get_fMi(vpHomogeneousMatrix *fMit) vp_override { m_mutex_fMi.lock(); for (int i = 0; i < 8; i++) { @@ -276,12 +276,12 @@ class VISP_EXPORT vpSimulatorViper850 : public vpRobotWireFrameSimulator, public } m_mutex_fMi.unlock(); } - void init() override; - void initArms() override; + void init() vp_override; + void initArms() vp_override; void initDisplay(); - int isInJointLimit() override; + int isInJointLimit() vp_override; bool singularityTest(const vpColVector &q, vpMatrix &J); - void updateArticularPosition() override; + void updateArticularPosition() vp_override; //@} }; diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h index 80edb39c38..f4dcd6e53f 100755 --- a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h +++ b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h @@ -102,7 +102,7 @@ class VISP_EXPORT vpForceTorqueAtiNetFTSensor : public vpUDPClient public: vpForceTorqueAtiNetFTSensor(); vpForceTorqueAtiNetFTSensor(const std::string &hostname, int port); - virtual ~vpForceTorqueAtiNetFTSensor() override; + virtual ~vpForceTorqueAtiNetFTSensor() vp_override; void bias(unsigned int n_counts = 50); /*! diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h index de7033e568..c1ac32aeec 100644 --- a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h +++ b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h @@ -85,7 +85,7 @@ class VISP_EXPORT vpForceTorqueAtiSensor : public vpComedi { public: vpForceTorqueAtiSensor(); - virtual ~vpForceTorqueAtiSensor() override; + virtual ~vpForceTorqueAtiSensor() vp_override; void bias(); void close(); diff --git a/modules/sensor/include/visp3/sensor/vpLaserScan.h b/modules/sensor/include/visp3/sensor/vpLaserScan.h index 2c659552f2..64a638dbbf 100644 --- a/modules/sensor/include/visp3/sensor/vpLaserScan.h +++ b/modules/sensor/include/visp3/sensor/vpLaserScan.h @@ -89,10 +89,11 @@ 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. */ + /*! Specifies the id of former measurements and increases with every measurement. */ inline void setMeasurementId(const unsigned short &id) { this->measurementId = id; } /*! Start time of measurement. */ inline void setStartTimestamp(const double &start_timestamp) { this->startTimestamp = start_timestamp; } diff --git a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h index 48173e26dd..e425b5a2c9 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) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include @@ -215,7 +215,7 @@ struct SessionDelegate : ST::CaptureSessionDelegate ~SessionDelegate() { } - void captureSessionEventDidOccur(ST::CaptureSession *session, ST::CaptureSessionEventId event) override + void captureSessionEventDidOccur(ST::CaptureSession *session, ST::CaptureSessionEventId event) vp_override { switch (event) { case ST::CaptureSessionEventId::Booting: @@ -242,7 +242,7 @@ struct SessionDelegate : ST::CaptureSessionDelegate } } - void captureSessionDidOutputSample(ST::CaptureSession *, const ST::CaptureSessionSample &sample) override + void captureSessionDidOutputSample(ST::CaptureSession *, const ST::CaptureSessionSample &sample) vp_override { // acquire sampleLock mutex. std::lock_guard u(m_sampleLock); diff --git a/modules/sensor/include/visp3/sensor/vpRealSense.h b/modules/sensor/include/visp3/sensor/vpRealSense.h index 05975be0b9..96dfc0322c 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) +#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include diff --git a/modules/sensor/include/visp3/sensor/vpRealSense2.h b/modules/sensor/include/visp3/sensor/vpRealSense2.h index 3e40c7ed14..6cff43fae8 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) +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include diff --git a/modules/sensor/include/visp3/sensor/vpScanPoint.h b/modules/sensor/include/visp3/sensor/vpScanPoint.h index f2633e72ef..28904ce659 100644 --- a/modules/sensor/include/visp3/sensor/vpScanPoint.h +++ b/modules/sensor/include/visp3/sensor/vpScanPoint.h @@ -143,7 +143,9 @@ 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/include/visp3/sensor/vpSickLDMRS.h b/modules/sensor/include/visp3/sensor/vpSickLDMRS.h index 650e6aec4d..a1bddca0c2 100644 --- a/modules/sensor/include/visp3/sensor/vpSickLDMRS.h +++ b/modules/sensor/include/visp3/sensor/vpSickLDMRS.h @@ -121,7 +121,7 @@ class VISP_EXPORT vpSickLDMRS : public vpLaserScanner { *this = sick; }; - virtual ~vpSickLDMRS() override; + virtual ~vpSickLDMRS() vp_override; /*! Copy operator. */ vpSickLDMRS &operator=(const vpSickLDMRS &sick) diff --git a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp index d2f06ed1f8..e618733b24 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) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include #include diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp index f0605385d8..807e4e1c51 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) +#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include "vpRealSense_impl.h" diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp index 93a918cf3a..15b9a43659 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) +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include #include diff --git a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp index 3fbbaee648..5cb41fd510 100644 --- a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp +++ b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp @@ -43,7 +43,8 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && ( VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 ) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include @@ -126,6 +127,10 @@ 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 05be0da7a8..8e80daacec 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) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTUR ) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include @@ -117,9 +117,16 @@ 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 c591caed22..3839e01e26 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) && (defined(VISP_HAVE_PCL)) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_PCL)) #ifdef VISP_HAVE_PCL #include @@ -133,12 +133,16 @@ int main() #else int main() { -#if !defined(VISP_HAVE_OCCIPITAL_STRUCTURE) +#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 !defined(VISP_HAVE_PCL) +#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 return EXIT_SUCCESS; diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp index 39073eb05f..a6e6ef61f8 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp @@ -41,7 +41,8 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp index 4610f12de3..25ea353468 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp @@ -40,7 +40,8 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_PCL) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ + && defined(VISP_HAVE_PCL) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp index 06cdf1084f..e2edda80bb 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) && \ +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (VISP_HAVE_OPENCV_VERSION >= 0x030000) #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp index f4caef1ea4..325347c53d 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp @@ -41,7 +41,8 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PCL) +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PCL) #include #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp index d4fb566e39..ea1024dbee 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp @@ -42,7 +42,8 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #ifdef VISP_HAVE_PCL #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp index 895035d488..a72de4d844 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) && \ +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() 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 5f84a4d420..a76074c0f6 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) && \ +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) #include 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 dea908efda..94581a572e 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) && \ +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp index 17f939e52c..a16868d488 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) && \ +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp index 63053891bd..ec2ad878ba 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) && \ +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp index 12d2d0b88b..27210cc8e0 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) && \ +#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) int main() diff --git a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp b/modules/sensor/test/rgb-depth/testRealSense_R200.cpp index 30485d63e8..f7447fa48d 100644 --- a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense_R200.cpp @@ -46,7 +46,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include @@ -581,6 +581,9 @@ 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 9e3821bd9d..d37e15e113 100644 --- a/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp @@ -46,7 +46,7 @@ #include #include -#if defined(VISP_HAVE_REALSENSE) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include @@ -514,6 +514,10 @@ 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/blob/include/visp3/blob/vpDot.h b/modules/tracker/blob/include/visp3/blob/vpDot.h index ef8e4190f5..fb76621f56 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot.h @@ -191,7 +191,7 @@ class VISP_EXPORT vpDot : public vpTracker vpDot(); explicit vpDot(const vpImagePoint &ip); vpDot(const vpDot &d); - virtual ~vpDot() override; + virtual ~vpDot() vp_override; void display(const vpImage &I, vpColor color = vpColor::red, unsigned int thickness = 1) const; diff --git a/modules/tracker/blob/include/visp3/blob/vpDot2.h b/modules/tracker/blob/include/visp3/blob/vpDot2.h index ec8171ebda..2e3c4b1130 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot2.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot2.h @@ -488,13 +488,9 @@ class VISP_EXPORT vpDot2 : public vpTracker double width; double height; double surface; - unsigned int gray_level_min; // minumum gray level for the dot. - // pixel with lower level don't belong - // to this dot. + unsigned int gray_level_min; // minumum gray level for the dot. Pixel with lower level don't belong to this dot. - unsigned int gray_level_max; // maximum gray level for the dot. - // pixel with higher level don't belong - // to this dot. + unsigned int gray_level_max; // maximum gray level for the dot. Pixel with higher level don't belong to this dot. double mean_gray_level; // Mean gray level of the dot double grayLevelPrecision; double gamma; diff --git a/modules/tracker/blob/src/dots/vpDot2.cpp b/modules/tracker/blob/src/dots/vpDot2.cpp index 4de44dbb60..be938889d4 100644 --- a/modules/tracker/blob/src/dots/vpDot2.cpp +++ b/modules/tracker/blob/src/dots/vpDot2.cpp @@ -271,7 +271,7 @@ void vpDot2::initTracking(const vpImage &I, unsigned int size) track(I); } catch (const vpException &e) { - // vpERROR_TRACE("Error caught") ; + // vpERROR_TRACE("Error caught") ; throw(e); } } @@ -331,7 +331,7 @@ void vpDot2::initTracking(const vpImage &I, const vpImagePoint &i track(I); } catch (const vpException &e) { - // vpERROR_TRACE("Error caught") ; + // vpERROR_TRACE("Error caught") ; throw(e); } } @@ -390,7 +390,7 @@ void vpDot2::initTracking(const vpImage &I, const vpImagePoint &i track(I); } catch (const vpException &e) { - // vpERROR_TRACE("Error caught") ; + // vpERROR_TRACE("Error caught") ; throw(e); } } @@ -1100,8 +1100,9 @@ void vpDot2::searchDotsInArea(const vpImage &I, int area_u, int a // otherwise estimate the width, height and surface of the dot we // created, and test it. - if (dotToTest != nullptr) + if (dotToTest != nullptr) { delete dotToTest; + } dotToTest = getInstance(); dotToTest->setCog(germ); dotToTest->setGrayLevelMin(getGrayLevelMin()); @@ -1190,13 +1191,14 @@ void vpDot2::searchDotsInArea(const vpImage &I, int area_u, int a } } else { - // Store bad dots + // Store bad dots badDotsVector.push_front(*dotToTest); } } } - if (dotToTest != nullptr) + if (dotToTest != nullptr) { delete dotToTest; + } } /*! @@ -1234,7 +1236,7 @@ bool vpDot2::isValid(const vpImage &I, const vpDot2 &wantedDot) if ((std::fabs(wantedDot.getWidth()) > std::numeric_limits::epsilon()) && (std::fabs(wantedDot.getHeight()) > std::numeric_limits::epsilon()) && (std::fabs(wantedDot.getArea()) > std::numeric_limits::epsilon())) - // if (size_precision!=0){ + // if (size_precision!=0){ { if (std::fabs(size_precision) > std::numeric_limits::epsilon()) { double epsilon = 0.001; @@ -1751,7 +1753,7 @@ bool vpDot2::computeParameters(const vpImage &I, const double &_u \param border_v : The column coordinate of the found starting point. \return false if the width of this dot was initialised and we already -crossed the dot on more than the max possible width. Return true if success. + crossed the dot on more than the max possible width. Return true if success. \sa computeParameters() */ @@ -1879,8 +1881,8 @@ bool vpDot2::computeFreemanChainElement(const vpImage &I, const u element = (element + 3) % 8; // turn diag right down } else { - // No neighbor with a good level - // + // No neighbor with a good level + // return false; } } @@ -1927,8 +1929,6 @@ bool vpDot2::computeFreemanChainElement(const vpImage &I, const u Considering the previous coordinates (u_p, v_p) of a pixel on a border, the next coordinates (u, v) are given by: u = u_p + du and v = v_p + dv - - */ void vpDot2::computeFreemanParameters(const int &u_p, const int &v_p, unsigned int &element, int &du, int &dv, float &dS, float &dMu, float &dMv, float &dMuv, float &dMu2, float &dMv2) @@ -2414,11 +2414,12 @@ void vpDot2::trackAndDisplay(vpDot2 dot[], const unsigned int &n, vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; - virtual inline vpColVector getError() const override { return m_error_depthDense; } + virtual inline vpColVector getError() const vp_override { return m_error_depthDense; } virtual std::vector > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - bool displayFullModel = false) override; + bool displayFullModel = false) vp_override; - virtual inline vpColVector getRobustWeights() const override { return m_w_depthDense; } + virtual inline vpColVector getRobustWeights() const vp_override { return m_w_depthDense; } - virtual void init(const vpImage &I) override; + virtual void init(const vpImage &I) vp_override; - virtual void loadConfigFile(const std::string &configFile, bool verbose = true) override; + virtual void loadConfigFile(const std::string &configFile, bool verbose = true) vp_override; void reInitModel(const vpImage &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose = false); @@ -75,9 +75,9 @@ class VISP_EXPORT vpMbDepthDenseTracker : public virtual vpMbTracker const vpHomogeneousMatrix &cMo, bool verbose = false); #endif - virtual void resetTracker() override; + virtual void resetTracker() vp_override; - virtual void setCameraParameters(const vpCameraParameters &camera) override; + virtual void setCameraParameters(const vpCameraParameters &camera) vp_override; virtual void setDepthDenseFilteringMaxDistance(double maxDistance); virtual void setDepthDenseFilteringMethod(int method); @@ -95,22 +95,22 @@ class VISP_EXPORT vpMbDepthDenseTracker : public virtual vpMbTracker m_depthDenseSamplingStepY = stepY; } - virtual void setOgreVisibilityTest(const bool &v) override; + virtual void setOgreVisibilityTest(const bool &v) vp_override; - virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) override; - virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) override; + virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) vp_override; + virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) vp_override; #ifdef VISP_HAVE_PCL virtual void setPose(const pcl::PointCloud::ConstPtr &point_cloud, const vpHomogeneousMatrix &cdMo); #endif - virtual void setScanLineVisibilityTest(const bool &v) override; + virtual void setScanLineVisibilityTest(const bool &v) vp_override; void setUseDepthDenseTracking(const std::string &name, const bool &useDepthDenseTracking); - virtual void testTracking() override; + virtual void testTracking() vp_override; - virtual void track(const vpImage &) override; - virtual void track(const vpImage &) override; + virtual void track(const vpImage &) vp_override; + virtual void track(const vpImage &) vp_override; #ifdef VISP_HAVE_PCL virtual void track(const pcl::PointCloud::ConstPtr &point_cloud); #endif @@ -149,20 +149,20 @@ class VISP_EXPORT vpMbDepthDenseTracker : public virtual vpMbTracker void computeVisibility(unsigned int width, unsigned int height); void computeVVS(); - virtual void computeVVSInit() override; - virtual void computeVVSInteractionMatrixAndResidu() override; + virtual void computeVVSInit() vp_override; + virtual void computeVVSInteractionMatrixAndResidu() vp_override; virtual void computeVVSWeights(); using vpMbTracker::computeVVSWeights; virtual void initCircle(const vpPoint &p1, const vpPoint &p2, const vpPoint &p3, double radius, int idFace = 0, - const std::string &name = "") override; + const std::string &name = "") vp_override; virtual void initCylinder(const vpPoint &p1, const vpPoint &p2, double radius, int idFace = 0, - const std::string &name = "") override; + const std::string &name = "") vp_override; - virtual void initFaceFromCorners(vpMbtPolygon &polygon) override; + virtual void initFaceFromCorners(vpMbtPolygon &polygon) vp_override; - virtual void initFaceFromLines(vpMbtPolygon &polygon) override; + virtual void initFaceFromLines(vpMbtPolygon &polygon) vp_override; #ifdef VISP_HAVE_PCL void segmentPointCloud(const pcl::PointCloud::ConstPtr &point_cloud); diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h index ed3cca7ab3..91f3cab506 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h @@ -47,31 +47,31 @@ class VISP_EXPORT vpMbDepthNormalTracker : public virtual vpMbTracker { public: vpMbDepthNormalTracker(); - virtual ~vpMbDepthNormalTracker() override; + virtual ~vpMbDepthNormalTracker() vp_override; virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual inline vpMbtFaceDepthNormal::vpFeatureEstimationType getDepthFeatureEstimationMethod() const { return m_depthNormalFeatureEstimationMethod; } - virtual inline vpColVector getError() const override { return m_error_depthNormal; } + virtual inline vpColVector getError() const vp_override { return m_error_depthNormal; } virtual std::vector > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - bool displayFullModel = false) override; + bool displayFullModel = false) vp_override; - virtual inline vpColVector getRobustWeights() const override { return m_w_depthNormal; } + virtual inline vpColVector getRobustWeights() const vp_override { return m_w_depthNormal; } - virtual void init(const vpImage &I) override; + virtual void init(const vpImage &I) vp_override; - virtual void loadConfigFile(const std::string &configFile, bool verbose = true) override; + virtual void loadConfigFile(const std::string &configFile, bool verbose = true) vp_override; void reInitModel(const vpImage &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose = false); @@ -80,9 +80,9 @@ class VISP_EXPORT vpMbDepthNormalTracker : public virtual vpMbTracker const vpHomogeneousMatrix &cMo, bool verbose = false); #endif - virtual void resetTracker() override; + virtual void resetTracker() vp_override; - virtual void setCameraParameters(const vpCameraParameters &camera) override; + virtual void setCameraParameters(const vpCameraParameters &camera) vp_override; virtual void setDepthNormalFaceCentroidMethod(const vpMbtFaceDepthNormal::vpFaceCentroidType &method); @@ -98,22 +98,22 @@ class VISP_EXPORT vpMbDepthNormalTracker : public virtual vpMbTracker // virtual void setDepthNormalUseRobust(bool use); - virtual void setOgreVisibilityTest(const bool &v) override; + virtual void setOgreVisibilityTest(const bool &v) vp_override; - virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) override; - virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) override; + virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) vp_override; + virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) vp_override; #if defined(VISP_HAVE_PCL) virtual void setPose(const pcl::PointCloud::ConstPtr &point_cloud, const vpHomogeneousMatrix &cdMo); #endif - virtual void setScanLineVisibilityTest(const bool &v) override; + virtual void setScanLineVisibilityTest(const bool &v) vp_override; void setUseDepthNormalTracking(const std::string &name, const bool &useDepthNormalTracking); - virtual void testTracking() override; + virtual void testTracking() vp_override; - virtual void track(const vpImage &) override; - virtual void track(const vpImage &I_color) override; + virtual void track(const vpImage &) vp_override; + virtual void track(const vpImage &I_color) vp_override; #if defined(VISP_HAVE_PCL) virtual void track(const pcl::PointCloud::ConstPtr &point_cloud); #endif @@ -164,20 +164,20 @@ class VISP_EXPORT vpMbDepthNormalTracker : public virtual vpMbTracker void computeVisibility(unsigned int width, unsigned int height); void computeVVS(); - virtual void computeVVSInit() override; - virtual void computeVVSInteractionMatrixAndResidu() override; + virtual void computeVVSInit() vp_override; + virtual void computeVVSInteractionMatrixAndResidu() vp_override; virtual std::vector > getFeaturesForDisplayDepthNormal(); virtual void initCircle(const vpPoint &p1, const vpPoint &p2, const vpPoint &p3, double radius, int idFace = 0, - const std::string &name = "") override; + const std::string &name = "") vp_override; virtual void initCylinder(const vpPoint &p1, const vpPoint &p2, double radius, int idFace = 0, - const std::string &name = "") override; + const std::string &name = "") vp_override; - virtual void initFaceFromCorners(vpMbtPolygon &polygon) override; + virtual void initFaceFromCorners(vpMbtPolygon &polygon) vp_override; - virtual void initFaceFromLines(vpMbtPolygon &polygon) override; + virtual void initFaceFromLines(vpMbtPolygon &polygon) vp_override; #ifdef VISP_HAVE_PCL void segmentPointCloud(const pcl::PointCloud::ConstPtr &point_cloud); diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h index 4ab137f519..e2c0508b4e 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h @@ -230,33 +230,33 @@ class VISP_EXPORT vpMbEdgeKltTracker : virtual ~vpMbEdgeKltTracker(); virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; - virtual inline vpColVector getError() const override { return m_error_hybrid; } + virtual inline vpColVector getError() const vp_override { return m_error_hybrid; } virtual std::vector > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - bool displayFullModel = false) override; + bool displayFullModel = false) vp_override; - virtual inline vpColVector getRobustWeights() const override { return m_w_hybrid; } + virtual inline vpColVector getRobustWeights() const vp_override { return m_w_hybrid; } /*! * Get the near distance for clipping. * * \return Near clipping value. */ - virtual inline double getNearClippingDistance() const override { return vpMbKltTracker::getNearClippingDistance(); } + virtual inline double getNearClippingDistance() const vp_override { return vpMbKltTracker::getNearClippingDistance(); } - virtual void loadConfigFile(const std::string &configFile, bool verbose = true) override; + virtual void loadConfigFile(const std::string &configFile, bool verbose = true) vp_override; void reInitModel(const vpImage &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo, - bool verbose = false, const vpHomogeneousMatrix &T = vpHomogeneousMatrix()) override; - void resetTracker() override; + bool verbose = false, const vpHomogeneousMatrix &T = vpHomogeneousMatrix()) vp_override; + void resetTracker() vp_override; - virtual void setCameraParameters(const vpCameraParameters &cam) override; + virtual void setCameraParameters(const vpCameraParameters &cam) vp_override; /*! * Specify which clipping to use. @@ -265,21 +265,21 @@ class VISP_EXPORT vpMbEdgeKltTracker : * * \param flags : New clipping flags. */ - virtual void setClipping(const unsigned int &flags) override { vpMbEdgeTracker::setClipping(flags); } + virtual void setClipping(const unsigned int &flags) vp_override { vpMbEdgeTracker::setClipping(flags); } /*! * Set the far distance for clipping. * * \param dist : Far clipping value. */ - virtual void setFarClippingDistance(const double &dist) override { vpMbEdgeTracker::setFarClippingDistance(dist); } + virtual void setFarClippingDistance(const double &dist) vp_override { vpMbEdgeTracker::setFarClippingDistance(dist); } /*! * Set the near distance for clipping. * * \param dist : Near clipping value. */ - virtual void setNearClippingDistance(const double &dist) override { vpMbEdgeTracker::setNearClippingDistance(dist); } + virtual void setNearClippingDistance(const double &dist) vp_override { vpMbEdgeTracker::setNearClippingDistance(dist); } /*! * Use Ogre3D for visibility tests @@ -289,7 +289,7 @@ class VISP_EXPORT vpMbEdgeKltTracker : * * \param v : True to use it, False otherwise */ - virtual void setOgreVisibilityTest(const bool &v) override + virtual void setOgreVisibilityTest(const bool &v) vp_override { vpMbTracker::setOgreVisibilityTest(v); #ifdef VISP_HAVE_OGRE @@ -302,14 +302,14 @@ class VISP_EXPORT vpMbEdgeKltTracker : * * \param v : True to use it, False otherwise */ - virtual void setScanLineVisibilityTest(const bool &v) override + virtual void setScanLineVisibilityTest(const bool &v) vp_override { vpMbEdgeTracker::setScanLineVisibilityTest(v); vpMbKltTracker::setScanLineVisibilityTest(v); } - virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) override; - virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) override; + virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) vp_override; + virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) vp_override; /*! * Set if the projection error criteria has to be computed. @@ -317,29 +317,29 @@ class VISP_EXPORT vpMbEdgeKltTracker : * \param flag : True if the projection error criteria has to be computed, * false otherwise */ - virtual void setProjectionErrorComputation(const bool &flag) override + virtual void setProjectionErrorComputation(const bool &flag) vp_override { vpMbEdgeTracker::setProjectionErrorComputation(flag); } - virtual void testTracking() override { } - virtual void track(const vpImage &I) override; - virtual void track(const vpImage &I_color) override; + virtual void testTracking() vp_override { } + virtual void track(const vpImage &I) vp_override; + virtual void track(const vpImage &I_color) vp_override; protected: virtual void computeVVS(const vpImage &I, const unsigned int &nbInfos, unsigned int &nbrow, unsigned int lvl = 0, double *edge_residual = nullptr, double *klt_residual = nullptr); - virtual void computeVVSInit() override; - virtual void computeVVSInteractionMatrixAndResidu() override; + virtual void computeVVSInit() vp_override; + virtual void computeVVSInteractionMatrixAndResidu() vp_override; using vpMbTracker::computeCovarianceMatrixVVS; using vpMbTracker::computeVVSPoseEstimation; - virtual void init(const vpImage &I) override; + virtual void init(const vpImage &I) vp_override; virtual void initCircle(const vpPoint &, const vpPoint &, const vpPoint &, double r, int idFace = 0, - const std::string &name = "") override; - virtual void initCylinder(const vpPoint &, const vpPoint &, double r, int idFace, const std::string &name = "") override; - virtual void initFaceFromCorners(vpMbtPolygon &polygon) override; - virtual void initFaceFromLines(vpMbtPolygon &polygon) override; + const std::string &name = "") vp_override; + virtual void initCylinder(const vpPoint &, const vpPoint &, double r, int idFace, const std::string &name = "") vp_override; + virtual void initFaceFromCorners(vpMbtPolygon &polygon) vp_override; + virtual void initFaceFromLines(vpMbtPolygon &polygon) vp_override; unsigned int initMbtTracking(unsigned int level = 0); bool postTracking(const vpImage &I, vpColVector &w_mbt, vpColVector &w_klt, unsigned int lvl = 0); diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h index 4f5073230f..866a3fdb36 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h @@ -310,15 +310,15 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker public: vpMbEdgeTracker(); - virtual ~vpMbEdgeTracker() override; + virtual ~vpMbEdgeTracker() vp_override; /** @name Inherited functionalities from vpMbEdgeTracker */ //@{ virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; void getLline(std::list &linesList, unsigned int level = 0) const; void getLcircle(std::list &circlesList, unsigned int level = 0) const; @@ -327,7 +327,7 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker virtual std::vector > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - bool displayFullModel = false) override; + bool displayFullModel = false) vp_override; /*! * Get the moving edge parameters. @@ -362,22 +362,22 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker */ inline double getGoodMovingEdgesRatioThreshold() const { return percentageGdPt; } - virtual inline vpColVector getError() const override { return m_error_edge; } + virtual inline vpColVector getError() const vp_override { return m_error_edge; } - virtual inline vpColVector getRobustWeights() const override { return m_w_edge; } + virtual inline vpColVector getRobustWeights() const vp_override { return m_w_edge; } - virtual void loadConfigFile(const std::string &configFile, bool verbose = true) override; + virtual void loadConfigFile(const std::string &configFile, bool verbose = true) vp_override; virtual void reInitModel(const vpImage &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose = false, const vpHomogeneousMatrix &T = vpHomogeneousMatrix()); - void resetTracker() override; + void resetTracker() vp_override; /*! * Set the camera parameters. * * \param cam : The new camera parameters. */ - virtual void setCameraParameters(const vpCameraParameters &cam) override + virtual void setCameraParameters(const vpCameraParameters &cam) vp_override { m_cam = cam; @@ -399,11 +399,11 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker } } - virtual void setClipping(const unsigned int &flags) override; + virtual void setClipping(const unsigned int &flags) vp_override; - virtual void setFarClippingDistance(const double &dist) override; + virtual void setFarClippingDistance(const double &dist) vp_override; - virtual void setNearClippingDistance(const double &dist) override; + virtual void setNearClippingDistance(const double &dist) vp_override; /*! * Use Ogre3D for visibility tests @@ -413,7 +413,7 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker * * \param v : True to use it, False otherwise */ - virtual void setOgreVisibilityTest(const bool &v) override + virtual void setOgreVisibilityTest(const bool &v) vp_override { vpMbTracker::setOgreVisibilityTest(v); #ifdef VISP_HAVE_OGRE @@ -426,7 +426,7 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker * * \param v : True to use it, False otherwise */ - virtual void setScanLineVisibilityTest(const bool &v) override + virtual void setScanLineVisibilityTest(const bool &v) vp_override { vpMbTracker::setScanLineVisibilityTest(v); @@ -456,15 +456,15 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker void setMovingEdge(const vpMe &me); - virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) override; - virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) override; + virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) vp_override; + virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) vp_override; void setScales(const std::vector &_scales); void setUseEdgeTracking(const std::string &name, const bool &useEdgeTracking); - virtual void track(const vpImage &I) override; - virtual void track(const vpImage &I) override; + virtual void track(const vpImage &I) vp_override; + virtual void track(const vpImage &I) vp_override; //@} protected: @@ -483,8 +483,8 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker void computeVVSFirstPhase(const vpImage &I, unsigned int iter, double &count, unsigned int lvl = 0); void computeVVSFirstPhaseFactor(const vpImage &I, unsigned int lvl = 0); void computeVVSFirstPhasePoseEstimation(unsigned int iter, bool &isoJoIdentity); - virtual void computeVVSInit() override; - virtual void computeVVSInteractionMatrixAndResidu() override; + virtual void computeVVSInit() vp_override; + virtual void computeVVSInteractionMatrixAndResidu() vp_override; virtual void computeVVSInteractionMatrixAndResidu(const vpImage &I); virtual void computeVVSWeights(); using vpMbTracker::computeVVSWeights; @@ -493,13 +493,13 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker void displayFeaturesOnImage(const vpImage &I); void downScale(const unsigned int _scale); virtual std::vector > getFeaturesForDisplayEdge(); - virtual void init(const vpImage &I) override; + virtual void init(const vpImage &I) vp_override; virtual void initCircle(const vpPoint &p1, const vpPoint &p2, const vpPoint &p3, double radius, int idFace = 0, - const std::string &name = "") override; + const std::string &name = "") vp_override; virtual void initCylinder(const vpPoint &p1, const vpPoint &p2, double radius, int idFace = 0, - const std::string &name = "") override; - virtual void initFaceFromCorners(vpMbtPolygon &polygon) override; - virtual void initFaceFromLines(vpMbtPolygon &polygon) override; + const std::string &name = "") vp_override; + virtual void initFaceFromCorners(vpMbtPolygon &polygon) vp_override; + virtual void initFaceFromLines(vpMbtPolygon &polygon) vp_override; unsigned int initMbtTracking(unsigned int &nberrors_lines, unsigned int &nberrors_cylinders, unsigned int &nberrors_circles); void initMovingEdge(const vpImage &I, const vpHomogeneousMatrix &_cMo); @@ -510,7 +510,7 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker void removeCylinder(const std::string &name); void removeLine(const std::string &name); void resetMovingEdge(); - virtual void testTracking() override; + virtual void testTracking() vp_override; void trackMovingEdge(const vpImage &I); void updateMovingEdge(const vpImage &I); void updateMovingEdgeWeights(); diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h index b4086d14ee..128a1d8908 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h @@ -213,17 +213,17 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker explicit vpMbGenericTracker(const std::vector &trackerTypes); vpMbGenericTracker(const std::vector &cameraNames, const std::vector &trackerTypes); - virtual ~vpMbGenericTracker() override; + virtual ~vpMbGenericTracker() vp_override; virtual double computeCurrentProjectionError(const vpImage &I, const vpHomogeneousMatrix &_cMo, - const vpCameraParameters &_cam) override; + const vpCameraParameters &_cam) vp_override; virtual double computeCurrentProjectionError(const vpImage &I, const vpHomogeneousMatrix &_cMo, const vpCameraParameters &_cam); virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual void display(const vpImage &I1, const vpImage &I2, const vpHomogeneousMatrix &c1Mo, const vpHomogeneousMatrix &c2Mo, const vpCameraParameters &cam1, @@ -245,7 +245,7 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual std::vector getCameraNames() const; using vpMbTracker::getCameraParameters; - virtual void getCameraParameters(vpCameraParameters &camera) const override; + virtual void getCameraParameters(vpCameraParameters &camera) const vp_override; virtual void getCameraParameters(vpCameraParameters &cam1, vpCameraParameters &cam2) const; virtual void getCameraParameters(std::map &mapOfCameraParameters) const; @@ -255,9 +255,9 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void getClipping(unsigned int &clippingFlag1, unsigned int &clippingFlag2) const; virtual void getClipping(std::map &mapOfClippingFlags) const; - virtual inline vpColVector getError() const override { return m_error; } + virtual inline vpColVector getError() const vp_override { return m_error; } - virtual vpMbHiddenFaces &getFaces() override; + virtual vpMbHiddenFaces &getFaces() vp_override; virtual vpMbHiddenFaces &getFaces(const std::string &cameraName); #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) @@ -302,7 +302,7 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual std::vector > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - bool displayFullModel = false) override; + bool displayFullModel = false) vp_override; virtual void getModelForDisplay(std::map > > &mapOfModels, const std::map &mapOfwidths, const std::map &mapOfheights, @@ -339,30 +339,30 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual unsigned int getNbPoints(unsigned int level = 0) const; virtual void getNbPoints(std::map &mapOfNbPoints, unsigned int level = 0) const; - virtual unsigned int getNbPolygon() const override; + virtual unsigned int getNbPolygon() const vp_override; virtual void getNbPolygon(std::map &mapOfNbPolygons) const; - virtual vpMbtPolygon *getPolygon(unsigned int index) override; + virtual vpMbtPolygon *getPolygon(unsigned int index) vp_override; virtual vpMbtPolygon *getPolygon(const std::string &cameraName, unsigned int index); virtual std::pair, std::vector > > - getPolygonFaces(bool orderPolygons = true, bool useVisibility = true, bool clipPolygon = false) override; + getPolygonFaces(bool orderPolygons = true, bool useVisibility = true, bool clipPolygon = false) vp_override; virtual void getPolygonFaces(std::map > &mapOfPolygons, std::map > > &mapOfPoints, bool orderPolygons = true, bool useVisibility = true, bool clipPolygon = false); using vpMbTracker::getPose; - virtual void getPose(vpHomogeneousMatrix &cMo) const override; + virtual void getPose(vpHomogeneousMatrix &cMo) const vp_override; virtual void getPose(vpHomogeneousMatrix &c1Mo, vpHomogeneousMatrix &c2Mo) const; virtual void getPose(std::map &mapOfCameraPoses) const; virtual std::string getReferenceCameraName() const; - virtual inline vpColVector getRobustWeights() const override { return m_w; } + virtual inline vpColVector getRobustWeights() const vp_override { return m_w; } virtual int getTrackerType() const; - virtual void init(const vpImage &I) override; + virtual void init(const vpImage &I) vp_override; #ifdef VISP_HAVE_MODULE_GUI using vpMbTracker::initClick; @@ -397,7 +397,7 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker const std::map &mapOfInitPoints); using vpMbTracker::initFromPose; - virtual void initFromPose(const vpImage &I, const vpHomogeneousMatrix &cMo) override; + virtual void initFromPose(const vpImage &I, const vpHomogeneousMatrix &cMo) vp_override; virtual void initFromPose(const vpImage &I1, const vpImage &I2, const std::string &initFile1, const std::string &initFile2); virtual void initFromPose(const vpImage &I_color1, const vpImage &I_color2, @@ -418,7 +418,7 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void initFromPose(const std::map *> &mapOfColorImages, const std::map &mapOfCameraPoses); - virtual void loadConfigFile(const std::string &configFile, bool verbose = true) override; + virtual void loadConfigFile(const std::string &configFile, bool verbose = true) vp_override; virtual void loadConfigFile(const std::string &configFile1, const std::string &configFile2, bool verbose = true); virtual void loadConfigFile(const std::map &mapOfConfigFiles, bool verbose = true); @@ -427,7 +427,7 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker #endif virtual void loadModel(const std::string &modelFile, bool verbose = false, - const vpHomogeneousMatrix &T = vpHomogeneousMatrix()) override; + const vpHomogeneousMatrix &T = vpHomogeneousMatrix()) vp_override; virtual void loadModel(const std::string &modelFile1, const std::string &modelFile2, bool verbose = false, const vpHomogeneousMatrix &T1 = vpHomogeneousMatrix(), const vpHomogeneousMatrix &T2 = vpHomogeneousMatrix()); @@ -463,17 +463,17 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker const std::map &mapOfCameraPoses, bool verbose = false, const std::map &mapOfT = std::map()); - virtual void resetTracker() override; + virtual void resetTracker() vp_override; - virtual void setAngleAppear(const double &a) override; + virtual void setAngleAppear(const double &a) vp_override; virtual void setAngleAppear(const double &a1, const double &a2); virtual void setAngleAppear(const std::map &mapOfAngles); - virtual void setAngleDisappear(const double &a) override; + virtual void setAngleDisappear(const double &a) vp_override; virtual void setAngleDisappear(const double &a1, const double &a2); virtual void setAngleDisappear(const std::map &mapOfAngles); - virtual void setCameraParameters(const vpCameraParameters &camera) override; + virtual void setCameraParameters(const vpCameraParameters &camera) vp_override; virtual void setCameraParameters(const vpCameraParameters &camera1, const vpCameraParameters &camera2); virtual void setCameraParameters(const std::map &mapOfCameraParameters); @@ -482,7 +482,7 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void setCameraTransformationMatrix(const std::map &mapOfTransformationMatrix); - virtual void setClipping(const unsigned int &flags) override; + virtual void setClipping(const unsigned int &flags) vp_override; virtual void setClipping(const unsigned int &flags1, const unsigned int &flags2); virtual void setClipping(const std::map &mapOfClippingFlags); @@ -499,9 +499,9 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void setDepthNormalPclPlaneEstimationRansacThreshold(double threshold); virtual void setDepthNormalSamplingStep(unsigned int stepX, unsigned int stepY); - virtual void setDisplayFeatures(bool displayF) override; + virtual void setDisplayFeatures(bool displayF) vp_override; - virtual void setFarClippingDistance(const double &dist) override; + virtual void setFarClippingDistance(const double &dist) vp_override; virtual void setFarClippingDistance(const double &dist1, const double &dist2); virtual void setFarClippingDistance(const std::map &mapOfClippingDists); @@ -526,28 +526,28 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void setKltThresholdAcceptation(double th); #endif - virtual void setLod(bool useLod, const std::string &name = "") override; + virtual void setLod(bool useLod, const std::string &name = "") vp_override; - virtual void setMask(const vpImage &mask) override; + virtual void setMask(const vpImage &mask) vp_override; - virtual void setMinLineLengthThresh(double minLineLengthThresh, const std::string &name = "") override; - virtual void setMinPolygonAreaThresh(double minPolygonAreaThresh, const std::string &name = "") override; + virtual void setMinLineLengthThresh(double minLineLengthThresh, const std::string &name = "") vp_override; + virtual void setMinPolygonAreaThresh(double minPolygonAreaThresh, const std::string &name = "") vp_override; virtual void setMovingEdge(const vpMe &me); virtual void setMovingEdge(const vpMe &me1, const vpMe &me2); virtual void setMovingEdge(const std::map &mapOfMe); - virtual void setNearClippingDistance(const double &dist) override; + virtual void setNearClippingDistance(const double &dist) vp_override; virtual void setNearClippingDistance(const double &dist1, const double &dist2); virtual void setNearClippingDistance(const std::map &mapOfDists); - virtual void setOgreShowConfigDialog(bool showConfigDialog) override; - virtual void setOgreVisibilityTest(const bool &v) override; + virtual void setOgreShowConfigDialog(bool showConfigDialog) vp_override; + virtual void setOgreVisibilityTest(const bool &v) vp_override; - virtual void setOptimizationMethod(const vpMbtOptimizationMethod &opt) override; + virtual void setOptimizationMethod(const vpMbtOptimizationMethod &opt) vp_override; - virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) override; - virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) override; + virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) vp_override; + virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) vp_override; virtual void setPose(const vpImage &I1, const vpImage &I2, const vpHomogeneousMatrix &c1Mo, const vpHomogeneousMatrix &c2Mo); @@ -559,15 +559,15 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void setPose(const std::map *> &mapOfColorImages, const std::map &mapOfCameraPoses); - virtual void setProjectionErrorComputation(const bool &flag) override; + virtual void setProjectionErrorComputation(const bool &flag) vp_override; - virtual void setProjectionErrorDisplay(bool display) override; - virtual void setProjectionErrorDisplayArrowLength(unsigned int length) override; - virtual void setProjectionErrorDisplayArrowThickness(unsigned int thickness) override; + virtual void setProjectionErrorDisplay(bool display) vp_override; + virtual void setProjectionErrorDisplayArrowLength(unsigned int length) vp_override; + virtual void setProjectionErrorDisplayArrowThickness(unsigned int thickness) vp_override; virtual void setReferenceCameraName(const std::string &referenceCameraName); - virtual void setScanLineVisibilityTest(const bool &v) override; + virtual void setScanLineVisibilityTest(const bool &v) vp_override; virtual void setTrackerType(int type); virtual void setTrackerType(const std::map &mapOfTrackerTypes); @@ -579,10 +579,10 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void setUseKltTracking(const std::string &name, const bool &useKltTracking); #endif - virtual void testTracking() override; + virtual void testTracking() vp_override; - virtual void track(const vpImage &I) override; - virtual void track(const vpImage &I_color) override; + virtual void track(const vpImage &I) vp_override; + virtual void track(const vpImage &I_color) vp_override; virtual void track(const vpImage &I1, const vpImage &I2); virtual void track(const vpImage &I_color1, const vpImage &I_color2); @@ -620,23 +620,23 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void computeVVS(std::map *> &mapOfImages); - virtual void computeVVSInit() override; + virtual void computeVVSInit() vp_override; virtual void computeVVSInit(std::map *> &mapOfImages); - virtual void computeVVSInteractionMatrixAndResidu() override; + virtual void computeVVSInteractionMatrixAndResidu() vp_override; virtual void computeVVSInteractionMatrixAndResidu(std::map *> &mapOfImages, std::map &mapOfVelocityTwist); using vpMbTracker::computeVVSWeights; virtual void computeVVSWeights(); virtual void initCircle(const vpPoint &p1, const vpPoint &p2, const vpPoint &p3, double radius, int idFace = 0, - const std::string &name = "") override; + const std::string &name = "") vp_override; virtual void initCylinder(const vpPoint &p1, const vpPoint &p2, double radius, int idFace = 0, - const std::string &name = "") override; + const std::string &name = "") vp_override; - virtual void initFaceFromCorners(vpMbtPolygon &polygon) override; + virtual void initFaceFromCorners(vpMbtPolygon &polygon) vp_override; - virtual void initFaceFromLines(vpMbtPolygon &polygon) override; + virtual void initFaceFromLines(vpMbtPolygon &polygon) vp_override; virtual void loadConfigFileXML(const std::string &configFile, bool verbose = true); #ifdef VISP_HAVE_NLOHMANN_JSON @@ -685,60 +685,60 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker TrackerWrapper(); explicit TrackerWrapper(int trackerType); - virtual inline vpColVector getError() const override { return m_error; } + virtual inline vpColVector getError() const vp_override { return m_error; } - virtual inline vpColVector getRobustWeights() const override { return m_w; } + virtual inline vpColVector getRobustWeights() const vp_override { return m_w; } virtual inline int getTrackerType() const { return m_trackerType; } virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual std::vector > getFeaturesForDisplay(); virtual std::vector > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - bool displayFullModel = false) override; + bool displayFullModel = false) vp_override; - virtual void init(const vpImage &I) override; + virtual void init(const vpImage &I) vp_override; - virtual void loadConfigFile(const std::string &configFile, bool verbose = true) override; + virtual void loadConfigFile(const std::string &configFile, bool verbose = true) vp_override; virtual void reInitModel(const vpImage &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose = false, - const vpHomogeneousMatrix &T = vpHomogeneousMatrix()) override; + const vpHomogeneousMatrix &T = vpHomogeneousMatrix()) vp_override; virtual void reInitModel(const vpImage &I_color, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose = false, const vpHomogeneousMatrix &T = vpHomogeneousMatrix()); - virtual void resetTracker() override; + virtual void resetTracker() vp_override; - virtual void setCameraParameters(const vpCameraParameters &camera) override; + virtual void setCameraParameters(const vpCameraParameters &camera) vp_override; - virtual void setClipping(const unsigned int &flags) override; + virtual void setClipping(const unsigned int &flags) vp_override; - virtual void setFarClippingDistance(const double &dist) override; + virtual void setFarClippingDistance(const double &dist) vp_override; - virtual void setNearClippingDistance(const double &dist) override; + virtual void setNearClippingDistance(const double &dist) vp_override; - virtual void setOgreVisibilityTest(const bool &v) override; + virtual void setOgreVisibilityTest(const bool &v) vp_override; - virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) override; - virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) override; + virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) vp_override; + virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) vp_override; - virtual void setProjectionErrorComputation(const bool &flag) override; + virtual void setProjectionErrorComputation(const bool &flag) vp_override; - virtual void setScanLineVisibilityTest(const bool &v) override; + virtual void setScanLineVisibilityTest(const bool &v) vp_override; virtual void setTrackerType(int type); - virtual void testTracking() override; + virtual void testTracking() vp_override; - virtual void track(const vpImage &I) override; - virtual void track(const vpImage &I_color) override; + virtual void track(const vpImage &I) vp_override; + virtual void track(const vpImage &I_color) vp_override; #ifdef VISP_HAVE_PCL // Fix error: using declaration ‘using vpMbDepthDenseTracker::setPose’ conflicts with a previous // using declaration that occurs with g++ 4.6.3 on Ubuntu 12.04 @@ -753,22 +753,22 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker protected: virtual void computeVVS(const vpImage *const ptr_I); - virtual void computeVVSInit() override; + virtual void computeVVSInit() vp_override; virtual void computeVVSInit(const vpImage *const ptr_I); - virtual void computeVVSInteractionMatrixAndResidu() override; + virtual void computeVVSInteractionMatrixAndResidu() vp_override; using vpMbEdgeTracker::computeVVSInteractionMatrixAndResidu; virtual void computeVVSInteractionMatrixAndResidu(const vpImage *const ptr_I); using vpMbTracker::computeVVSWeights; - virtual void computeVVSWeights() override; + virtual void computeVVSWeights() vp_override; virtual void initCircle(const vpPoint &p1, const vpPoint &p2, const vpPoint &p3, double radius, int idFace = 0, - const std::string &name = "") override; + const std::string &name = "") vp_override; virtual void initCylinder(const vpPoint &p1, const vpPoint &p2, double radius, int idFace = 0, - const std::string &name = "") override; + const std::string &name = "") vp_override; - virtual void initFaceFromCorners(vpMbtPolygon &polygon) override; - virtual void initFaceFromLines(vpMbtPolygon &polygon) override; + virtual void initFaceFromCorners(vpMbtPolygon &polygon) vp_override; + virtual void initFaceFromLines(vpMbtPolygon &polygon) vp_override; virtual void initMbtTracking(const vpImage *const ptr_I); @@ -801,7 +801,7 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker #endif #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) virtual void setPose(const vpImage *I, const vpImage *I_color, - const vpHomogeneousMatrix &cdMo) override; + const vpHomogeneousMatrix &cdMo) vp_override; #else virtual void setPose(const vpImage *I, const vpImage *I_color, const vpHomogeneousMatrix &cdMo); diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbKltTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbKltTracker.h index 0cf2f5a162..bc9910aea2 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbKltTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbKltTracker.h @@ -257,9 +257,9 @@ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker void addCircle(const vpPoint &P1, const vpPoint &P2, const vpPoint &P3, double r, const std::string &name = ""); virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; virtual void display(const vpImage &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) override; + const vpColor &col, unsigned int thickness = 1, bool displayFullModel = false) vp_override; /*! Return the address of the circle feature list. */ virtual std::list &getFeaturesCircle() { return circles_disp; } @@ -308,22 +308,22 @@ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker */ inline double getKltThresholdAcceptation() const { return threshold_outlier; } - virtual inline vpColVector getError() const override { return m_error_klt; } + virtual inline vpColVector getError() const vp_override { return m_error_klt; } - virtual inline vpColVector getRobustWeights() const override { return m_w_klt; } + virtual inline vpColVector getRobustWeights() const vp_override { return m_w_klt; } virtual std::vector > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, - bool displayFullModel = false) override; + bool displayFullModel = false) vp_override; - virtual void loadConfigFile(const std::string &configFile, bool verbose = true) override; + virtual void loadConfigFile(const std::string &configFile, bool verbose = true) vp_override; virtual void reInitModel(const vpImage &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose = false, const vpHomogeneousMatrix &T = vpHomogeneousMatrix()); - void resetTracker() override; + void resetTracker() vp_override; - void setCameraParameters(const vpCameraParameters &cam) override; + void setCameraParameters(const vpCameraParameters &cam) vp_override; /*! * Set the erosion of the mask used on the Model faces. @@ -354,7 +354,7 @@ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker * * \param v : True to use it, False otherwise */ - virtual void setOgreVisibilityTest(const bool &v) override + virtual void setOgreVisibilityTest(const bool &v) vp_override { vpMbTracker::setOgreVisibilityTest(v); #ifdef VISP_HAVE_OGRE @@ -367,7 +367,7 @@ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker * * \param v : True to use it, False otherwise */ - virtual void setScanLineVisibilityTest(const bool &v) override + virtual void setScanLineVisibilityTest(const bool &v) vp_override { vpMbTracker::setScanLineVisibilityTest(v); @@ -375,8 +375,8 @@ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker (*it)->useScanLine = v; } - virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) override; - virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) override; + virtual void setPose(const vpImage &I, const vpHomogeneousMatrix &cdMo) vp_override; + virtual void setPose(const vpImage &I_color, const vpHomogeneousMatrix &cdMo) vp_override; /*! * Set if the projection error criteria has to be computed. @@ -384,7 +384,7 @@ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker * \param flag : True if the projection error criteria has to be computed, * false otherwise */ - virtual void setProjectionErrorComputation(const bool &flag) override + virtual void setProjectionErrorComputation(const bool &flag) vp_override { if (flag) std::cerr << "This option is not yet implemented in vpMbKltTracker, " @@ -394,9 +394,9 @@ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker void setUseKltTracking(const std::string &name, const bool &useKltTracking); - virtual void testTracking() override; - virtual void track(const vpImage &I) override; - virtual void track(const vpImage &I_color) override; + virtual void testTracking() vp_override; + virtual void track(const vpImage &I) vp_override; + virtual void track(const vpImage &I_color) vp_override; /*! @name Deprecated functions @@ -454,16 +454,16 @@ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker /** @name Protected Member Functions Inherited from vpMbKltTracker */ //@{ void computeVVS(); - virtual void computeVVSInit() override; - virtual void computeVVSInteractionMatrixAndResidu() override; + virtual void computeVVSInit() vp_override; + virtual void computeVVSInteractionMatrixAndResidu() vp_override; virtual std::vector > getFeaturesForDisplayKlt(); - virtual void init(const vpImage &I) override; - virtual void initFaceFromCorners(vpMbtPolygon &polygon) override; - virtual void initFaceFromLines(vpMbtPolygon &polygon) override; - virtual void initCircle(const vpPoint &, const vpPoint &, const vpPoint &, double, int, const std::string &name = "") override; - virtual void initCylinder(const vpPoint &, const vpPoint &, double, int, const std::string &name = "") override; + virtual void init(const vpImage &I) vp_override; + virtual void initFaceFromCorners(vpMbtPolygon &polygon) vp_override; + virtual void initFaceFromLines(vpMbtPolygon &polygon) vp_override; + virtual void initCircle(const vpPoint &, const vpPoint &, const vpPoint &, double, int, const std::string &name = "") vp_override; + virtual void initCylinder(const vpPoint &, const vpPoint &, double, int, const std::string &name = "") vp_override; void preTracking(const vpImage &I); bool postTracking(const vpImage &I, vpColVector &w); diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h index f5fd18fa99..9d74be7618 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h @@ -74,7 +74,7 @@ class VISP_EXPORT vpMbtMeEllipse : public vpMeEllipse private: void reSample(const vpImage &I); - void sample(const vpImage &I, bool doNotTrack = false) override; + void sample(const vpImage &I, bool doNotTrack = false) vp_override; void suppressPoints(); }; diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeLine.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeLine.h index 9cf88f3cfd..16d22ae8cc 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeLine.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeLine.h @@ -53,11 +53,11 @@ class VISP_EXPORT vpMbtMeLine : public vpMeTracker { private: - vpMeSite PExt[2]; - double rho, theta, theta_1; - double delta, delta_1; - int sign; - double a, b, c; + vpMeSite m_PExt[2]; + double m_rho, m_theta, m_theta_1; + double m_delta, m_delta_1; + int m_sign; + double m_a, m_b, m_c; public: int imin, imax; @@ -66,7 +66,7 @@ class VISP_EXPORT vpMbtMeLine : public vpMeTracker public: vpMbtMeLine(); - virtual ~vpMbtMeLine() override; + virtual ~vpMbtMeLine() vp_override; void computeProjectionError(const vpImage &_I, double &_sumErrorRad, unsigned int &_nbFeatures, const vpMatrix &SobelX, const vpMatrix &SobelY, bool display, unsigned int length, @@ -81,7 +81,7 @@ class VISP_EXPORT vpMbtMeLine : public vpMeTracker * * \return : The a coefficient of the moving edge */ - inline double get_a() const { return this->a; } + inline double get_a() const { return m_a; } /*! * Get the a coefficient of the line corresponding to \f$ i \; cos(\theta) + j @@ -89,7 +89,7 @@ class VISP_EXPORT vpMbtMeLine : public vpMeTracker * * \return : The b coefficient of the moving edge */ - inline double get_b() const { return this->b; } + inline double get_b() const { return m_b; } /*! * Get the a coefficient of the line corresponding to \f$ i \; cos(\theta) + j @@ -97,7 +97,7 @@ class VISP_EXPORT vpMbtMeLine : public vpMeTracker * * \return : The c coefficient of the moving edge */ - inline double get_c() const { return this->c; } + inline double get_c() const { return m_c; } void initTracking(const vpImage &I, const vpImagePoint &ip1, const vpImagePoint &ip2, double rho, double theta, bool doNoTrack); @@ -111,7 +111,7 @@ class VISP_EXPORT vpMbtMeLine : public vpMeTracker private: void bubbleSortI(); void bubbleSortJ(); - void sample(const vpImage &image, bool doNotTrack = false) override; + void sample(const vpImage &image, bool doNotTrack = false) vp_override; void seekExtremities(const vpImage &I); void setExtremities(); void suppressPoints(const vpImage &I); diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h index 763a4ec1d8..166c90bdba 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 USE_TRANSFORM +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) && USE_TRANSFORM #define HAVE_TRANSFORM 1 #include #endif diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp index c6d636bc9e..066b4817fb 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp @@ -312,7 +312,7 @@ bool vpMbtFaceDepthDense::computeDesiredFeatures(const vpHomogeneousMatrix &cMo, : 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) { + if (vpMeTracker::inRoiMask(mask, i, j) && pcl::isFinite((*point_cloud)(j, i)) && (*point_cloud)(j, i).z > 0) { totalPoints++; m_pointCloudFace.push_back((*point_cloud)(j, i).x); @@ -398,7 +398,7 @@ bool vpMbtFaceDepthDense::computeDesiredFeatures(const vpHomogeneousMatrix &cMo, : polygon_2d.isInside(vpImagePoint(i, j)))) { totalTheoreticalPoints++; - if (vpMeTracker::inMask(mask, i, j) && point_cloud[i * width + j][2] > 0) { + if (vpMeTracker::inRoiMask(mask, i, j) && point_cloud[i * width + j][2] > 0) { totalPoints++; m_pointCloudFace.push_back(point_cloud[i * width + j][0]); @@ -483,7 +483,7 @@ bool vpMbtFaceDepthDense::computeDesiredFeatures(const vpHomogeneousMatrix &cMo, : polygon_2d.isInside(vpImagePoint(i, j)))) { totalTheoreticalPoints++; - if (vpMeTracker::inMask(mask, i, j) && point_cloud[i * width + j][2] > 0) { + if (vpMeTracker::inRoiMask(mask, i, j) && point_cloud[i * width + j][2] > 0) { totalPoints++; m_pointCloudFace.push_back(point_cloud[i * width + j][0]); diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp index 33238a61bc..de946581c5 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp @@ -220,7 +220,7 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo double x = 0.0, y = 0.0; for (unsigned int i = top; i < bottom; i += stepY) { for (unsigned int j = left; j < right; j += stepX) { - if (vpMeTracker::inMask(mask, i, j) && pcl::isFinite((*point_cloud)(j, i)) && (*point_cloud)(j, i).z > 0 && + if (vpMeTracker::inRoiMask(mask, i, j) && pcl::isFinite((*point_cloud)(j, i)) && (*point_cloud)(j, i).z > 0 && (m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() && j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs()[i][j] == m_polygon->getIndex()) @@ -379,7 +379,7 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo double x = 0.0, y = 0.0; for (unsigned int i = top; i < bottom; i += stepY) { for (unsigned int j = left; j < right; j += stepX) { - if (vpMeTracker::inMask(mask, i, j) && point_cloud[i * width + j][2] > 0 && + if (vpMeTracker::inRoiMask(mask, i, j) && point_cloud[i * width + j][2] > 0 && (m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() && j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs()[i][j] == m_polygon->getIndex()) @@ -540,7 +540,7 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo double x = 0.0, y = 0.0; for (unsigned int i = top; i < bottom; i += stepY) { for (unsigned int j = left; j < right; j += stepX) { - if (vpMeTracker::inMask(mask, i, j) && point_cloud[i * width + j][2] > 0 && + if (vpMeTracker::inRoiMask(mask, i, j) && point_cloud[i * width + j][2] > 0 && (m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() && j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs()[i][j] == m_polygon->getIndex()) @@ -1556,7 +1556,7 @@ void vpMbtFaceDepthNormal::estimatePlaneEquationSVD(const std::vector &p tukey.MEstimator(residues, weights, 1e-4); } else { - // Transform the plane equation for the current pose + // Transform the plane equation for the current pose m_planeCamera = m_planeObject; m_planeCamera.changeFrame(cMo); @@ -1699,10 +1699,20 @@ vpMbtFaceDepthNormal::getFeaturesForDisplay(const vpHomogeneousMatrix &cMo, cons vpMeterPixelConversion::convertPoint(cam, pt_extremity.get_x(), pt_extremity.get_y(), im_extremity); { - std::vector params = { 2, // desired normal - im_centroid.get_i(), im_centroid.get_j(), im_extremity.get_i(), +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + 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 features.push_back(params); } @@ -1729,10 +1739,20 @@ vpMbtFaceDepthNormal::getFeaturesForDisplay(const vpHomogeneousMatrix &cMo, cons vpMeterPixelConversion::convertPoint(cam, pt_extremity.get_x(), pt_extremity.get_y(), im_extremity); { - std::vector params = { 3, // normal at current pose - im_centroid.get_i(), im_centroid.get_j(), im_extremity.get_i(), +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + 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 features.push_back(params); } } diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp index 5bfffe2fb7..edd86cc12d 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp @@ -321,8 +321,18 @@ std::vector > vpMbtDistanceCircle::getFeaturesForDisplay() for (std::list::const_iterator it = meEllipse->getMeList().begin(); it != meEllipse->getMeList().end(); ++it) { vpMeSite p_me = *it; - std::vector params = { 0, // ME - p_me.get_ifloat(), p_me.get_jfloat(), static_cast(p_me.getState()) }; +#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 features.push_back(params); } @@ -449,7 +459,7 @@ void vpMbtDistanceCircle::computeInteractionMatrixError(const vpHomogeneousMatri for (std::list::const_iterator it = meEllipse->getMeList().begin(); it != meEllipse->getMeList().end(); ++it) { - vpPixelMeterConversion::convertPoint(cam, it->j, it->i, x, y); + vpPixelMeterConversion::convertPoint(cam, it->m_j, it->m_i, x, y); // TRO Chaumette 2004 eq 25 H[0] = 2 * (n11 * (y - yg) + n02 * (xg - x)); H[1] = 2 * (n20 * (yg - y) + n11 * (x - xg)); diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp index ba13ab1220..ac273e55e3 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp @@ -579,8 +579,18 @@ std::vector > vpMbtDistanceCylinder::getFeaturesForDisplay() for (std::list::const_iterator it = meline1->getMeList().begin(); it != meline1->getMeList().end(); ++it) { vpMeSite p_me = *it; - std::vector params = { 0, // ME - p_me.get_ifloat(), p_me.get_jfloat(), static_cast(p_me.getState()) }; +#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 features.push_back(params); } @@ -590,8 +600,18 @@ std::vector > vpMbtDistanceCylinder::getFeaturesForDisplay() for (std::list::const_iterator it = meline2->getMeList().begin(); it != meline2->getMeList().end(); ++it) { vpMeSite p_me = *it; - std::vector params = { 0, // ME - p_me.get_ifloat(), p_me.get_jfloat(), static_cast(p_me.getState()) }; +#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 features.push_back(params); } @@ -664,9 +684,32 @@ std::vector > vpMbtDistanceCylinder::getModelForDisplay(unsi ip21.set_ij(i21, j21); ip22.set_ij(i22, j22); - 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() }; +#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 models.push_back(params1); models.push_back(params2); @@ -787,8 +830,8 @@ void vpMbtDistanceCylinder::computeInteractionMatrixError(const vpHomogeneousMat unsigned int j = 0; for (std::list::const_iterator it = meline1->getMeList().begin(); it != meline1->getMeList().end(); ++it) { - double x = (double)it->j; - double y = (double)it->i; + double x = (double)it->m_j; + double y = (double)it->m_i; x = (x - xc) * mx; y = (y - yc) * my; @@ -804,15 +847,15 @@ void vpMbtDistanceCylinder::computeInteractionMatrixError(const vpHomogeneousMat error[j] = rho1 - (x * co1 + y * si1); if (disp) - vpDisplay::displayCross(I, it->i, it->j, (unsigned int)(error[j] * 100), vpColor::orange, 1); + vpDisplay::displayCross(I, it->m_i, it->m_j, (unsigned int)(error[j] * 100), vpColor::orange, 1); j++; } for (std::list::const_iterator it = meline2->getMeList().begin(); it != meline2->getMeList().end(); ++it) { - double x = (double)it->j; - double y = (double)it->i; + double x = (double)it->m_j; + double y = (double)it->m_i; x = (x - xc) * mx; y = (y - yc) * my; @@ -828,7 +871,7 @@ void vpMbtDistanceCylinder::computeInteractionMatrixError(const vpHomogeneousMat error[j] = rho2 - (x * co2 + y * si2); if (disp) - vpDisplay::displayCross(I, it->i, it->j, (unsigned int)(error[j] * 100), vpColor::red, 1); + vpDisplay::displayCross(I, it->m_i, it->m_j, (unsigned int)(error[j] * 100), vpColor::red, 1); j++; } diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp index 7fdcba420c..b51cf1547d 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp @@ -705,8 +705,18 @@ std::vector > vpMbtDistanceLine::getFeaturesForDisplay() if (me_l != nullptr) { for (std::list::const_iterator it = me_l->getMeList().begin(); it != me_l->getMeList().end(); ++it) { vpMeSite p_me_l = *it; - std::vector params = { 0, // ME - p_me_l.get_ifloat(), p_me_l.get_jfloat(), static_cast(p_me_l.getState()) }; +#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 features.push_back(params); } @@ -768,8 +778,20 @@ 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); - std::vector params = { 0, // 0 for line parameters - ip1.get_i(), ip1.get_j(), ip2.get_i(), ip2.get_j() }; +#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 models.push_back(params); } @@ -833,8 +855,8 @@ void vpMbtDistanceLine::computeInteractionMatrixError(const vpHomogeneousMatrix for (size_t i = 0; i < meline.size(); i++) { for (std::list::const_iterator it = meline[i]->getMeList().begin(); it != meline[i]->getMeList().end(); ++it) { - x = (double)it->j; - y = (double)it->i; + x = (double)it->m_j; + y = (double)it->m_i; x = (x - xc) * mx; y = (y - yc) * my; @@ -889,8 +911,8 @@ bool vpMbtDistanceLine::closeToImageBorder(const vpImage &I, cons for (size_t i = 0; i < meline.size(); i++) { for (std::list::const_iterator it = meline[i]->getMeList().begin(); it != meline[i]->getMeList().end(); ++it) { - int i_ = it->i; - int j_ = it->j; + int i_ = it->m_i; + int j_ = it->m_j; if (i_ < 0 || j_ < 0) { // out of image. return true; diff --git a/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp b/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp index c0a0a55a93..2329446c52 100644 --- a/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp @@ -89,9 +89,9 @@ void vpMbtMeEllipse::computeProjectionError(const vpImage &I, dou vpColVector vecSite(2); vpColVector vecGrad(2); - for (std::list::iterator it = list.begin(); it != list.end(); ++it) { - double iSite = it->ifloat; - double jSite = it->jfloat; + for (std::list::iterator it = m_meList.begin(); it != m_meList.end(); ++it) { + double iSite = it->m_ifloat; + double jSite = it->m_jfloat; if (!outOfImage(vpMath::round(iSite), vpMath::round(jSite), 0, height, width)) { // Check if necessary // The tangent angle to the ellipse at a site @@ -198,25 +198,26 @@ void vpMbtMeEllipse::initTracking(const vpImage &I, const vpImage computeKiFromNij(); if (m_trackArc) { - alpha1 = computeAngleOnEllipse(*pt1); - alpha2 = computeAngleOnEllipse(*pt2); - if ((alpha2 <= alpha1) || (std::fabs(alpha2 - alpha1) < m_arcEpsilon)) { - alpha2 += 2.0 * M_PI; + m_alpha1 = computeAngleOnEllipse(*pt1); + m_alpha2 = computeAngleOnEllipse(*pt2); + if ((m_alpha2 <= m_alpha1) || (std::fabs(m_alpha2 - m_alpha1) < m_arcEpsilon)) { + m_alpha2 += 2.0 * M_PI; } // useful for track(I) - iP1 = *pt1; - iP2 = *pt2; + m_iP1 = *pt1; + m_iP2 = *pt2; } else { - alpha1 = 0.0; - alpha2 = 2.0 * M_PI; + m_alpha1 = 0.0; + m_alpha2 = 2.0 * M_PI; // useful for track(I) vpImagePoint ip; - computePointOnEllipse(alpha1, ip); - iP1 = iP2 = ip; + computePointOnEllipse(m_alpha1, ip); + m_iP1 = ip; + m_iP2 = ip; } // useful for display(I) so useless if no display before track(I) - iPc.set_uv(m_uc, m_vc); + m_iPc.set_uv(m_uc, m_vc); sample(I, doNotTrack); @@ -240,7 +241,7 @@ void vpMbtMeEllipse::track(const vpImage &I) vpMeTracker::track(I); if (m_mask != nullptr) { // Expected density could be modified if some vpMeSite are no more tracked because they are outside the mask. - m_expectedDensity = static_cast(list.size()); + m_expectedDensity = static_cast(m_meList.size()); } } catch (const vpException &exception) { @@ -285,7 +286,7 @@ void vpMbtMeEllipse::updateParameters(const vpImage &I, const vpI */ void vpMbtMeEllipse::reSample(const vpImage &I) { - if (!me) { + if (!m_me) { vpDERROR_TRACE(2, "Tracking error: Moving edges not initialized"); throw(vpTrackingException(vpTrackingException::initializationError, "Moving edges not initialized")); } @@ -312,27 +313,27 @@ void vpMbtMeEllipse::reSample(const vpImage &I) void vpMbtMeEllipse::sample(const vpImage &I, bool doNotTrack) { // Warning: similar code in vpMeEllipse::sample() except for display that is removed here - if (!me) { + if (!m_me) { throw(vpException(vpException::fatalError, "Moving edges on ellipse not initialized")); } // Delete old lists - list.clear(); - angle.clear(); + m_meList.clear(); + m_angleList.clear(); int nbrows = static_cast(I.getHeight()); int nbcols = static_cast(I.getWidth()); - if (std::fabs(me->getSampleStep()) <= std::numeric_limits::epsilon()) { + if (std::fabs(m_me->getSampleStep()) <= std::numeric_limits::epsilon()) { std::cout << "In vpMeEllipse::sample: "; std::cout << "function called with sample step = 0, set to 10 dg"; - me->setSampleStep(10.0); + m_me->setSampleStep(10.0); } - double incr = vpMath::rad(me->getSampleStep()); // angle increment + double incr = vpMath::rad(m_me->getSampleStep()); // angle increment // alpha2 - alpha1 = 2 * M_PI for a complete ellipse - m_expectedDensity = static_cast(floor((alpha2 - alpha1) / incr)); + m_expectedDensity = static_cast(floor((m_alpha2 - m_alpha1) / incr)); // starting angle for sampling - double ang = alpha1 + ((alpha2 - alpha1) - static_cast(m_expectedDensity) * incr) / 2.0; + double ang = m_alpha1 + ((m_alpha2 - m_alpha1) - static_cast(m_expectedDensity) * incr) / 2.0; // sample positions for (unsigned int i = 0; i < m_expectedDensity; i++) { vpImagePoint iP; @@ -344,10 +345,10 @@ void vpMbtMeEllipse::sample(const vpImage &I, bool doNotTrack) vpMeSite pix; // (i,j) frame used for vpMeSite pix.init(iP.get_i(), iP.get_j(), theta); - pix.setDisplay(selectDisplay); + pix.setDisplay(m_selectDisplay); pix.setState(vpMeSite::NO_SUPPRESSION); - list.push_back(pix); - angle.push_back(ang); + m_meList.push_back(pix); + m_angleList.push_back(ang); } ang += incr; } @@ -363,10 +364,10 @@ void vpMbtMeEllipse::sample(const vpImage &I, bool doNotTrack) void vpMbtMeEllipse::suppressPoints() { // Loop through list of sites to track - for (std::list::iterator it = list.begin(); it != list.end();) { + for (std::list::iterator it = m_meList.begin(); it != m_meList.end();) { vpMeSite s = *it; // current reference pixel if (s.getState() != vpMeSite::NO_SUPPRESSION) - it = list.erase(it); + it = m_meList.erase(it); else ++it; } diff --git a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp index 9bbf295f66..03cc98fa22 100644 --- a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp @@ -65,14 +65,17 @@ static void normalizeAngle(double &delta) Basic constructor that calls the constructor of the class vpMeTracker. */ vpMbtMeLine::vpMbtMeLine() - : rho(0.), theta(0.), theta_1(M_PI / 2), delta(0.), delta_1(0), sign(1), a(0.), b(0.), c(0.), imin(0), imax(0), - jmin(0), jmax(0), expecteddensity(0.) + : m_rho(0.), m_theta(0.), m_theta_1(M_PI / 2), m_delta(0.), m_delta_1(0), m_sign(1), m_a(0.), m_b(0.), m_c(0.), + imin(0), imax(0), jmin(0), jmax(0), expecteddensity(0.) { } /*! Basic destructor. */ -vpMbtMeLine::~vpMbtMeLine() { list.clear(); } +vpMbtMeLine::~vpMbtMeLine() +{ + m_meList.clear(); +} /*! Initialization of the tracking. The line is defined thanks to the @@ -85,37 +88,37 @@ vpMbtMeLine::~vpMbtMeLine() { list.clear(); } \param I : Image in which the line appears. \param ip1 : Coordinates of the first point. \param ip2 : Coordinates of the second point. - \param rho_ : The \f$\rho\f$ parameter - \param theta_ : The \f$\theta\f$ parameter + \param rho : The \f$\rho\f$ parameter + \param theta : The \f$\theta\f$ parameter \param doNoTrack : If true, ME are not tracked */ void vpMbtMeLine::initTracking(const vpImage &I, const vpImagePoint &ip1, const vpImagePoint &ip2, - double rho_, double theta_, bool doNoTrack) + double rho, double theta, bool doNoTrack) { vpCDEBUG(1) << " begin vpMeLine::initTracking()" << std::endl; try { // 1. On fait ce qui concerne les droites (peut etre vide) // Points extremites - PExt[0].ifloat = (float)ip1.get_i(); - PExt[0].jfloat = (float)ip1.get_j(); - PExt[1].ifloat = (float)ip2.get_i(); - PExt[1].jfloat = (float)ip2.get_j(); + m_PExt[0].m_ifloat = (float)ip1.get_i(); + m_PExt[0].m_jfloat = (float)ip1.get_j(); + m_PExt[1].m_ifloat = (float)ip2.get_i(); + m_PExt[1].m_jfloat = (float)ip2.get_j(); - this->rho = rho_; - this->theta = theta_; - theta_1 = theta_; + m_rho = rho; + m_theta = theta; + m_theta_1 = theta; - a = cos(theta); - b = sin(theta); - c = -rho; + m_a = cos(m_theta); + m_b = sin(m_theta); + m_c = -m_rho; - delta = -theta + M_PI / 2.0; - normalizeAngle(delta); - delta_1 = delta; + m_delta = -m_theta + M_PI / 2.0; + normalizeAngle(m_delta); + m_delta_1 = m_delta; sample(I, doNoTrack); - expecteddensity = (double)list.size(); + expecteddensity = (double)m_meList.size(); if (!doNoTrack) vpMeTracker::track(I); @@ -135,66 +138,69 @@ void vpMbtMeLine::initTracking(const vpImage &I, const vpImagePoi */ void vpMbtMeLine::sample(const vpImage &I, bool doNoTrack) { - int rows = (int)I.getHeight(); - int cols = (int)I.getWidth(); + int nbrows = static_cast(I.getHeight()); + int nbcols = static_cast(I.getWidth()); double n_sample; - // if (me->getSampleStep==0) - if (std::fabs(me->getSampleStep()) <= std::numeric_limits::epsilon()) { + if (std::fabs(m_me->getSampleStep()) <= std::numeric_limits::epsilon()) { throw(vpTrackingException(vpTrackingException::fatalError, "Function vpMbtMeLine::sample() called with " "moving-edges sample step = 0")); } // i, j portions of the line_p - double diffsi = PExt[0].ifloat - PExt[1].ifloat; - double diffsj = PExt[0].jfloat - PExt[1].jfloat; + double diffsi = m_PExt[0].m_ifloat - m_PExt[1].m_ifloat; + double diffsj = m_PExt[0].m_jfloat - m_PExt[1].m_jfloat; double length_p = sqrt((vpMath::sqr(diffsi) + vpMath::sqr(diffsj))); // number of samples along line_p - n_sample = length_p / (double)me->getSampleStep(); + n_sample = length_p / (double)m_me->getSampleStep(); double stepi = diffsi / (double)n_sample; double stepj = diffsj / (double)n_sample; // Choose starting point - double is = PExt[1].ifloat; - double js = PExt[1].jfloat; + double is = m_PExt[1].m_ifloat; + double js = m_PExt[1].m_jfloat; // Delete old list - list.clear(); + m_meList.clear(); - // sample positions at i*me->getSampleStep() interval along the + // sample positions at i*m_me->getSampleStep() interval along the // line_p, starting at PSiteExt[0] - vpImagePoint ip; for (int i = 0; i <= vpMath::round(n_sample); i++) { + vpImagePoint iP; + iP.set_i(is); + iP.set_j(js); // If point is in the image, add to the sample list - if (!outOfImage(vpMath::round(is), vpMath::round(js), (int)(me->getRange() + me->getMaskSize() + 1), (int)rows, - (int)cols) && - vpMeTracker::inMask(m_mask, vpMath::round(is), vpMath::round(js))) { - vpMeSite pix; //= list.value(); - pix.init((int)is, (int)js, delta, 0, sign); - - if (!doNoTrack) - pix.track(I, me, false); - - pix.setDisplay(selectDisplay); + if ((!outOfImage(iP, (int)(m_me->getRange() + m_me->getMaskSize() + 1), nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) + && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + vpMeSite pix; + pix.init(iP.get_i(), iP.get_j(), m_delta, 0, m_sign); + pix.setDisplay(m_selectDisplay); + pix.setState(vpMeSite::NO_SUPPRESSION); + const double marginRatio = m_me->getThresholdMarginRatio(); + double convolution = pix.convolution(I, m_me); + double contrastThreshold = fabs(convolution) * marginRatio; + pix.setContrastThreshold(contrastThreshold, *m_me); + + if (!doNoTrack) { + pix.track(I, m_me, false); + } if (vpDEBUG_ENABLE(3)) { - ip.set_i(is); - ip.set_j(js); - vpDisplay::displayCross(I, ip, 2, vpColor::blue); + vpDisplay::displayCross(I, iP, 2, vpColor::blue); } - list.push_back(pix); + m_meList.push_back(pix); } is += stepi; js += stepj; } vpCDEBUG(1) << "end vpMeLine::sample() : "; - vpCDEBUG(1) << list.size() << " point inserted in the list " << std::endl; + vpCDEBUG(1) << m_meList.size() << " point inserted in the list " << std::endl; } /*! @@ -204,35 +210,35 @@ void vpMbtMeLine::sample(const vpImage &I, bool doNoTrack) */ void vpMbtMeLine::suppressPoints(const vpImage &I) { - for (std::list::iterator it = list.begin(); it != list.end();) { + for (std::list::iterator it = m_meList.begin(); it != m_meList.end();) { vpMeSite s = *it; // current reference pixel - if (fabs(sin(theta)) > 0.9) // Vertical line management + if (fabs(sin(m_theta)) > 0.9) // Vertical line management { - if ((s.i < imin) || (s.i > imax)) { + if ((s.m_i < imin) || (s.m_i > imax)) { s.setState(vpMeSite::CONTRAST); } } - else if (fabs(cos(theta)) > 0.9) // Horizontal line management + else if (fabs(cos(m_theta)) > 0.9) // Horizontal line management { - if ((s.j < jmin) || (s.j > jmax)) { + if ((s.m_j < jmin) || (s.m_j > jmax)) { s.setState(vpMeSite::CONTRAST); } } else { - if ((s.i < imin) || (s.i > imax) || (s.j < jmin) || (s.j > jmax)) { + if ((s.m_i < imin) || (s.m_i > imax) || (s.m_j < jmin) || (s.m_j > jmax)) { s.setState(vpMeSite::CONTRAST); } } - if (outOfImage(s.i, s.j, (int)(me->getRange() + me->getMaskSize() + 1), (int)I.getHeight(), (int)I.getWidth())) { + if (outOfImage(s.m_i, s.m_j, (int)(m_me->getRange() + m_me->getMaskSize() + 1), (int)I.getHeight(), (int)I.getWidth())) { s.setState(vpMeSite::TOO_NEAR); } if (s.getState() != vpMeSite::NO_SUPPRESSION) - it = list.erase(it); + it = m_meList.erase(it); else ++it; } @@ -252,14 +258,14 @@ void vpMbtMeLine::seekExtremities(const vpImage &I) int cols = (int)I.getWidth(); double n_sample; - // if (me->getSampleStep()==0) - if (std::fabs(me->getSampleStep()) <= std::numeric_limits::epsilon()) { + // if (m_me->getSampleStep()==0) + if (std::fabs(m_me->getSampleStep()) <= std::numeric_limits::epsilon()) { throw(vpTrackingException(vpTrackingException::fatalError, "Function called with sample step = 0")); } // i, j portions of the line_p - double diffsi = PExt[0].ifloat - PExt[1].ifloat; - double diffsj = PExt[0].jfloat - PExt[1].jfloat; + double diffsi = m_PExt[0].m_ifloat - m_PExt[1].m_ifloat; + double diffsj = m_PExt[0].m_jfloat - m_PExt[1].m_jfloat; double s = vpMath::sqr(diffsi) + vpMath::sqr(diffsj); @@ -269,66 +275,66 @@ void vpMbtMeLine::seekExtremities(const vpImage &I) double length_p = sqrt(s); /*(vpMath::sqr(diffsi)+vpMath::sqr(diffsj))*/ // number of samples along line_p - n_sample = length_p / (double)me->getSampleStep(); - double sample_step = (double)me->getSampleStep(); + n_sample = length_p / (double)m_me->getSampleStep(); + double sample_step = (double)m_me->getSampleStep(); vpMeSite P; - P.init((int)PExt[0].ifloat, (int)PExt[0].jfloat, delta_1, 0, sign); - P.setDisplay(selectDisplay); + P.init((int)m_PExt[0].m_ifloat, (int)m_PExt[0].m_jfloat, m_delta_1, 0, m_sign); + P.setDisplay(m_selectDisplay); - unsigned int memory_range = me->getRange(); - me->setRange(1); + unsigned int memory_range = m_me->getRange(); + m_me->setRange(1); for (int i = 0; i < 3; i++) { - P.ifloat = P.ifloat + di * sample_step; - P.i = (int)P.ifloat; - P.jfloat = P.jfloat + dj * sample_step; - P.j = (int)P.jfloat; + P.m_ifloat = P.m_ifloat + di * sample_step; + P.m_i = (int)P.m_ifloat; + P.m_jfloat = P.m_jfloat + dj * sample_step; + P.m_j = (int)P.m_jfloat; - if ((P.i < imin) || (P.i > imax) || (P.j < jmin) || (P.j > jmax)) { + if ((P.m_i < imin) || (P.m_i > imax) || (P.m_j < jmin) || (P.m_j > jmax)) { if (vpDEBUG_ENABLE(3)) - vpDisplay::displayCross(I, P.i, P.j, 5, vpColor::cyan); + vpDisplay::displayCross(I, P.m_i, P.m_j, 5, vpColor::cyan); } - else if (!outOfImage(P.i, P.j, (int)(me->getRange() + me->getMaskSize() + 1), (int)rows, (int)cols)) { - P.track(I, me, false); + else if (!outOfImage(P.m_i, P.m_j, (int)(m_me->getRange() + m_me->getMaskSize() + 1), (int)rows, (int)cols)) { + P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { - list.push_back(P); + m_meList.push_back(P); if (vpDEBUG_ENABLE(3)) - vpDisplay::displayCross(I, P.i, P.j, 5, vpColor::green); + vpDisplay::displayCross(I, P.m_i, P.m_j, 5, vpColor::green); } else if (vpDEBUG_ENABLE(3)) - vpDisplay::displayCross(I, P.i, P.j, 10, vpColor::blue); + vpDisplay::displayCross(I, P.m_i, P.m_j, 10, vpColor::blue); } } - P.init((int)PExt[1].ifloat, (int)PExt[1].jfloat, delta_1, 0, sign); - P.setDisplay(selectDisplay); + P.init((int)m_PExt[1].m_ifloat, (int)m_PExt[1].m_jfloat, m_delta_1, 0, m_sign); + P.setDisplay(m_selectDisplay); for (int i = 0; i < 3; i++) { - P.ifloat = P.ifloat - di * sample_step; - P.i = (int)P.ifloat; - P.jfloat = P.jfloat - dj * sample_step; - P.j = (int)P.jfloat; + P.m_ifloat = P.m_ifloat - di * sample_step; + P.m_i = (int)P.m_ifloat; + P.m_jfloat = P.m_jfloat - dj * sample_step; + P.m_j = (int)P.m_jfloat; - if ((P.i < imin) || (P.i > imax) || (P.j < jmin) || (P.j > jmax)) { + if ((P.m_i < imin) || (P.m_i > imax) || (P.m_j < jmin) || (P.m_j > jmax)) { if (vpDEBUG_ENABLE(3)) - vpDisplay::displayCross(I, P.i, P.j, 5, vpColor::cyan); + vpDisplay::displayCross(I, P.m_i, P.m_j, 5, vpColor::cyan); } - else if (!outOfImage(P.i, P.j, (int)(me->getRange() + me->getMaskSize() + 1), (int)rows, (int)cols)) { - P.track(I, me, false); + else if (!outOfImage(P.m_i, P.m_j, (int)(m_me->getRange() + m_me->getMaskSize() + 1), (int)rows, (int)cols)) { + P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { - list.push_back(P); + m_meList.push_back(P); if (vpDEBUG_ENABLE(3)) - vpDisplay::displayCross(I, P.i, P.j, 5, vpColor::green); + vpDisplay::displayCross(I, P.m_i, P.m_j, 5, vpColor::green); } else if (vpDEBUG_ENABLE(3)) - vpDisplay::displayCross(I, P.i, P.j, 10, vpColor::blue); + vpDisplay::displayCross(I, P.m_i, P.m_j, 10, vpColor::blue); } } - me->setRange(memory_range); + m_me->setRange(memory_range); vpCDEBUG(1) << "end vpMeLine::sample() : "; vpCDEBUG(1) << n_sample << " point inserted in the list " << std::endl; @@ -354,13 +360,15 @@ void vpMbtMeLine::computeProjectionError(const vpImage &_I, doubl { _sumErrorRad = 0; _nbFeatures = 0; - double deltaNormalized = theta; + double deltaNormalized = m_theta; unsigned int iter = 0; - while (deltaNormalized < 0) + while (deltaNormalized < 0) { deltaNormalized += M_PI; - while (deltaNormalized > M_PI) + } + while (deltaNormalized > M_PI) { deltaNormalized -= M_PI; + } vpColVector vecLine(2); vecLine[0] = cos(deltaNormalized); @@ -369,13 +377,13 @@ void vpMbtMeLine::computeProjectionError(const vpImage &_I, doubl double offset = std::floor(SobelX.getRows() / 2.0f); - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { - if (iter != 0 && iter + 1 != list.size()) { + for (std::list::const_iterator it = m_meList.begin(); it != m_meList.end(); ++it) { + if (iter != 0 && iter + 1 != m_meList.size()) { double gradientX = 0; double gradientY = 0; - double iSite = it->ifloat; - double jSite = it->jfloat; + double iSite = it->m_ifloat; + double jSite = it->m_jfloat; for (unsigned int i = 0; i < SobelX.getRows(); i++) { double iImg = iSite + (i - offset); @@ -468,15 +476,13 @@ void vpMbtMeLine::reSample(const vpImage &I) unsigned int n = numberOfSignal(); if ((double)n < 0.5 * expecteddensity && n > 0) { - double delta_new = delta; - delta = delta_1; + double delta_new = m_delta; + m_delta = m_delta_1; sample(I); - expecteddensity = (double)list.size(); - delta = delta_new; + expecteddensity = (double)m_meList.size(); + m_delta = delta_new; // 2. On appelle ce qui n'est pas specifique - { - vpMeTracker::initTracking(I); - } + vpMeTracker::initTracking(I); } } @@ -494,19 +500,19 @@ void vpMbtMeLine::reSample(const vpImage &I) */ void vpMbtMeLine::reSample(const vpImage &I, const vpImagePoint &ip1, const vpImagePoint &ip2) { - size_t n = list.size(); + size_t n = m_meList.size(); if ((double)n < 0.5 * expecteddensity /*&& n > 0*/) // n is always > 0 { - double delta_new = delta; - delta = delta_1; - PExt[0].ifloat = (float)ip1.get_i(); - PExt[0].jfloat = (float)ip1.get_j(); - PExt[1].ifloat = (float)ip2.get_i(); - PExt[1].jfloat = (float)ip2.get_j(); + double delta_new = m_delta; + m_delta = m_delta_1; + m_PExt[0].m_ifloat = (float)ip1.get_i(); + m_PExt[0].m_jfloat = (float)ip1.get_j(); + m_PExt[1].m_ifloat = (float)ip2.get_i(); + m_PExt[1].m_jfloat = (float)ip2.get_j(); sample(I); - expecteddensity = (double)list.size(); - delta = delta_new; + expecteddensity = (double)m_meList.size(); + m_delta = delta_new; vpMeTracker::track(I); } } @@ -521,27 +527,28 @@ void vpMbtMeLine::updateDelta() double diff = 0; // if(fabs(theta) == M_PI ) - if (std::fabs(std::fabs(theta) - M_PI) <= - vpMath::maximum(std::fabs(theta), (double)M_PI) * std::numeric_limits::epsilon()) { - theta = 0; + if (std::fabs(std::fabs(m_theta) - M_PI) <= + vpMath::maximum(std::fabs(m_theta), (double)M_PI) * std::numeric_limits::epsilon()) { + m_theta = 0; } - diff = fabs(theta - theta_1); - if (diff > M_PI / 2.0) - sign *= -1; + diff = fabs(m_theta - m_theta_1); + if (diff > M_PI / 2.0) { + m_sign *= -1; + } - theta_1 = theta; + m_theta_1 = m_theta; - delta = -theta + M_PI / 2.0; - normalizeAngle(delta); + m_delta = -m_theta + M_PI / 2.0; + normalizeAngle(m_delta); - for (std::list::iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::iterator it = m_meList.begin(); it != m_meList.end(); ++it) { p_me = *it; - p_me.alpha = delta; - p_me.mask_sign = sign; + p_me.m_alpha = m_delta; + p_me.m_mask_sign = m_sign; *it = p_me; } - delta_1 = delta; + m_delta_1 = m_delta; } /*! @@ -555,7 +562,7 @@ void vpMbtMeLine::track(const vpImage &I) vpMeTracker::track(I); if (m_mask != nullptr) { // Expected density could be modified if some vpMeSite are no more tracked because they are outside the mask. - expecteddensity = (double)list.size(); + expecteddensity = (double)m_meList.size(); } } catch (...) { @@ -567,17 +574,17 @@ void vpMbtMeLine::track(const vpImage &I) Update the moving edges parameters after the virtual visual servoing. \param I : The image. - \param rho_ : The \f$\rho\f$ parameter used in the line's polar equation. - \param theta_ : The \f$\theta\f$ parameter used in the line's polar + \param rho : The \f$\rho\f$ parameter used in the line's polar equation. + \param theta : The \f$\theta\f$ parameter used in the line's polar equation. */ -void vpMbtMeLine::updateParameters(const vpImage &I, double rho_, double theta_) +void vpMbtMeLine::updateParameters(const vpImage &I, double rho, double theta) { - this->rho = rho_; - this->theta = theta_; - a = cos(theta); - b = sin(theta); - c = -rho; + m_rho = rho; + m_theta = theta; + m_a = cos(m_theta); + m_b = sin(m_theta); + m_c = -m_rho; // recherche de point aux extremite de la droites // dans le cas d'un glissement suppressPoints(I); @@ -597,18 +604,18 @@ void vpMbtMeLine::updateParameters(const vpImage &I, double rho_, \param I : The image. \param ip1 : The first extremity of the line. \param ip2 : The second extremity of the line. - \param rho_ : The \f$\rho\f$ parameter used in the line's polar equation. - \param theta_ : The \f$\theta\f$ parameter used in the line's polar + \param rho : The \f$\rho\f$ parameter used in the line's polar equation. + \param theta : The \f$\theta\f$ parameter used in the line's polar equation. */ void vpMbtMeLine::updateParameters(const vpImage &I, const vpImagePoint &ip1, const vpImagePoint &ip2, - double rho_, double theta_) + double rho, double theta) { - this->rho = rho_; - this->theta = theta_; - a = cos(theta); - b = sin(theta); - c = -rho; + m_rho = rho; + m_theta = theta; + m_a = cos(m_theta); + m_b = sin(m_theta); + m_c = -m_rho; // recherche de point aux extremite de la droites // dans le cas d'un glissement suppressPoints(I); @@ -633,45 +640,45 @@ void vpMbtMeLine::setExtremities() double j_max = -1; // Loop through list of sites to track - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::const_iterator it = m_meList.begin(); it != m_meList.end(); ++it) { vpMeSite s = *it; // current reference pixel - if (s.ifloat < i_min) { - i_min = s.ifloat; - j_min = s.jfloat; + if (s.m_ifloat < i_min) { + i_min = s.m_ifloat; + j_min = s.m_jfloat; } - if (s.ifloat > i_max) { - i_max = s.ifloat; - j_max = s.jfloat; + if (s.m_ifloat > i_max) { + i_max = s.m_ifloat; + j_max = s.m_jfloat; } } - if (!list.empty()) { - PExt[0].ifloat = i_min; - PExt[0].jfloat = j_min; - PExt[1].ifloat = i_max; - PExt[1].jfloat = j_max; + if (!m_meList.empty()) { + m_PExt[0].m_ifloat = i_min; + m_PExt[0].m_jfloat = j_min; + m_PExt[1].m_ifloat = i_max; + m_PExt[1].m_jfloat = j_max; } if (fabs(i_min - i_max) < 25) { - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::const_iterator it = m_meList.begin(); it != m_meList.end(); ++it) { vpMeSite s = *it; // current reference pixel - if (s.jfloat < j_min) { - i_min = s.ifloat; - j_min = s.jfloat; + if (s.m_jfloat < j_min) { + i_min = s.m_ifloat; + j_min = s.m_jfloat; } - if (s.jfloat > j_max) { - i_max = s.ifloat; - j_max = s.jfloat; + if (s.m_jfloat > j_max) { + i_max = s.m_ifloat; + j_max = s.m_jfloat; } } - if (!list.empty()) { - PExt[0].ifloat = i_min; - PExt[0].jfloat = j_min; - PExt[1].ifloat = i_max; - PExt[1].jfloat = j_max; + if (!m_meList.empty()) { + m_PExt[0].m_ifloat = i_min; + m_PExt[0].m_jfloat = j_min; + m_PExt[1].m_ifloat = i_max; + m_PExt[1].m_jfloat = j_max; } bubbleSortJ(); } @@ -680,46 +687,46 @@ void vpMbtMeLine::setExtremities() bubbleSortI(); } -static bool sortByI(const vpMeSite &s1, const vpMeSite &s2) { return (s1.ifloat > s2.ifloat); } +static bool sortByI(const vpMeSite &s1, const vpMeSite &s2) { return (s1.m_ifloat > s2.m_ifloat); } void vpMbtMeLine::bubbleSortI() { #if 0 - unsigned int nbElmt = list.size(); + unsigned int nbElmt = m_meList.size(); for (unsigned int pass = 1; pass < nbElmt; pass++) { - list.front(); + m_meList.front(); for (unsigned int i = 0; i < nbElmt-pass; i++) { - vpMeSite s1 = list.value(); - vpMeSite s2 = list.nextValue(); - if (s1.ifloat > s2.ifloat) - list.swapRight(); + vpMeSite s1 = m_meList.value(); + vpMeSite s2 = m_meList.nextValue(); + if (s1.m_ifloat > s2.m_ifloat) + m_meList.swapRight(); else - list.next(); + m_meList.next(); } } #endif - list.sort(sortByI); + m_meList.sort(sortByI); } -static bool sortByJ(const vpMeSite &s1, const vpMeSite &s2) { return (s1.jfloat > s2.jfloat); } +static bool sortByJ(const vpMeSite &s1, const vpMeSite &s2) { return (s1.m_jfloat > s2.m_jfloat); } void vpMbtMeLine::bubbleSortJ() { #if 0 - unsigned int nbElmt = list.size(); + unsigned int nbElmt = m_meList.size(); for (unsigned int pass = 1; pass < nbElmt; pass++) { - list.front(); + m_meList.front(); for (unsigned int i = 0; i < nbElmt-pass; i++) { - vpMeSite s1 = list.value(); - vpMeSite s2 = list.nextValue(); - if (s1.jfloat > s2.jfloat) - list.swapRight(); + vpMeSite s1 = m_meList.value(); + vpMeSite s2 = m_meList.nextValue(); + if (s1.m_jfloat > s2.m_jfloat) + m_meList.swapRight(); else - list.next(); + m_meList.next(); } } #endif - list.sort(sortByJ); + m_meList.sort(sortByJ); } #endif diff --git a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp index 2671cffd87..b3ddd420d7 100644 --- a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp +++ b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp @@ -92,7 +92,7 @@ void vpMbtDistanceKltPoints::init(const vpKltOpencv &_tracker, const vpImagegetMbScanLineRenderer().getPrimitiveIDs().getHeight() && (unsigned int)x_tmp < hiddenface->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && @@ -157,7 +157,7 @@ unsigned int vpMbtDistanceKltPoints::computeNbDetectedCurrent(const vpKltOpencv for (unsigned int i = 0; i < static_cast(_tracker.getNbFeatures()); i++) { _tracker.getFeature((int)i, id, x, y); - if (isTrackedFeature((int)id) && vpMeTracker::inMask(mask, (unsigned int)y, (unsigned int)x)) { + if (isTrackedFeature((int)id) && vpMeTracker::inRoiMask(mask, (unsigned int)y, (unsigned int)x)) { #ifdef TARGET_OS_IPHONE curPoints[(int)id] = vpImagePoint(static_cast(y), static_cast(x)); curPointsInd[(int)id] = (int)i; diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp index 03087c034b..bf51f2b0ac 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp @@ -376,7 +376,7 @@ bool run(const std::string &input_directory, bool opt_click_allowed, bool opt_di #endif #else map_thresh[vpMbGenericTracker::EDGE_TRACKER] = - useScanline ? std::pair(0.008, 2.3) : std::pair(0.007, 2.1); + useScanline ? std::pair(0.008, 2.3) : std::pair(0.009, 4.0); #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) map_thresh[vpMbGenericTracker::KLT_TRACKER] = useScanline ? std::pair(0.006, 1.7) : std::pair(0.005, 1.4); diff --git a/modules/tracker/me/include/visp3/me/vpMe.h b/modules/tracker/me/include/visp3/me/vpMe.h index a35e03254f..42efa389d7 100644 --- a/modules/tracker/me/include/visp3/me/vpMe.h +++ b/modules/tracker/me/include/visp3/me/vpMe.h @@ -66,6 +66,8 @@ * vpMe me; * me.setLikelihoodThresholdType(vpMe::NORMALIZED_THRESHOLD); * me.setThreshold(20); // Value in range [0 ; 255] + * me.setThresholdMarginRatio(-1.); // Deactivate automatic thresholding + * me.setMinThreshold(-1.); // Deactivate automatic thresholding * me.setMaskNumber(180); * me.setMaskSign(0); * me.setMu1(0.5); @@ -103,6 +105,8 @@ * Query range +/- J................5 pixels * Likelihood threshold type........normalized * Likelihood threshold.............20 + * Likelihood margin ratio..........unused + * Minimum likelihood threshold.....unused * Contrast tolerance +/-...........50% and 50% * Sample step......................10 pixels * Strip............................2 pixels @@ -113,7 +117,7 @@ * \code{.unparsed} * $ cat me.json * {"maskSign":0,"maskSize":5,"minSampleStep":4.0,"mu":[0.5,0.5],"nMask":180,"ntotalSample":0,"pointsToTrack":200, - * "range":5,"sampleStep":10.0,"strip":2,"threshold":20.0,"thresholdType":1} + * "range":5,"sampleStep":10.0,"strip":2,"threshold":20.0,"thresholdMarginRatio":-1.0,"minThreshold":-1.0,"thresholdType":1} * \endcode */ class VISP_EXPORT vpMe @@ -135,6 +139,9 @@ class VISP_EXPORT vpMe vpLikelihoodThresholdType m_likelihood_threshold_type; //!< Likelihood threshold type //! Old likelihood ratio threshold (to be avoided) or easy-to-use normalized threshold: minimal contrast double m_threshold; + double m_thresholdMarginRatio; //!< The ratio of the initial contrast to use to initialize the contrast threshold of the vpMeSite. + double m_minThreshold; //!< The minimum moving-edge threshold in grey level used when the contrast threshold of the vpMeSites is automatically computed. + bool m_useAutomaticThreshold; //!< Set to true if the user wants to automatically compute the vpMeSite contrast thresholds, false if the user wants to use a global threshold. double m_mu1; //!< Contrast continuity parameter (left boundary) double m_mu2; //!< Contrast continuity parameter (right boundary) double m_min_samplestep; @@ -174,10 +181,12 @@ 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. @@ -295,6 +304,33 @@ class VISP_EXPORT vpMe */ inline double getThreshold() const { return m_threshold; } + /*! + * Return the ratio of the initial contrast to use to initialize the contrast threshold of the \b vpMeSite. + * + * \return Value of the likelihood threshold ratio, between 0 and 1. + * + * \sa setThresholdMarginRatio(), setMinThreshold(), getMinThreshold(), getLikelihoodThresholdType(), setLikelihoodThresholdType() + */ + inline double getThresholdMarginRatio() const { return m_thresholdMarginRatio; } + + /*! + * Return the minimum contrast threshold of the \b vpMeSite that can be used when using the + * automatic threshold computation. + * + * \return Value of the minimum contrast threshold. + * + * \sa setThresholdMarginRatio(), getThresholdMarginRatio(), setMinThreshold(), getLikelihoodThresholdType(), setLikelihoodThresholdType() + */ + inline double getMinThreshold() const { return m_minThreshold; } + + /*! + * \brief Indicates if the contrast threshold of the vpMeSite is automatically computed. + * + * \return true The contrast threshold of the vpMeSite is automatically computed. + * \return false The vpMe::m_threshold is used as a global threshold. + */ + inline bool getUseAutomaticThreshold() const { return m_useAutomaticThreshold; } + /*! * Return the selected choice for the likelihood threshold. * @@ -419,6 +455,8 @@ class VISP_EXPORT vpMe * vpMe me; * me.setLikelihoodThresholdType(NORMALIZED_THRESHOLD); * me.setThreshold(20); // Value in range [0 ; 255] + * me.setThresholdMarginRatio(-1.); // Deactivate automatic thresholding + * me.setMinThreshold(-1.); // Deactivate automatic thresholding * \endcode * * When the likelihood threshold type is set by default to OLD_THRESHOLD like in the next example, values of the likelihood threshold @@ -426,17 +464,50 @@ class VISP_EXPORT vpMe * \code * vpMe me; // By default the constructor set the threshold type to OLD_THRESHOLD * me.setThreshold(10000); // Value that depends on the minimal luminance contrast to consider and the mask size. + * me.setThresholdMarginRatio(-1.); // Deactivate automatic thresholding + * me.setMinThreshold(-1.); // Deactivate automatic thresholding * \endcode * The previous sample code is similar to the next one: * \code * vpMe me; * me.setLikelihoodThresholdType(OLD_THRESHOLD); * me.setThreshold(10000); // Value that depends on the minimal luminance contrast to consider and the mask size. + * me.setThresholdMarginRatio(-1.); // Deactivate automatic thresholding + * me.setMinThreshold(-1.); // Deactivate automatic thresholding * \endcode * \sa getThreshold(), getLikelihoodThresholdType() */ void setThreshold(const double &threshold) { m_threshold = threshold; } + /*! + * Set the the ratio of the initial contrast to use to initialize the contrast threshold of the \b vpMeSite. + * + * \param thresholdMarginRatio Value of the likelihood threshold ratio, between 0 and 1. + * + * \sa getThresholdMarginRatio(), setMinThreshold(), getMinThreshold(), getLikelihoodThresholdType(), setLikelihoodThresholdType() + */ + inline void setThresholdMarginRatio(const double &thresholdMarginRatio) + { + if (thresholdMarginRatio > 1.) { + throw(vpException(vpException::badValue, "Threshold margin ratio must be between 0 and 1 if you want to use automatic threshold computation, or negative otherwise")); + } + m_thresholdMarginRatio = thresholdMarginRatio; + m_useAutomaticThreshold = (m_thresholdMarginRatio > 0) && (m_minThreshold > 0); + } + + /*! + * Set the minimum value of the contrast threshold of the \b vpMeSite. + * + * \param minThreshold Minimum value of the contrast threshold. + * + * \sa getMinThreshold(), setThresholdMarginRatio(), getThresholdMarginRatio(), getLikelihoodThresholdType(), setLikelihoodThresholdType() + */ + inline void setMinThreshold(const double &minThreshold) + { + m_minThreshold = minThreshold; + m_useAutomaticThreshold = (m_thresholdMarginRatio > 0) && (m_minThreshold > 0); + } + /*! * Set the likelihood threshold type used to determine if the moving edge is valid or not. * @@ -462,6 +533,8 @@ class VISP_EXPORT vpMe * JSON content (key: type): * - thresholdType: int, vpMe::getLikelihoodThresholdType() * - threshold: double, vpMe::setThreshold() + * - thresholdMarginRatio: double, vpMe::setThresholdMarginRatio() + * - minThreshold: double, vpMe::setMinThreshold() * - mu : [double, double], vpMe::setMu1, vpMe::setMu2() * - minSampleStep: double, vpMe::setMinSampleStep() * - angleStep: double, vpMe::setAngleStep() @@ -491,8 +564,10 @@ class VISP_EXPORT vpMe * "range": 7, * "sampleStep": 4.0, * "strip": 2, - * "thresholdType": 1 - * "threshold": 20.0 + * "thresholdType": 1, + * "threshold": 20.0, + * "thresholdMarginRatio": 0.75, + * "minThreshold": 20.0, * } * \endcode * @@ -510,6 +585,8 @@ inline void to_json(nlohmann::json &j, const vpMe &me) j = { {"thresholdType", me.getLikelihoodThresholdType()}, {"threshold", me.getThreshold()}, + {"thresholdMarginRatio", me.getThresholdMarginRatio()}, + {"minThreshold", me.getMinThreshold()}, {"mu", {me.getMu1(), me.getMu2()}}, {"minSampleStep", me.getMinSampleStep()}, {"sampleStep", me.getSampleStep()}, @@ -529,6 +606,8 @@ inline void from_json(const nlohmann::json &j, vpMe &me) me.setLikelihoodThresholdType(j.value("thresholdType", me.getLikelihoodThresholdType())); } me.setThreshold(j.value("threshold", me.getThreshold())); + me.setThresholdMarginRatio(j.value("thresholdMarginRatio", me.getThresholdMarginRatio())); + me.setMinThreshold(j.value("minThreshold", me.getMinThreshold())); if (j.contains("mu")) { std::vector mus = j.at("mu").get>(); diff --git a/modules/tracker/me/include/visp3/me/vpMeEllipse.h b/modules/tracker/me/include/visp3/me/vpMeEllipse.h index 41b24437dc..f68b0243a2 100644 --- a/modules/tracker/me/include/visp3/me/vpMeEllipse.h +++ b/modules/tracker/me/include/visp3/me/vpMeEllipse.h @@ -102,7 +102,8 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker /*! * Destructor. */ - virtual ~vpMeEllipse() override; + virtual ~vpMeEllipse() vp_override; + /*! * Display the ellipse or arc of ellipse * @@ -146,9 +147,9 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker inline vpColVector get_ABE() const { vpColVector ABE(3); - ABE[0] = a; - ABE[1] = b; - ABE[2] = e; + ABE[0] = m_a; + ABE[1] = m_b; + ABE[2] = m_e; return ABE; } @@ -161,14 +162,14 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker * * \sa getCenter(), get_nij(), get_ABE() */ - inline double getArea() const { return m00; } + inline double getArea() const { return m_m00; } /*! * Gets the center of the ellipse. * * \sa get_nij(), get_ABE(), getArea() */ - inline vpImagePoint getCenter() const { return iPc; } + inline vpImagePoint getCenter() const { return m_iPc; } /*! * \return Expected number of moving edges to track along the ellipse. @@ -186,7 +187,7 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker * * \sa getSecondEndpoint() */ - inline vpImagePoint getFirstEndpoint() const { return iP1; } + inline vpImagePoint getFirstEndpoint() const { return m_iP1; } /*! * Gets the highest \f$ alpha \f$ angle of the moving edges tracked @@ -202,7 +203,7 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker * * \sa getFirstEndpoint() */ - inline vpImagePoint getSecondEndpoint() const { return iP2; } + inline vpImagePoint getSecondEndpoint() const { return m_iP2; } /*! * Gets the smallest \f$ alpha \f$ angle of the moving edges tracked @@ -275,8 +276,8 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker */ void setEndpoints(const vpImagePoint &pt1, const vpImagePoint &pt2) { - iP1 = pt1; - iP2 = pt2; + m_iP1 = pt1; + m_iP2 = pt2; } /*! @@ -291,13 +292,13 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker void setThresholdRobust(double threshold) { if (threshold < 0) { - thresholdWeight = 0; + m_thresholdWeight = 0; } else if (threshold > 1) { - thresholdWeight = 1; + m_thresholdWeight = 1; } else { - thresholdWeight = threshold; + m_thresholdWeight = threshold; } } @@ -368,46 +369,46 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker /*! Parameters of the ellipse satisfying the homogeneous equation : * \f[ K_0 u^2 + K_1 v^2 + 2K_2 uv + 2K_3u + 2K_4v + K5 = 0 \f] */ - vpColVector K; + vpColVector m_K; //! The coordinates of the ellipse center. - vpImagePoint iPc; + vpImagePoint m_iPc; //! \f$ a \f$ is the semi major axis of the ellipse. - double a; + double m_a; //! \f$ b \f$ is the semi minor axis of the ellipse. - double b; + double m_b; /*! \f$ e \in [-\pi/2;\pi/2] \f$ is the angle made by the major axis * and the u axis of the image frame \f$ (u,v) \f$. */ - double e; + double m_e; /*! The coordinates of the first endpoint of the ellipse arc * corresponding to angle \f$ \alpha_1 \f$ */ - vpImagePoint iP1; + vpImagePoint m_iP1; /*! The coordinates of the second endpoint of the ellipse arc * corresponding to angle \f$ \alpha_2 \f$ */ - vpImagePoint iP2; + vpImagePoint m_iP2; /*! The angle \f$ \alpha_1 \in [-\pi;\pi] \f$ on the ellipse corresponding * to the first endpoint. Its value is 0 for tracking a complete ellipse */ - double alpha1; + double m_alpha1; /*! The angle \f$ \alpha_2 \in [\alpha_1;\alpha_1+2\pi]\f$ on the ellipse * corresponding to the second endpoint. Its value is \f$ 2 \pi \f$ for * tracking a complete ellipse */ - double alpha2; + double m_alpha2; //! Value of cos(e). - double ce; + double m_ce; //! Value of sin(e). - double se; + double m_se; //! Stores the value in increasing order of the \f$ alpha \f$ angle on the ellipse for each vpMeSite. - std::list angle; + std::list m_angleList; //! Ellipse area - double m00; + double m_m00; //! Threshold on the weights for the robust least square. - double thresholdWeight; + double m_thresholdWeight; /*! The smallest angle \f$ \alpha_{min} \in [\alpha_1;\alpha_2]\f$ * of the current moving edge list @@ -549,7 +550,7 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker * \exception vpTrackingException::initializationError : Moving edges not * initialized. */ - virtual void sample(const vpImage &I, bool doNotTrack = false) override; + virtual void sample(const vpImage &I, bool doNotTrack = false) vp_override; /*! * 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 0ba0cb1cf6..c3a833ffe8 100644 --- a/modules/tracker/me/include/visp3/me/vpMeLine.h +++ b/modules/tracker/me/include/visp3/me/vpMeLine.h @@ -149,23 +149,23 @@ class VISP_EXPORT vpMeLine : public vpMeTracker static void update_indices(double theta, int incr, int i, int j, int &i1, int &i2, int &j1, int &j2); protected: - vpMeSite PExt[2]; //!< Line extremities + vpMeSite m_PExt[2]; //!< Line extremities - double rho; //!< rho parameter of the line - double theta; //!< theta parameter of the line - double delta; //!< Angle in rad between the extremities - double delta_1; //!< Angle in rad between the extremities - double angle; //!< Angle in deg between the extremities - double angle_1; //!< Angle in deg between the extremities - int sign; //!< Sign + double m_rho; //!< rho parameter of the line + double m_theta; //!< theta parameter of the line + double m_delta; //!< Angle in rad between the extremities + double m_delta_1; //!< Angle in rad between the extremities + double m_angle; //!< Angle in deg between the extremities + double m_angle_1; //!< Angle in deg between the extremities + int m_sign; //!< Sign //! Flag to specify wether the intensity of the image at the middle point is //! used to compute the sign of rho or not. - bool _useIntensityForRho; + bool m_useIntensityForRho; - double a; //!< Parameter a of the line equation a*i + b*j + c = 0 - double b; //!< Parameter b of the line equation a*i + b*j + c = 0 - double c; //!< Parameter c of the line equation a*i + b*j + c = 0 + double m_a; //!< Parameter a of the line equation a*i + b*j + c = 0 + double m_b; //!< Parameter b of the line equation a*i + b*j + c = 0 + double m_c; //!< Parameter c of the line equation a*i + b*j + c = 0 public: /*! @@ -181,7 +181,7 @@ class VISP_EXPORT vpMeLine : public vpMeTracker /*! * Destructor. */ - virtual ~vpMeLine() override; + virtual ~vpMeLine() vp_override; /*! * Display line. @@ -213,7 +213,7 @@ class VISP_EXPORT vpMeLine : public vpMeTracker * \exception vpTrackingException::initializationError : Moving edges not * initialized. */ - virtual void sample(const vpImage &I, bool doNotTrack = false) override; + virtual void sample(const vpImage &I, bool doNotTrack = false) vp_override; /*! * Resample the line if the number of sample is less than 80% of the @@ -314,25 +314,25 @@ class VISP_EXPORT vpMeLine : public vpMeTracker */ void getEquationParam(double &A, double &B, double &C) { - A = a; - B = b; - C = c; + A = m_a; + B = m_b; + C = m_c; } /*! Gets parameter a of the line equation a*i + b*j + c = 0 */ - inline double getA() const { return a; } + inline double getA() const { return m_a; } /*! Gets parameter b of the line equation a*i + b*j + c = 0 */ - inline double getB() const { return b; } + inline double getB() const { return m_b; } /*! Gets parameter c of the line equation a*i + b*j + c = 0 */ - inline double getC() const { return c; } + inline double getC() const { return m_c; } /*! * Computes the intersection point of two lines. The result is given in @@ -356,7 +356,7 @@ class VISP_EXPORT vpMeLine : public vpMeTracker \param useIntensityForRho : new value of the flag. */ - inline void computeRhoSignFromIntensity(bool useIntensityForRho) { _useIntensityForRho = useIntensityForRho; } + inline void computeRhoSignFromIntensity(bool useIntensityForRho) { m_useIntensityForRho = useIntensityForRho; } /*! * Display of a moving line thanks to its equation parameters and its diff --git a/modules/tracker/me/include/visp3/me/vpMeSite.h b/modules/tracker/me/include/visp3/me/vpMeSite.h index 12069f161d..fd3ead62c2 100644 --- a/modules/tracker/me/include/visp3/me/vpMeSite.h +++ b/modules/tracker/me/include/visp3/me/vpMeSite.h @@ -80,65 +80,49 @@ class VISP_EXPORT vpMeSite */ typedef enum { - NO_SUPPRESSION = 0, ///< Point used by the tracker. - CONTRAST = 1, ///< Point removed due to a contrast problem. + NO_SUPPRESSION = 0, ///< Point successfully tracked. + CONTRAST = 1, ///< Point not tracked due to a likelihood problem, but retained in the ME list. #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - CONSTRAST = CONTRAST, ///< Point removed due to a contrast problem. + CONSTRAST = CONTRAST, ///< Deprecated. Point not tracked due to a likelihood problem, but retained in the ME list. Use instead CONTRAST. #endif - THRESHOLD = 2, ///< Point removed due to a threshold problem. - M_ESTIMATOR = 3, ///< Point removed during virtual visual-servoing because considered as an outlier. - TOO_NEAR = 4, ///< Point removed because too near image borders. - UNKNOW = 5 ///< Reserved. + THRESHOLD = 2, ///< Point not tracked due to a lack of contrast problem, but retained in the ME list. + M_ESTIMATOR = 3, ///< Point detected as an outlier during virtual visual-servoing. + TOO_NEAR = 4, ///< Point not tracked anymore, since too near from its neighbor. + UNKNOW = 5, ///< Reserved. + OUTSIDE_ROI_MASK = 6 ///< Point is outside the region of interest mask, but retained in the ME list. } vpMeSiteState; - //! Coordinate along i of a site - int i; - //! Coordinates along j of a site - int j; - //! Floating coordinates along i of a site - double ifloat; - //! Floating coordinates along j of a site - double jfloat; + //! Integer coordinate along i of a site + int m_i; + //! Integer coordinates along j of a site + int m_j; + //! Subpixel coordinates along i of a site + double m_ifloat; + //! Subpixel coordinates along j of a site + double m_jfloat; //! Mask sign - int mask_sign; + int m_mask_sign; //! Angle of tangent at site - double alpha; + double m_alpha; //! Convolution of Site in previous image - double convlt; + double m_convlt; //! Convolution of Site in previous image - double normGradient; + double m_normGradient; //! Uncertainty of point given as a probability between 0 and 1 - double weight; - - /*! - * Initialize moving-edge site with default parameters. - */ - void init(); - - /*! - * Initialize moving-edge site parameters. - */ - void init(double ip, double jp, double alphap); + double m_weight; + //! Old likelihood ratio threshold (to be avoided) or easy-to-use normalized threshold: minimal contrast + double m_contrastThreshold; +public: /*! - * Initialize moving-edge site parameters. + * Default constructor. */ - void init(double ip, double jp, double alphap, double convltp); - - /*! - * Initialize moving-edge site parameters. - */ - void init(double ip, double jp, double alphap, double convltp, int sign); - - /*! - * Default constructor. - */ vpMeSite(); /*! * Constructor from pixel coordinates. */ - vpMeSite(double ip, double jp); + vpMeSite(const double &ip, const double &jp); /*! * Copy constructor. @@ -150,6 +134,11 @@ class VISP_EXPORT vpMeSite */ virtual ~vpMeSite() { }; + /*! + * Compute convolution. + */ + double convolution(const vpImage &ima, const vpMe *me); + /*! * Display moving edges in image I. * @param I : Input image. @@ -163,73 +152,94 @@ class VISP_EXPORT vpMeSite void display(const vpImage &I); /*! - * Compute convolution. + * Get the angle of tangent at site. + * + * \return value of alpha */ - double convolution(const vpImage &ima, const vpMe *me); + inline double getAlpha() const { return m_alpha; } + + /*! + * Return site weight or uncertainty as a probability between 0 and 1. + */ + inline double getWeight() const { return m_weight; } /*! * Construct and return the list of vpMeSite along the normal to the contour, * in the given range. - * \pre : ifloat, jfloat, and the direction of the normal (alpha) have to be set. + * \pre : Subpixel coordinates (ifloat, jfloat) and the direction of the normal (alpha) have to be set. * \param I : Image in which the display is performed. * \param range : +/- the range within which the pixel's correspondent will be sought. * \return Pointer to the list of query sites */ - vpMeSite *getQueryList(const vpImage &I, const int range); + vpMeSite *getQueryList(const vpImage &I, const int &range) const; /*! - * Specific function for moving-edges. - * - * \warning To display the moving edges graphics a call to vpDisplay::flush() is needed after this function. + * Return integer coordinate along i (rows). + * \sa get_ifloat() */ - void track(const vpImage &im, const vpMe *me, bool test_likelihood = true); + inline int get_i() const { return m_i; } /*! - * Set the angle of tangent at site. - * - * \param a : new value of alpha + * Return integer coordinate along j (columns). + * \sa get_jfloat() */ - void setAlpha(const double &a) { alpha = a; } + inline int get_j() const { return m_j; } /*! - * Get the angle of tangent at site. - * - * \return value of alpha + * Return subpixel coordinate along i (rows). + * \sa get_i() */ - inline double getAlpha() const { return alpha; } + inline double get_ifloat() const { return m_ifloat; } /*! - * Display selector. + * Return subpixel coordinate along j (columns). + * \sa get_j() */ - void setDisplay(vpMeSiteDisplayType select) { m_selectDisplay = select; } + inline double get_jfloat() const { return m_jfloat; } /*! - * Get the i coordinate (integer). - * - * \return value of i + * Initialize moving-edge site with default parameters. */ - inline int get_i() const { return i; } + void init(); /*! - * Get the j coordinate (f). - * - * \return value of j + * Initialize moving-edge site parameters. + */ + void init(const double &ip, const double &jp, const double &alphap); + + /*! + * Initialize moving-edge site parameters. */ - inline int get_j() const { return j; } + void init(const double &ip, const double &jp, const double &alphap, const double &convltp); /*! - * Get the i coordinate (double). + * Initialize moving-edge site parameters. + */ + void init(const double &ip, const double &jp, const double &alphap, const double &convltp, const int &sign); + + /*! + * Initialize moving-edge site parameters. + */ + void init(const double &ip, const double &jp, const double &alphap, const double &convltp, const int &sign, const double &contrastThreshold); + + /*! + * Specific function for moving-edges. * - * \return value of i + * \warning To display the moving edges graphics a call to vpDisplay::flush() is needed after this function. */ - inline double get_ifloat() const { return ifloat; } + void track(const vpImage &im, const vpMe *me, const bool &test_likelihood = true); /*! - * Get the j coordinate (double). + * Set the angle of tangent at site. * - * \return value of j + * \param a : new value of alpha */ - inline double get_jfloat() const { return jfloat; } + void setAlpha(const double &a) { m_alpha = a; } + + /*! + * Display selector. + */ + void setDisplay(vpMeSiteDisplayType select) { m_selectDisplay = select; } /*! * Set the state of the site. @@ -251,18 +261,42 @@ class VISP_EXPORT vpMeSite inline vpMeSiteState getState() const { return m_state; } /*! - * Set the weight of the site. + * Set the weight or uncertainty of the site. + * + * \param weight : New value of weight as a probability between 0 and 1. + */ + void setWeight(const double &weight) { m_weight = weight; } + + /*! + * Set the contrast threshold of the site. + * If the \b vpMe::m_useAutomaticThreshold is set to false, the contrast threshold is set to the global + * value retrieved using vpMe::getThreshold(). This value can be set using vpMe::setThreshold(). + * Otherwise, the contrast threshold will be set to the highest value + * between \b thresh and the minimum value set by vpMe::setMinThreshold() that could be retrieved using + * vpMe::getMinThreshold(). * - * \param w : new value of weight + * \param thresh : new value of contrast threshold + * \param me: moving-edge parameters */ - void setWeight(const double &w) { weight = w; } + void setContrastThreshold(const double &thresh, const vpMe &me) + { + double threshold; + if (me.getUseAutomaticThreshold()) { + threshold = std::max(thresh, me.getMinThreshold()); + } + else { + threshold = me.getThreshold(); + } + + m_contrastThreshold = threshold; + } /*! - * Get the weight of the site. + * Get the contrast threshold of the site. * - * \return value of weight + * \return value of the contrast threshold of the site. */ - inline double getWeight() const { return weight; } + inline double getContrastThreshold() const { return m_contrastThreshold; } /*! * Copy operator. @@ -309,7 +343,7 @@ class VISP_EXPORT vpMeSite */ static double sqrDistance(const vpMeSite &S1, const vpMeSite &S2) { - return (vpMath::sqr(S1.ifloat - S2.ifloat) + vpMath::sqr(S1.jfloat - S2.jfloat)); + return (vpMath::sqr(S1.m_ifloat - S2.m_ifloat) + vpMath::sqr(S1.m_jfloat - S2.m_jfloat)); } /*! @@ -319,7 +353,7 @@ class VISP_EXPORT vpMeSite * - If blue : The point is removed because of the vpMeSite tracking phase (contrast problem). * - If purple : The point is removed because of the vpMeSite tracking phase (threshold problem). * - If red : The point is removed because of the robust method in the virtual visual servoing (M-Estimator problem). - * - If cyan : The point is removed because it's too close to another. + * - If cyan : The point is outside the mask, see vpMeTracker::setMask(). * - Yellow otherwise. * * \param I : The image. @@ -337,7 +371,7 @@ class VISP_EXPORT vpMeSite * - If blue : The point is removed because of the vpMeSite tracking phase (contrast problem). * - If purple : The point is removed because of the vpMeSite tracking phase (threshold problem). * - If red : The point is removed because of the robust method in the virtual visual servoing (M-Estimator problem). - * - If cyan : The point is removed because it's too close to another. + * - If cyan : The point is outside the mask, see vpMeTracker::setMask(). * - Yellow otherwise * * \param I : The image. diff --git a/modules/tracker/me/include/visp3/me/vpMeTracker.h b/modules/tracker/me/include/visp3/me/vpMeTracker.h index 758d3cbbaf..c96c169ea3 100644 --- a/modules/tracker/me/include/visp3/me/vpMeTracker.h +++ b/modules/tracker/me/include/visp3/me/vpMeTracker.h @@ -58,32 +58,24 @@ */ class VISP_EXPORT vpMeTracker : public vpTracker { -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -public: - /** @name Public Attributes Inherited from vpMeTracker */ - //@{ -#else protected: /** @name Protected Attributes Inherited from vpMeTracker */ //@{ -#endif //! Tracking dependent variables/functions //! List of tracked moving edges points. - std::list list; + std::list m_meList; //! Moving edges initialisation parameters - vpMe *me; + vpMe *m_me; //! Initial range - unsigned int init_range; + unsigned int m_init_range; //! Number of good moving-edges that are tracked - int nGoodElement; + int m_nGoodElement; //! Mask used to disable tracking on a part of image const vpImage *m_mask; - //@} - -protected: - /** @name Protected Attributes Inherited from vpMeTracker */ - //@{ - vpMeSite::vpMeSiteDisplayType selectDisplay; + //! Mask used to determine candidate points for initialization in an image + const vpImage *m_maskCandidates; + //! Moving-edges display type + vpMeSite::vpMeSiteDisplayType m_selectDisplay; //@} public: @@ -100,7 +92,7 @@ class VISP_EXPORT vpMeTracker : public vpTracker /*! * Destructor. */ - virtual ~vpMeTracker() override; + virtual ~vpMeTracker() vp_override; /** @name Public Member Functions Inherited from vpMeTracker */ //@{ @@ -143,50 +135,61 @@ class VISP_EXPORT vpMeTracker : public vpTracker void display(const vpImage &I, vpColVector &w, unsigned int &index_w); /*! - * Test whether the pixel is inside the mask. Mask values that are set to true + * Test whether the pixel is inside the region of interest mask. Mask values that are set to true * are considered in the tracking. * - * \param mask: Mask image or nullptr if not wanted. Mask values that are set to true - * are considered in the tracking. To disable a pixel, set false. + * \param mask: Mask corresponding to the region of interest in the image or nullptr if not wanted. + * Mask values that are set to true are considered in the tracking. To disable a pixel, set false. * \param i : Pixel coordinate along the rows. * \param j : Pixel coordinate along the columns. */ - static bool inMask(const vpImage *mask, unsigned int i, unsigned int j); + static bool inRoiMask(const vpImage *mask, unsigned int i, unsigned int j); + + /*! + * Test whether the moving-edge (ME) is inside the mask of ME candidates for the initialization. + * Mask values that are set to true and their 8 neighbors are considered for the initialization. + * + * \param meMaskCandidates: Mask corresponding the ME location in the image or nullptr if not wanted. + * Mask values that are set to true are considered for the initialization. To disable a pixel, set false. + * \param i : ME coordinate along the rows. + * \param j : ME coordinate along the columns. + */ + static bool inMeMaskCandidates(const vpImage *meMaskCandidates, unsigned int i, unsigned int j); /*! * Return the initial range. * * \return Value of init_range. */ - inline unsigned int getInitRange() { return init_range; } + inline unsigned int getInitRange() { return m_init_range; } /*! * Return the moving edges initialisation parameters. * * \return Moving Edges. */ - inline vpMe *getMe() { return me; } + inline vpMe *getMe() { return m_me; } /*! * Return the list of moving edges * * \return List of Moving Edges. */ - inline std::list &getMeList() { return list; } + inline std::list &getMeList() { return m_meList; } /*! * Return the list of moving edges * * \return List of Moving Edges. */ - inline std::list getMeList() const { return list; } + inline std::list getMeList() const { return m_meList; } /*! * Return the number of points that has not been suppressed. * * \return Number of good points. */ - inline int getNbPoints() const { return nGoodElement; } + inline int getNbPoints() const { return m_nGoodElement; } /*! * Initialize the tracker. @@ -210,16 +213,25 @@ class VISP_EXPORT vpMeTracker : public vpTracker /*! * Copy operator. */ - vpMeTracker &operator=(vpMeTracker &f); + vpMeTracker &operator=(vpMeTracker &meTracker); /*! * Check if a pixel i,j is out of the image. + * \param[in] i,j : Pixel coordinates. + * \param[in] border : Number of pixels along the image border to exclude. When border is set to 0, consider the complete image. + * \param[in] nrows,ncols : Size of the image. + * \return true when the pixel is inside the image minus the border size, false otherwise. */ - int outOfImage(int i, int j, int half, int row, int cols); + bool outOfImage(int i, int j, int border, int nrows, int ncols); + /*! * Check if a pixel i,j is out of the image. + * \param[in] iP : Pixel coordinates. + * \param[in] border : Number of pixels along the image border to exclude. When border is set to 0, consider the complete image. + * \param[in] nrows,ncols : Size of the image. + * \return true when the pixel is inside the image minus the border size, false otherwise. */ - int outOfImage(const vpImagePoint &iP, int half, int rows, int cols); + bool outOfImage(const vpImagePoint &iP, int border, int nrows, int ncols); /*! * Reset the tracker by removing all the moving edges. @@ -235,14 +247,14 @@ class VISP_EXPORT vpMeTracker : public vpTracker * Set type of moving-edges display. * @param select : Display type selector. */ - void setDisplay(vpMeSite::vpMeSiteDisplayType select) { selectDisplay = select; } + void setDisplay(vpMeSite::vpMeSiteDisplayType select) { m_selectDisplay = select; } /*! * Set the initial range. * * \param r : initial range. */ - void setInitRange(const unsigned int &r) { init_range = r; } + void setInitRange(const unsigned int &r) { m_init_range = r; } /*! * Set the mask. @@ -251,19 +263,26 @@ class VISP_EXPORT vpMeTracker : public vpTracker */ virtual void setMask(const vpImage &mask) { m_mask = &mask; } + /*! + * Set the mask of candidates points for initialization. + * + * \param maskCandidates : Pointer towards the mask of candidates points for initialization. + */ + virtual void setMaskCandidates(const vpImage *maskCandidates) { m_maskCandidates = maskCandidates; } + /*! * Set the moving edges initialisation parameters. * - * \param p_me : Moving Edges. + * \param me : Moving Edges. */ - void setMe(vpMe *p_me) { this->me = p_me; } + void setMe(vpMe *me) { m_me = me; } /*! * Set the list of moving edges. * - * \param l : list of Moving Edges. + * \param meList : List of Moving Edges. */ - void setMeList(const std::list &l) { list = l; } + void setMeList(const std::list &meList) { m_meList = meList; } /*! * Return the total number of moving-edges. @@ -280,12 +299,25 @@ class VISP_EXPORT vpMeTracker : public vpTracker void track(const vpImage &I); //@} -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -public: - /** @name Public Attributes Inherited from vpMeTracker */ +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) + /*! + @name Deprecated functions + */ //@{ - int query_range; - bool display_point; //! If true displays the line that is being tracked + /*! + * \deprecated You should rather use inRoiMask(). + * Test whether the pixel is inside the region of interest mask. Mask values that are set to true + * are considered in the tracking. + * + * \param mask: Mask corresponding to the region of interest in the image or nullptr if not wanted. + * Mask values that are set to true are considered in the tracking. To disable a pixel, set false. + * \param i : Pixel coordinate along the rows. + * \param j : Pixel coordinate along the columns. + */ + vp_deprecated static bool inMask(const vpImage *mask, unsigned int i, unsigned int j) + { + return inRoiMask(mask, i, j); + } //@} #endif }; diff --git a/modules/tracker/me/src/moving-edges/vpMe.cpp b/modules/tracker/me/src/moving-edges/vpMe.cpp index 1ad911484c..016a645e21 100644 --- a/modules/tracker/me/src/moving-edges/vpMe.cpp +++ b/modules/tracker/me/src/moving-edges/vpMe.cpp @@ -44,13 +44,13 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS namespace { -struct vpPoint2D_t +struct vpPoint2Dt { double x; double y; }; -struct vpDroite2D_t +struct vpDroite2Dt { double a; double b; @@ -64,45 +64,51 @@ template inline void permute(Type &a, Type &b) b = t; } -static vpDroite2D_t droite_cartesienne(vpPoint2D_t P, vpPoint2D_t Q) +static vpDroite2Dt droiteCartesienne(vpPoint2Dt P, vpPoint2Dt Q) { - vpDroite2D_t PQ; + vpDroite2Dt PQ; PQ.a = P.y - Q.y; PQ.b = Q.x - P.x; - PQ.c = Q.y * P.x - Q.x * P.y; + PQ.c = (Q.y * P.x) - (Q.x * P.y); - return (PQ); + return PQ; } -static vpPoint2D_t point_intersection(vpDroite2D_t D1, vpDroite2D_t D2) +static vpPoint2Dt pointIntersection(vpDroite2Dt D1, vpDroite2Dt D2) { - vpPoint2D_t I; + vpPoint2Dt I; double det; // determinant des 2 vect.normaux - det = (D1.a * D2.b - D2.a * D1.b); // interdit D1,D2 paralleles - I.x = (D2.c * D1.b - D1.c * D2.b) / det; - I.y = (D1.c * D2.a - D2.c * D1.a) / det; + det = ((D1.a * D2.b) - (D2.a * D1.b)); // interdit D1,D2 paralleles + I.x = ((D2.c * D1.b) - (D1.c * D2.b)) / det; + I.y = ((D1.c * D2.a) - (D2.c * D1.a)) / det; - return (I); + return I; } -static void recale(vpPoint2D_t &P, double Xmin, double Ymin, double Xmax, double Ymax) +static void recale(vpPoint2Dt &P, double Xmin, double Ymin, double Xmax, double Ymax) { - if (vpMath::equal(P.x, Xmin)) + if (vpMath::equal(P.x, Xmin)) { P.x = Xmin; // a peu pres => exactement ! - if (vpMath::equal(P.x, Xmax)) + } + + if (vpMath::equal(P.x, Xmax)) { P.x = Xmax; + } - if (vpMath::equal(P.y, Ymin)) + if (vpMath::equal(P.y, Ymin)) { P.y = Ymin; - if (vpMath::equal(P.y, Ymax)) + } + + if (vpMath::equal(P.y, Ymax)) { P.y = Ymax; + } } -static void permute(vpPoint2D_t &A, vpPoint2D_t &B) +static void permute(vpPoint2Dt &A, vpPoint2Dt &B) { - vpPoint2D_t C; + vpPoint2Dt C; if (A.x > B.x) // fonction sans doute a tester... { @@ -113,10 +119,10 @@ static void permute(vpPoint2D_t &A, vpPoint2D_t &B) } // vrai si partie visible -static bool clipping(vpPoint2D_t A, vpPoint2D_t B, double Xmin, double Ymin, double Xmax, double Ymax, vpPoint2D_t &Ac, - vpPoint2D_t &Bc) // resultat: A,B clippes +static bool clipping(vpPoint2Dt A, vpPoint2Dt B, double Xmin, double Ymin, double Xmax, double Ymax, vpPoint2Dt &Ac, + vpPoint2Dt &Bc) // resultat: A,B clippes { - vpDroite2D_t AB, D[4]; + vpDroite2Dt AB, D[4]; D[0].a = 1; D[0].b = 0; D[0].c = -Xmin; @@ -130,70 +136,78 @@ static bool clipping(vpPoint2D_t A, vpPoint2D_t B, double Xmin, double Ymin, dou D[3].b = 1; D[3].c = -Ymax; - vpPoint2D_t P[2]; + const int nbP = 2; + vpPoint2Dt P[nbP]; P[0] = A; P[1] = B; - int code_P[2], // codes de P[n] + int code_P[nbP], // codes de P[n] i, bit_i, // i -> (0000100...) n; - AB = droite_cartesienne(A, B); + AB = droiteCartesienne(A, B); for (;;) // 2 sorties directes internes { // CALCULE CODE DE VISIBILITE (Sutherland & Sproul) // ================================================ - for (n = 0; n < 2; n++) { - code_P[n] = 0000; + for (n = 0; n < nbP; ++n) { + code_P[n] = 0; - if (P[n].x < Xmin) + if (P[n].x < Xmin) { code_P[n] |= 1; // positionne bit0 - if (P[n].x > Xmax) + } + + if (P[n].x > Xmax) { code_P[n] |= 2; // .. bit1 - if (P[n].y < Ymin) + } + + if (P[n].y < Ymin) { code_P[n] |= 4; // .. bit2 - if (P[n].y > Ymax) + } + + if (P[n].y > Ymax) { code_P[n] |= 8; // .. bit3 + } } // 2 CAS OU L'ON PEUT CONCLURE => sortie // ===================================== - if ((code_P[0] | code_P[1]) == 0000) // Aucun bit a 1 - /* NE TRIE PLUS LE RESULTAT ! S_relative() en tient compte - { if(P[0].x < P[1].x) // Rend le couple de points - { Ac=P[0]; Bc=P[1]; } // clippes (ordonnes selon - else { Ac=P[1]; Bc=P[0]; } // leur abscisse x) - */ - { + if ((code_P[0] | code_P[1]) == 0) { Ac = P[0]; Bc = P[1]; - if (vpMath::equal(Ac.x, Bc.x) && vpMath::equal(Ac.y, Bc.y)) - return (false); // AB = 1 point = invisible - else - return (true); // Partie de AB clippee visible! + if (vpMath::equal(Ac.x, Bc.x) && vpMath::equal(Ac.y, Bc.y)) { + return false; // AB = 1 point = invisible + } + else { + return true; // Partie de AB clippee visible! + } } - if ((code_P[0] & code_P[1]) != 0000) // au moins 1 bit commun + if ((code_P[0] & code_P[1]) != 0) // au moins 1 bit commun { - return (false); // AB completement invisible! + return false; // AB completement invisible! } // CAS GENERAL (on sait que code_P[0 ou 1] a au moins un bit a 1 // - clippe le point P[n] qui sort de la fenetre (coupe Droite i) // - reboucle avec le nouveau couple de points // ================================================================ - if (code_P[0] != 0000) { + if (code_P[0] != 0) { n = 0; // c'est P[0] qu'on clippera - for (i = 0, bit_i = 1; !(code_P[0] & bit_i); i++, bit_i <<= 1) { + bit_i = 1; + for (i = 0; !(code_P[0] & bit_i); ++i) { + bit_i <<= 1; } } else { n = 1; // c'est P[1] qu'on clippera - for (i = 0, bit_i = 1; !(code_P[1] & bit_i); i++, bit_i <<= 1) { + bit_i = 1; + for (i = 0; !(code_P[1] & bit_i); ++i) { + bit_i <<= 1; } } - P[n] = point_intersection(AB, D[i]); // clippe le point concerne + P[n] = pointIntersection(AB, D[i]); // clippe le point concerne // RECALE EXACTEMENT LE POINT (calcul flottant => arrondi) // AFIN QUE LE CALCUL DES CODES NE BOUCLE PAS INDEFINIMENT @@ -205,69 +219,78 @@ static bool clipping(vpPoint2D_t A, vpPoint2D_t B, double Xmin, double Ymin, dou // calcule la surface relative des 2 portions definies // par le segment PQ sur le carre Xmin,Ymin,Xmax,Ymax // Rem : P,Q tries sur x, et donc seulement 6 cas -static double S_relative(vpPoint2D_t P, vpPoint2D_t Q, double Xmin, double Ymin, double Xmax, double Ymax) +static double surfaceRelative(vpPoint2Dt P, vpPoint2Dt Q, double Xmin, double Ymin, double Xmax, double Ymax) { - if (Q.x < P.x) // tri le couple de points + if (Q.x < P.x) { // tri le couple de points permute(P, Q); // selon leur abscisse x + } recale(P, Xmin, Ymin, Xmax, Ymax); // permet des calculs de S_relative recale(Q, Xmin, Ymin, Xmax, Ymax); // moins approximatifs. - // if(P.x==Xmin && Q.x==Xmax) + // Case P.x=Xmin and Q.x=Xmax if ((std::fabs(P.x - Xmin) <= - vpMath::maximum(std::fabs(P.x), std::fabs(Xmin)) * std::numeric_limits::epsilon()) && - (std::fabs(Q.x - Xmax) <= - vpMath::maximum(std::fabs(Q.x), std::fabs(Xmax)) * std::numeric_limits::epsilon())) - return (fabs(Ymax + Ymin - P.y - Q.y)); + (vpMath::maximum(std::fabs(P.x), std::fabs(Xmin)) * std::numeric_limits::epsilon())) && + (std::fabs(Q.x - Xmax) <= + (vpMath::maximum(std::fabs(Q.x), std::fabs(Xmax)) * std::numeric_limits::epsilon()))) { + return fabs(Ymax + Ymin - P.y - Q.y); + } - // if( (P.y==Ymin && Q.y==Ymax) || - // (Q.y==Ymin && P.y==Ymax)) + // Case (P.y=Ymin and Q.y==Ymax) or (Q.y=Ymin and P.y==Ymax) if (((std::fabs(P.y - Ymin) <= - vpMath::maximum(std::fabs(P.y), std::fabs(Ymin)) * std::numeric_limits::epsilon()) && + (vpMath::maximum(std::fabs(P.y), std::fabs(Ymin)) * std::numeric_limits::epsilon())) && (std::fabs(Q.y - Ymax) <= - vpMath::maximum(std::fabs(Q.y), std::fabs(Ymax)) * std::numeric_limits::epsilon())) || - ((std::fabs(Q.y - Ymin) <= - vpMath::maximum(std::fabs(Q.y), std::fabs(Ymin)) * std::numeric_limits::epsilon()) && - (std::fabs(P.y - Ymax) <= - vpMath::maximum(std::fabs(P.y), std::fabs(Ymax)) * std::numeric_limits::epsilon()))) - return (fabs(Xmax + Xmin - P.x - Q.x)); - - // if( P.x==Xmin && Q.y==Ymax ) - if (std::fabs(P.x - Xmin) <= - vpMath::maximum(std::fabs(P.x), std::fabs(Xmin)) * std::numeric_limits::epsilon() && - std::fabs(Q.y - Ymax) <= - vpMath::maximum(std::fabs(Q.y), std::fabs(Ymax)) * std::numeric_limits::epsilon()) - return (1 - (Ymax - P.y) * (Q.x - Xmin)); - // if( P.x==Xmin && Q.y==Ymin ) - if (std::fabs(P.x - Xmin) <= - vpMath::maximum(std::fabs(P.x), std::fabs(Xmin)) * std::numeric_limits::epsilon() && - std::fabs(Q.y - Ymin) <= - vpMath::maximum(std::fabs(Q.y), std::fabs(Ymin)) * std::numeric_limits::epsilon()) - return (1 - (P.y - Ymin) * (Q.x - Xmin)); - // if( P.y==Ymin && Q.x==Xmax ) - if (std::fabs(P.y - Ymin) <= - vpMath::maximum(std::fabs(P.y), std::fabs(Ymin)) * std::numeric_limits::epsilon() && - std::fabs(Q.x - Xmax) <= - vpMath::maximum(std::fabs(Q.x), std::fabs(Xmax)) * std::numeric_limits::epsilon()) - return (1 - (Xmax - P.x) * (Q.y - Ymin)); - // if( P.y==Ymax && Q.x==Xmax ) - if (std::fabs(P.y - Ymax) <= - vpMath::maximum(std::fabs(P.y), std::fabs(Ymax)) * std::numeric_limits::epsilon() && - std::fabs(Q.x - Xmax) <= - vpMath::maximum(std::fabs(Q.x), std::fabs(Xmax)) * std::numeric_limits::epsilon()) - return (1 - (Xmax - P.x) * (Ymax - Q.y)); - - throw(vpException(vpException::fatalError, "utils_ecm: error in S_relative (%f,%f) (%f,%f) %f %f %f %f", P.x, P.y, Q.x, Q.y, Xmin, Ymin, Xmax, Ymax)); + (vpMath::maximum(std::fabs(Q.y), std::fabs(Ymax)) * std::numeric_limits::epsilon()))) || + ((std::fabs(Q.y - Ymin) <= + (vpMath::maximum(std::fabs(Q.y), std::fabs(Ymin)) * std::numeric_limits::epsilon())) && + (std::fabs(P.y - Ymax) <= + (vpMath::maximum(std::fabs(P.y), std::fabs(Ymax)) * std::numeric_limits::epsilon())))) { + return fabs(Xmax + Xmin - P.x - Q.x); + } + + // Case P.x=Xmin and Q.y=Ymax + if ((std::fabs(P.x - Xmin) <= + (vpMath::maximum(std::fabs(P.x), std::fabs(Xmin)) * std::numeric_limits::epsilon())) && + (std::fabs(Q.y - Ymax) <= + (vpMath::maximum(std::fabs(Q.y), std::fabs(Ymax)) * std::numeric_limits::epsilon()))) { + return (1 - ((Ymax - P.y) * (Q.x - Xmin))); + } + + // Case P.x=Xmin and Q.y=Ymin + if ((std::fabs(P.x - Xmin) <= + (vpMath::maximum(std::fabs(P.x), std::fabs(Xmin)) * std::numeric_limits::epsilon())) && + (std::fabs(Q.y - Ymin) <= + (vpMath::maximum(std::fabs(Q.y), std::fabs(Ymin)) * std::numeric_limits::epsilon()))) { + return (1 - ((P.y - Ymin) * (Q.x - Xmin))); + } + + // Case P.y=Ymin and Q.x=Xmax + if ((std::fabs(P.y - Ymin) <= + (vpMath::maximum(std::fabs(P.y), std::fabs(Ymin)) * std::numeric_limits::epsilon())) && + (std::fabs(Q.x - Xmax) <= + (vpMath::maximum(std::fabs(Q.x), std::fabs(Xmax)) * std::numeric_limits::epsilon()))) { + return (1 - ((Xmax - P.x) * (Q.y - Ymin))); + } + + // Case P.y=Ymax and Q.x=Xmax + if ((std::fabs(P.y - Ymax) <= + (vpMath::maximum(std::fabs(P.y), std::fabs(Ymax)) * std::numeric_limits::epsilon())) && + (std::fabs(Q.x - Xmax) <= + (vpMath::maximum(std::fabs(Q.x), std::fabs(Xmax)) * std::numeric_limits::epsilon()))) { + return (1 - ((Xmax - P.x) * (Ymax - Q.y))); + } + + throw(vpException(vpException::fatalError, "utils_ecm: error in surfaceRelative (%f,%f) (%f,%f) %f %f %f %f", P.x, P.y, Q.x, Q.y, Xmin, Ymin, Xmax, Ymax)); } -static void calcul_masques(vpColVector &angle, // definitions des angles theta - unsigned int n, // taille masques (PAIRE ou IMPAIRE Ok) - vpMatrix *M) // resultat M[theta](n,n) +static void calculMasques(vpColVector &angle, // definitions des angles theta + unsigned int n, // taille masques (PAIRE ou IMPAIRE Ok) + vpMatrix *M) // resultat M[theta](n,n) { unsigned int i, j; - double X, Y, moitie = ((double)n) / 2.0; // moitie REELLE du masque - vpPoint2D_t P1, Q1, P, Q; // clippe Droite(theta) P1,Q1 -> P,Q + double X, Y, moitie = (static_cast(n)) / 2.0; // moitie REELLE du masque + vpPoint2Dt P1, Q1, P, Q; // clippe Droite(theta) P1,Q1 -> P,Q double v; // ponderation de M(i,j) // For a mask of size nxn, normalization given by n*trunc(n/2.0) @@ -276,8 +299,8 @@ static void calcul_masques(vpColVector &angle, // definitions des angles theta unsigned int nb_theta = angle.getRows(); - for (unsigned int i_theta = 0; i_theta < nb_theta; i_theta++) { - double theta = M_PI / 180 * angle[i_theta]; // indice i -> theta(i) en radians + for (unsigned int i_theta = 0; i_theta < nb_theta; ++i_theta) { + double theta = (M_PI / 180) * angle[i_theta]; // indice i -> theta(i) en radians // angle[] dans [0,180[ double cos_theta = cos(theta); // vecteur directeur de l'ECM double sin_theta = sin(theta); // associe au masque @@ -285,18 +308,19 @@ static void calcul_masques(vpColVector &angle, // definitions des angles theta // PRE-CALCULE 2 POINTS DE D(theta) BIEN EN DEHORS DU MASQUE // ========================================================= // if( angle[i_theta]==90 ) // => tan(theta) infinie ! - if (std::fabs(angle[i_theta] - 90) <= vpMath::maximum(std::fabs(angle[i_theta]), 90.) * - std::numeric_limits::epsilon()) // => tan(theta) infinie ! + const double thetaWhoseTanInfinite = 90.; + if (std::fabs(angle[i_theta] - thetaWhoseTanInfinite) <= (vpMath::maximum(std::fabs(angle[i_theta]), thetaWhoseTanInfinite) * + std::numeric_limits::epsilon())) // => tan(theta) infinie ! { P1.x = 0; - P1.y = -(int)n; + P1.y = -static_cast(n); Q1.x = 0; Q1.y = n; } else { double tan_theta = sin_theta / cos_theta; // pente de la droite D(theta) - P1.x = -(int)n; - P1.y = tan_theta * (-(int)n); + P1.x = -static_cast(n); + P1.y = tan_theta * (-static_cast(n)); Q1.x = n; Q1.y = tan_theta * n; } @@ -305,18 +329,19 @@ static void calcul_masques(vpColVector &angle, // definitions des angles theta // ====================== M[i_theta].resize(n, n); // allocation (si necessaire) - for (i = 0, Y = -moitie + 0.5; i < n; i++, Y++) { - for (j = 0, X = -moitie + 0.5; j < n; j++, X++) { + for (i = 0, Y = -moitie + 0.5; i < n; ++i, ++Y) { + for (j = 0, X = -moitie + 0.5; j < n; ++j, ++X) { // produit vectoriel dir_droite*(X,Y) - int sgn = vpMath::sign(cos_theta * Y - sin_theta * X); + int sgn = vpMath::sign((cos_theta * Y) - (sin_theta * X)); // Resultat = P,Q if (clipping(P1, Q1, X - 0.5, Y - 0.5, X + 0.5, Y + 0.5, P, Q)) { // v dans [0,1] - v = S_relative(P, Q, X - 0.5, Y - 0.5, X + 0.5, Y + 0.5); + v = surfaceRelative(P, Q, X - 0.5, Y - 0.5, X + 0.5, Y + 0.5); } - else + else { v = 1; // PQ ne coupe pas le pixel(i,j) + } M[i_theta][i][j] = sgn * v * norm; } @@ -328,21 +353,23 @@ static void calcul_masques(vpColVector &angle, // definitions des angles theta void vpMe::initMask() { - if (m_mask != nullptr) + if (m_mask != nullptr) { delete[] m_mask; + } m_mask = new vpMatrix[m_mask_number]; vpColVector angle(m_mask_number); - unsigned int angle_pas; - angle_pas = 180 / m_mask_number; + unsigned int angle_pas = 180 / m_mask_number; - unsigned int k = 0; - for (unsigned int i = 0; k < m_mask_number; i += angle_pas) - angle[k++] = i; + unsigned int i = 0; + for (unsigned int k = 0; k < m_mask_number; ++k) { + angle[k] = i; + i += angle_pas; + } - calcul_masques(angle, m_mask_size, m_mask); + calculMasques(angle, m_mask_size, m_mask); } void vpMe::print() @@ -354,7 +381,18 @@ void vpMe::print() std::cout << " Number of masks.................." << m_mask_number << std::endl; std::cout << " Query range +/- J................" << m_range << " pixels" << std::endl; std::cout << " Likelihood threshold type........" << (m_likelihood_threshold_type == NORMALIZED_THRESHOLD ? "normalized " : "old threshold (to be avoided)") << std::endl; - std::cout << " Likelihood threshold............." << m_threshold << std::endl; + + if (m_useAutomaticThreshold) { + std::cout << " Likelihood threshold............." << "unused" << std::endl; + std::cout << " Likelihood margin ratio.........." << m_thresholdMarginRatio << std::endl; + std::cout << " Minimum likelihood threshold....." << m_minThreshold << std::endl; + } + else { + std::cout << " Likelihood threshold............." << m_threshold << std::endl; + std::cout << " Likelihood margin ratio.........." << "unused" << std::endl; + std::cout << " Minimum likelihood threshold....." << "unused" << std::endl; + } + std::cout << " Contrast tolerance +/-..........." << m_mu1 * 100 << "% and " << m_mu2 * 100 << "% " << std::endl; std::cout << " Sample step......................" << m_sample_step << " pixels" << std::endl; std::cout << " Strip............................" << m_strip << " pixels " << std::endl; @@ -362,17 +400,18 @@ void vpMe::print() } vpMe::vpMe() - : m_likelihood_threshold_type(OLD_THRESHOLD), m_threshold(10000), + : m_likelihood_threshold_type(OLD_THRESHOLD), m_threshold(10000), m_thresholdMarginRatio(-1), m_minThreshold(-1), m_useAutomaticThreshold(false), m_mu1(0.5), m_mu2(0.5), m_min_samplestep(4), m_anglestep(1), m_mask_sign(0), m_range(4), m_sample_step(10), m_ntotal_sample(0), m_points_to_track(500), m_mask_size(5), m_mask_number(180), m_strip(2), m_mask(nullptr) { - m_anglestep = (180 / m_mask_number); + const unsigned int flatAngle = 180; + m_anglestep = (flatAngle / m_mask_number); initMask(); } vpMe::vpMe(const vpMe &me) - : m_likelihood_threshold_type(OLD_THRESHOLD), m_threshold(10000), + : m_likelihood_threshold_type(OLD_THRESHOLD), m_threshold(10000), m_thresholdMarginRatio(-1), m_minThreshold(-1), m_useAutomaticThreshold(false), m_mu1(0.5), m_mu2(0.5), m_min_samplestep(4), m_anglestep(1), m_mask_sign(0), m_range(4), m_sample_step(10), m_ntotal_sample(0), m_points_to_track(500), m_mask_size(5), m_mask_number(180), m_strip(2), m_mask(nullptr) { @@ -388,6 +427,9 @@ vpMe &vpMe::operator=(const vpMe &me) m_likelihood_threshold_type = me.m_likelihood_threshold_type; m_threshold = me.m_threshold; + m_thresholdMarginRatio = me.m_thresholdMarginRatio; + m_minThreshold = me.m_minThreshold; + m_useAutomaticThreshold = me.m_useAutomaticThreshold; m_mu1 = me.m_mu1; m_mu2 = me.m_mu2; m_min_samplestep = me.m_min_samplestep; @@ -405,6 +447,7 @@ 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 != nullptr) { @@ -413,6 +456,9 @@ vpMe &vpMe::operator=(const vpMe &&me) } m_likelihood_threshold_type = std::move(me.m_likelihood_threshold_type); m_threshold = std::move(me.m_threshold); + m_thresholdMarginRatio = std::move(me.m_thresholdMarginRatio); + m_minThreshold = std::move(me.m_minThreshold); + m_useAutomaticThreshold = std::move(me.m_useAutomaticThreshold); m_mu1 = std::move(me.m_mu1); m_mu2 = std::move(me.m_mu2); m_min_samplestep = std::move(me.m_min_samplestep); @@ -429,6 +475,7 @@ vpMe &vpMe::operator=(const vpMe &&me) initMask(); return *this; } +#endif vpMe::~vpMe() { @@ -440,8 +487,9 @@ vpMe::~vpMe() void vpMe::setMaskNumber(const unsigned int &mask_number) { + const unsigned int flatAngle = 180; m_mask_number = mask_number; - m_anglestep = 180 / m_mask_number; + m_anglestep = flatAngle / m_mask_number; initMask(); } diff --git a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp index cfc355620b..0e2c34c101 100644 --- a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp @@ -40,24 +40,28 @@ #include #include +// #define VP_ME_ELLIPSE_REGULAR_SAMPLING +#ifndef VP_ME_ELLIPSE_REGULAR_SAMPLING +#define VP_ME_ELLIPSE_TWO_CONCENTRIC_CIRCLES +#endif vpMeEllipse::vpMeEllipse() - : K(), iPc(), a(0.), b(0.), e(0.), iP1(), iP2(), alpha1(0), alpha2(2 * M_PI), ce(0.), se(0.), angle(), m00(0.), - thresholdWeight(0.2), m_alphamin(0.), m_alphamax(0.), m_uc(0.), m_vc(0.), m_n20(0.), m_n11(0.), m_n02(0.), + : m_K(), m_iPc(), m_a(0.), m_b(0.), m_e(0.), m_iP1(), m_iP2(), m_alpha1(0), m_alpha2(2 * M_PI), m_ce(0.), m_se(0.), m_angleList(), m_m00(0.), + m_thresholdWeight(0.2), m_alphamin(0.), m_alphamax(0.), m_uc(0.), m_vc(0.), m_n20(0.), m_n11(0.), m_n02(0.), m_expectedDensity(0), m_numberOfGoodPoints(0), m_trackCircle(false), m_trackArc(false), m_arcEpsilon(1e-6) { // Resize internal parameters vector // K0 u^2 + K1 v^2 + 2 K2 u v + 2 K3 u + 2 K4 v + K5 = 0 - K.resize(6); - iP1.set_ij(0, 0); - iP2.set_ij(0, 0); + m_K.resize(6); + m_iP1.set_ij(0, 0); + m_iP2.set_ij(0, 0); } vpMeEllipse::vpMeEllipse(const vpMeEllipse &me_ellipse) - : vpMeTracker(me_ellipse), K(me_ellipse.K), iPc(me_ellipse.iPc), a(me_ellipse.a), b(me_ellipse.b), e(me_ellipse.e), - iP1(me_ellipse.iP1), iP2(me_ellipse.iP2), alpha1(me_ellipse.alpha1), alpha2(me_ellipse.alpha2), ce(me_ellipse.ce), - se(me_ellipse.se), angle(me_ellipse.angle), m00(me_ellipse.m00), - thresholdWeight(me_ellipse.thresholdWeight), + : vpMeTracker(me_ellipse), m_K(me_ellipse.m_K), m_iPc(me_ellipse.m_iPc), m_a(me_ellipse.m_a), m_b(me_ellipse.m_b), m_e(me_ellipse.m_e), + m_iP1(me_ellipse.m_iP1), m_iP2(me_ellipse.m_iP2), m_alpha1(me_ellipse.m_alpha1), m_alpha2(me_ellipse.m_alpha2), m_ce(me_ellipse.m_ce), + m_se(me_ellipse.m_se), m_angleList(me_ellipse.m_angleList), m_m00(me_ellipse.m_m00), + m_thresholdWeight(me_ellipse.m_thresholdWeight), m_alphamin(me_ellipse.m_alphamin), m_alphamax(me_ellipse.m_alphamax), m_uc(me_ellipse.m_uc), m_vc(me_ellipse.m_vc), m_n20(me_ellipse.m_n20), m_n11(me_ellipse.m_n11), m_n02(me_ellipse.m_n02), m_expectedDensity(me_ellipse.m_expectedDensity), m_numberOfGoodPoints(me_ellipse.m_numberOfGoodPoints), @@ -66,8 +70,8 @@ vpMeEllipse::vpMeEllipse(const vpMeEllipse &me_ellipse) vpMeEllipse::~vpMeEllipse() { - list.clear(); - angle.clear(); + m_meList.clear(); + m_angleList.clear(); } double vpMeEllipse::computeTheta(const vpImagePoint &iP) const @@ -80,25 +84,26 @@ double vpMeEllipse::computeTheta(const vpImagePoint &iP) const double vpMeEllipse::computeTheta(double u, double v) const { - double A = K[0] * u + K[2] * v + K[3]; - double B = K[1] * v + K[2] * u + K[4]; + double A = (m_K[0] * u) + (m_K[2] * v) + m_K[3]; + double B = (m_K[1] * v) + (m_K[2] * u) + m_K[4]; double theta = atan2(B, A); // Angle between the tangent and the u axis. if (theta < 0) { // theta in [0;Pi] // FC : pourquoi ? pour me sans doute theta += M_PI; } - return (theta); + return theta; } void vpMeEllipse::updateTheta() { vpMeSite p_me; vpImagePoint iP; - for (std::list::iterator it = list.begin(); it != list.end(); ++it) { + std::list::iterator end = m_meList.end(); + for (std::list::iterator it = m_meList.begin(); it != end; ++it) { p_me = *it; // (i,j) frame used for vpMESite - iP.set_ij(p_me.ifloat, p_me.jfloat); - p_me.alpha = computeTheta(iP); + iP.set_ij(p_me.m_ifloat, p_me.m_jfloat); + p_me.m_alpha = computeTheta(iP); *it = p_me; } } @@ -106,34 +111,33 @@ void vpMeEllipse::updateTheta() void vpMeEllipse::computePointOnEllipse(const double angle, vpImagePoint &iP) { // Two versions are available. If you change from one version to the other - // one, do not forget to change also the reciprocal function - // computeAngleOnEllipse() just below and, for a correct display of an arc - // of ellipse, adapt vpMeEllipse::display() below and + // one, do not forget to adapt, for a correct display of an arc + // of ellipse, vpMeEllipse::display() below and // vp_display_display_ellipse() in modules/core/src/display/vpDisplay_impl.h // so that the two extremities of the arc are correctly shown. +#ifdef VP_ME_ELLIPSE_REGULAR_SAMPLING // Version that gives a regular angular sampling on the ellipse, so less // points at its extremities - /* double co = cos(angle); double si = sin(angle); - double coef = a * b / sqrt(b * b * co * co + a * a * si * si); + double coef = m_a * m_b / sqrt((m_b * m_b * co * co) + (m_a * m_a * si * si)); double u = co * coef; double v = si * coef; - iP.set_u(uc + ce * u - se * v); - iP.set_v(vc + se * u + ce * v); - */ - + iP.set_u((uc + (m_ce * u)) - (m_se * v)); + iP.set_v(vc + (m_se * u) + (m_ce * v)); +#elif defined(VP_ME_ELLIPSE_TWO_CONCENTRIC_CIRCLES) // Version from "the two concentric circles" method that gives more points // at the ellipse extremities for a regular angle sampling. It is better to // display an ellipse, not necessarily to track it // (u,v) are the coordinates on the canonical centered ellipse; - double u = a * cos(angle); - double v = b * sin(angle); + double u = m_a * cos(angle); + double v = m_b * sin(angle); // a rotation of e and a translation by (uc,vc) are done // to get the coordinates of the point on the shifted ellipse - iP.set_uv(m_uc + ce * u - se * v, m_vc + se * u + ce * v); + iP.set_uv((m_uc + (m_ce * u)) - (m_se * v), m_vc + (m_se * u) + (m_ce * v)); +#endif } double vpMeEllipse::computeAngleOnEllipse(const vpImagePoint &pt) const @@ -143,101 +147,104 @@ double vpMeEllipse::computeAngleOnEllipse(const vpImagePoint &pt) const // computePointOnEllipse() just above. Adapt also the display; see comment // at the beginning of computePointOnEllipse() +#ifdef VP_ME_ELLIPSE_REGULAR_SAMPLING // Regular angle sampling method - /* double du = pt.get_u() - uc; double dv = pt.get_v() - vc; - double ang = atan2(dv,du) - e; + double ang = atan2(dv, du) - m_e; if (ang > M_PI) { ang -= 2.0 * M_PI; } else if (ang < -M_PI) { ang += 2.0 * M_PI; } - */ +#ifdef VP_ME_ELLIPSE_TWO_CONCENTRIC_CIRCLES // for the "two concentric circles method" starting from the previous one // (just to remember the link between both methods: // tan(theta_2cc) = a/b tan(theta_rs)) - /* + double co = cos(ang); double si = sin(ang); - double coeff = 1.0/sqrt(b*b*co*co+a*a*si*si); - si *= a*coeff; - co *= b*coeff; - ang = atan2(si,co); - */ + double coeff = 1.0 / sqrt((m_b * m_b * co * co) + (m_a * m_a * si * si)); + si *= m_a * coeff; + co *= m_b * coeff; + ang = atan2(si, co); +#endif +#elif defined(VP_ME_ELLIPSE_TWO_CONCENTRIC_CIRCLES) // For the "two concentric circles" method starting from scratch double du = pt.get_u() - m_uc; double dv = pt.get_v() - m_vc; - double co = (du * ce + dv * se) / a; - double si = (-du * se + dv * ce) / b; + double co = ((du * m_ce) + (dv * m_se)) / m_a; + double si = ((-du * m_se) + (dv * m_ce)) / m_b; double angle = atan2(si, co); +#endif - return (angle); + return angle; } void vpMeEllipse::computeAbeFromNij() { double num = m_n20 - m_n02; - double d = num * num + 4.0 * m_n11 * m_n11; // always >= 0 + double d = (num * num) + (4.0 * m_n11 * m_n11); // always >= 0 if (d <= std::numeric_limits::epsilon()) { - e = 0.0; // case n20 = n02 and n11 = 0 : circle, e undefined - ce = 1.0; - se = 0.0; - a = b = 2.0 * sqrt(m_n20); // = sqrt(2.0*(n20+n02)) + m_e = 0.0; // case n20 = n02 and n11 = 0 : circle, e undefined + m_ce = 1.0; + m_se = 0.0; + m_a = (m_b = 2.0 * sqrt(m_n20)); // = sqrt(2.0*(n20+n02)) } else { // real ellipse - e = atan2(2.0 * m_n11, num) / 2.0; // e in [-Pi/2 ; Pi/2] - ce = cos(e); - se = sin(e); + m_e = atan2(2.0 * m_n11, num) / 2.0; // e in [-Pi/2 ; Pi/2] + m_ce = cos(m_e); + m_se = sin(m_e); d = sqrt(d); // d in sqrt always >= 0 num = m_n20 + m_n02; - a = sqrt(2.0 * (num + d)); // term in sqrt always > 0 - b = sqrt(2.0 * (num - d)); // term in sqrt always > 0 + m_a = sqrt(2.0 * (num + d)); // term in sqrt always > 0 + m_b = sqrt(2.0 * (num - d)); // term in sqrt always > 0 } } void vpMeEllipse::computeKiFromNij() { - K[0] = m_n02; - K[1] = m_n20; - K[2] = -m_n11; - K[3] = m_n11 * m_vc - m_n02 * m_uc; - K[4] = m_n11 * m_uc - m_n20 * m_vc; - K[5] = m_n02 * m_uc * m_uc + m_n20 * m_vc * m_vc - 2.0 * m_n11 * m_uc * m_vc + 4.0 * (m_n11 * m_n11 - m_n20 * m_n02); + m_K[0] = m_n02; + m_K[1] = m_n20; + m_K[2] = -m_n11; + m_K[3] = (m_n11 * m_vc) - (m_n02 * m_uc); + m_K[4] = (m_n11 * m_uc) - (m_n20 * m_vc); + m_K[5] = (m_n02 * m_uc * m_uc) + (m_n20 * m_vc * m_vc) - (2.0 * m_n11 * m_uc * m_vc) + (4.0 * ((m_n11 * m_n11) - (m_n20 * m_n02))); } void vpMeEllipse::computeNijFromAbe() { - m_n20 = 0.25 * (a * a * ce * ce + b * b * se * se); - m_n11 = 0.25 * se * ce * (a * a - b * b); - m_n02 = 0.25 * (a * a * se * se + b * b * ce * ce); + m_n20 = 0.25 * ((m_a * m_a * m_ce * m_ce) + (m_b * m_b * m_se * m_se)); + m_n11 = 0.25 * m_se * m_ce * ((m_a * m_a) - (m_b * m_b)); + m_n02 = 0.25 * ((m_a * m_a * m_se * m_se) + (m_b * m_b * m_ce * m_ce)); } void vpMeEllipse::getParameters() { // Equations below from Chaumette PhD and TRO 2004 paper - double num = K[0] * K[1] - K[2] * K[2]; // > 0 for an ellipse + double num = (m_K[0] * m_K[1]) - (m_K[2] * m_K[2]); // > 0 for an ellipse if (num <= 0) { throw(vpException(vpException::fatalError, "The points do not belong to an ellipse! num: %f", num)); } - m_uc = (K[2] * K[4] - K[1] * K[3]) / num; - m_vc = (K[2] * K[3] - K[0] * K[4]) / num; - iPc.set_uv(m_uc, m_vc); + m_uc = ((m_K[2] * m_K[4]) - (m_K[1] * m_K[3])) / num; + m_vc = ((m_K[2] * m_K[3]) - (m_K[0] * m_K[4])) / num; + m_iPc.set_uv(m_uc, m_vc); - double d = (K[0] * m_uc * m_uc + K[1] * m_vc * m_vc + 2.0 * K[2] * m_uc * m_vc - K[5]) / (4.0 * num); - m_n20 = K[1] * d; // always > 0 - m_n11 = -K[2] * d; - m_n02 = K[0] * d; // always > 0 + double d = (((m_K[0] * m_uc * m_uc) + (m_K[1] * m_vc * m_vc) + (2.0 * m_K[2] * m_uc * m_vc)) - m_K[5]) / (4.0 * num); + m_n20 = m_K[1] * d; // always > 0 + m_n11 = -m_K[2] * d; + m_n02 = m_K[0] * d; // always > 0 computeAbeFromNij(); // normalization so that K0 = n02, K1 = n20, etc (Eq (25) of TRO paper) - d = m_n02 / K[0]; // fabs(K[0]) > 0 - for (unsigned int i = 0; i < 6; i++) { - K[i] *= d; + d = m_n02 / m_K[0]; // fabs(K[0]) > 0 + unsigned int Ksize = m_K.size(); + for (unsigned int i = 0; i < Ksize; ++i) { + m_K[i] *= d; } if (vpDEBUG_ENABLE(3)) { printParameters(); @@ -246,64 +253,70 @@ void vpMeEllipse::getParameters() void vpMeEllipse::printParameters() const { - std::cout << "K :" << K.t() << std::endl; + std::cout << "K :" << m_K.t() << std::endl; std::cout << "xc = " << m_uc << ", yc = " << m_vc << std::endl; std::cout << "n20 = " << m_n20 << ", n11 = " << m_n11 << ", n02 = " << m_n02 << std::endl; - std::cout << "A = " << a << ", B = " << b << ", E (dg) " << vpMath::deg(e) << std::endl; + std::cout << "A = " << m_a << ", B = " << m_b << ", E (dg) " << vpMath::deg(m_e) << std::endl; } void vpMeEllipse::sample(const vpImage &I, bool doNotTrack) { // Warning: similar code in vpMbtMeEllipse::sample() - if (!me) { + if (!m_me) { throw(vpException(vpException::fatalError, "Moving edges on ellipse not initialized")); } // Delete old lists - list.clear(); - angle.clear(); + m_meList.clear(); + m_angleList.clear(); int nbrows = static_cast(I.getHeight()); int nbcols = static_cast(I.getWidth()); // New version using distance for sampling - if (std::fabs(me->getSampleStep()) <= std::numeric_limits::epsilon()) { + if (std::fabs(m_me->getSampleStep()) <= std::numeric_limits::epsilon()) { std::cout << "Warning: In vpMeEllipse::sample() "; std::cout << "function called with sample step = 0. We set it rather to 10 pixels"; // std::cout << "function called with sample step = 0, set to 10 dg"; - me->setSampleStep(10.0); + m_me->setSampleStep(10.0); } // Perimeter of the ellipse using Ramanujan formula - double perim = M_PI * (3.0 * (a + b) - sqrt((3.0 * a + b) * (a + 3.0 * b))); + double perim = M_PI * ((3.0 * (m_a + m_b)) - sqrt(((3.0 * m_a) + m_b) * (m_a + (3.0 * m_b)))); // Number of points for a complete ellipse - unsigned int nb_pt = static_cast(floor(perim / me->getSampleStep())); - double incr = 2.0 * M_PI / nb_pt; + unsigned int nb_pt = static_cast(floor(perim / m_me->getSampleStep())); + double incr = (2.0 * M_PI) / nb_pt; // Compute of the expected density if (!m_trackArc) { // number of points for a complete ellipse m_expectedDensity = nb_pt; } else { // number of points for an arc of ellipse - m_expectedDensity *= static_cast(floor(perim / me->getSampleStep() * (alpha2 - alpha1) / (2.0 * M_PI))); + m_expectedDensity *= static_cast(floor((perim / m_me->getSampleStep()) * ((m_alpha2 - m_alpha1) / (2.0 * M_PI)))); } // Starting angle for sampling: new version to not start at 0 - double ang = alpha1 + incr / 2.0; + double ang = m_alpha1 + (incr / 2.0); // sample positions - for (unsigned int i = 0; i < m_expectedDensity; i++) { + for (unsigned int i = 0; i < m_expectedDensity; ++i) { vpImagePoint iP; computePointOnEllipse(ang, iP); // If point is in the image, add to the sample list // Check done in (i,j) frame) - if (!outOfImage(vpMath::round(iP.get_i()), vpMath::round(iP.get_j()), 0, nbrows, nbcols)) { - vpDisplay::displayCross(I, iP, 5, vpColor::red); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) + && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + const unsigned int crossSize = 5; + vpDisplay::displayCross(I, iP, crossSize, vpColor::red); double theta = computeTheta(iP); vpMeSite pix; // (i,j) frame used for vpMeSite pix.init(iP.get_i(), iP.get_j(), theta); - pix.setDisplay(selectDisplay); + pix.setDisplay(m_selectDisplay); pix.setState(vpMeSite::NO_SUPPRESSION); - list.push_back(pix); - angle.push_back(ang); + const double marginRatio = m_me->getThresholdMarginRatio(); + double convolution = pix.convolution(I, m_me); + double contrastThreshold = fabs(convolution) * marginRatio; + pix.setContrastThreshold(contrastThreshold, *m_me); + m_meList.push_back(pix); + m_angleList.push_back(ang); } ang += incr; } @@ -315,47 +328,52 @@ void vpMeEllipse::sample(const vpImage &I, bool doNotTrack) unsigned int vpMeEllipse::plugHoles(const vpImage &I) { - if (!me) { + if (!m_me) { throw(vpException(vpException::fatalError, "Moving edges on ellipse tracking not initialized")); } unsigned int nb_pts_added = 0; int nbrows = static_cast(I.getHeight()); int nbcols = static_cast(I.getWidth()); - unsigned int memory_range = me->getRange(); - me->setRange(2); + unsigned int memory_range = m_me->getRange(); + m_me->setRange(2); // Perimeter of the ellipse using Ramanujan formula - double perim = M_PI * (3.0 * (a + b) - sqrt((3.0 * a + b) * (a + 3.0 * b))); + double perim = M_PI * ((3.0 * (m_a + m_b)) - sqrt(((3.0 * m_a) + m_b) * (m_a + (3.0 * m_b)))); // Number of points for a complete ellipse - unsigned int nb_pt = static_cast(floor(perim / me->getSampleStep())); - double incr = 2.0 * M_PI / nb_pt; + unsigned int nb_pt = static_cast(floor(perim / m_me->getSampleStep())); + double incr = (2.0 * M_PI) / nb_pt; // Detect holes and try to complete them // In this option, the sample step is used to complete the holes as much as possible - std::list::iterator angleList = angle.begin(); - std::list::iterator meList = list.begin(); + std::list::iterator angleList = m_angleList.begin(); + std::list::iterator meList = m_meList.begin(); + const double marginRatio = m_me->getThresholdMarginRatio(); double ang = *angleList; ++angleList; ++meList; - while (meList != list.end()) { + + while (meList != m_meList.end()) { double nextang = *angleList; - if ((nextang - ang) > 2.0 * incr) { // A hole exists + if ((nextang - ang) > (2.0 * incr)) { // A hole exists ang += incr; // next point to be checked // adding only 1 point if hole of 1 point while (ang < (nextang - incr)) { vpImagePoint iP; computePointOnEllipse(ang, iP); - if (!outOfImage(vpMath::round(iP.get_i()), vpMath::round(iP.get_j()), 0, nbrows, nbcols)) { + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); - pix.setDisplay(selectDisplay); + pix.setDisplay(m_selectDisplay); pix.setState(vpMeSite::NO_SUPPRESSION); - pix.track(I, me, false); + double convolution = pix.convolution(I, m_me); + double contrastThreshold = fabs(convolution) * marginRatio; + pix.setContrastThreshold(contrastThreshold, *m_me); + pix.track(I, m_me, false); if (pix.getState() == vpMeSite::NO_SUPPRESSION) { // good point - nb_pts_added++; - iP.set_ij(pix.ifloat, pix.jfloat); + ++nb_pts_added; + iP.set_ij(pix.get_ifloat(), pix.get_jfloat()); double new_ang = computeAngleOnEllipse(iP); if ((new_ang - ang) > M_PI) { new_ang -= 2.0 * M_PI; @@ -363,10 +381,11 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) else if ((ang - new_ang) > M_PI) { new_ang += 2.0 * M_PI; } - list.insert(meList, pix); - angle.insert(angleList, new_ang); + m_meList.insert(meList, pix); + m_angleList.insert(angleList, new_ang); if (vpDEBUG_ENABLE(3)) { - vpDisplay::displayCross(I, iP, 5, vpColor::blue); + const unsigned int crossSize = 5; + vpDisplay::displayCross(I, iP, crossSize, vpColor::blue); } } } @@ -385,32 +404,35 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) } // Add points in case two neighboring points are too far away - angleList = angle.begin(); + angleList = m_angleList.begin(); ang = *angleList; - meList = list.begin(); + meList = m_meList.begin(); vpMeSite pix1 = *meList; ++angleList; ++meList; - while (meList != list.end()) { + while (meList != m_meList.end()) { double nextang = *angleList; vpMeSite pix2 = *meList; - double dist = sqrt((pix1.ifloat - pix2.ifloat) * (pix1.ifloat - pix2.ifloat) - + (pix1.jfloat - pix2.jfloat) * (pix1.jfloat - pix2.jfloat)); + double dist = sqrt(((pix1.get_ifloat() - pix2.get_ifloat()) * (pix1.get_ifloat() - pix2.get_ifloat())) + + ((pix1.get_jfloat() - pix2.get_jfloat()) * (pix1.get_jfloat() - pix2.get_jfloat()))); // Only one point is added if two neighboring points are too far away - if (dist > 2.0 * me->getSampleStep()) { + if (dist > (2.0 * m_me->getSampleStep())) { ang = (nextang + ang) / 2.0; // point added at mid angle vpImagePoint iP; computePointOnEllipse(ang, iP); - if (!outOfImage(vpMath::round(iP.get_i()), vpMath::round(iP.get_j()), 0, nbrows, nbcols)) { + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); - pix.setDisplay(selectDisplay); + pix.setDisplay(m_selectDisplay); pix.setState(vpMeSite::NO_SUPPRESSION); - pix.track(I, me, false); + double convolution = pix.convolution(I, m_me); + double contrastThreshold = fabs(convolution) * marginRatio; + pix.setContrastThreshold(contrastThreshold, *m_me); + pix.track(I, m_me, false); if (pix.getState() == vpMeSite::NO_SUPPRESSION) { // good point - nb_pts_added++; - iP.set_ij(pix.ifloat, pix.jfloat); + ++nb_pts_added; + iP.set_ij(pix.get_ifloat(), pix.get_jfloat()); double new_ang = computeAngleOnEllipse(iP); if ((new_ang - ang) > M_PI) { new_ang -= 2.0 * M_PI; @@ -418,10 +440,11 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) else if ((ang - new_ang) > M_PI) { new_ang += 2.0 * M_PI; } - list.insert(meList, pix); - angle.insert(angleList, new_ang); + m_meList.insert(meList, pix); + m_angleList.insert(angleList, new_ang); if (vpDEBUG_ENABLE(3)) { - vpDisplay::displayCross(I, iP, 5, vpColor::blue); + const unsigned int crossSize = 5; + vpDisplay::displayCross(I, iP, crossSize, vpColor::blue); } } } @@ -435,8 +458,8 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) if (vpDEBUG_ENABLE(3)) { if (nb_pts_added > 0) { std::cout << "Number of added points from holes : " << nb_pts_added << std::endl; - angleList = angle.begin(); - while (angleList != angle.end()) { + angleList = m_angleList.begin(); + while (angleList != m_angleList.end()) { ang = *angleList; std::cout << "ang = " << vpMath::deg(ang) << std::endl; ++angleList; @@ -445,25 +468,31 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) } // Try to fill the first extremity: from alpha_min - incr to alpha1 + incr/2 + meList = m_meList.begin(); + pix1 = *meList; unsigned int nbpts = 0; // Add - incr/2.0 to avoid being too close to 0 - if ((m_alphamin - alpha1 - incr / 2.0) > 0.0) { - nbpts = static_cast(floor((m_alphamin - alpha1 - incr / 2.0) / incr)); + if ((m_alphamin - m_alpha1 - (incr / 2.0)) > 0.0) { + nbpts = static_cast(floor((m_alphamin - m_alpha1 - (incr / 2.0)) / incr)); } ang = m_alphamin - incr; - for (unsigned int i = 0; i < nbpts; i++) { + for (unsigned int i = 0; i < nbpts; ++i) { vpImagePoint iP; computePointOnEllipse(ang, iP); - if (!outOfImage(vpMath::round(iP.get_i()), vpMath::round(iP.get_j()), 0, nbrows, nbcols)) { + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); - pix.setDisplay(selectDisplay); + pix.setDisplay(m_selectDisplay); pix.setState(vpMeSite::NO_SUPPRESSION); - pix.track(I, me, false); + //pix.setContrastThreshold(pix1.getContrastThreshold(), *m_me); + double convolution = pix.convolution(I, m_me); + double contrastThreshold = fabs(convolution) * marginRatio; + pix.setContrastThreshold(contrastThreshold, *m_me); + pix.track(I, m_me, false); if (pix.getState() == vpMeSite::NO_SUPPRESSION) { - nb_pts_added++; - iP.set_ij(pix.ifloat, pix.jfloat); + ++nb_pts_added; + iP.set_ij(pix.get_ifloat(), pix.get_jfloat()); double new_ang = computeAngleOnEllipse(iP); if ((new_ang - ang) > M_PI) { new_ang -= 2.0 * M_PI; @@ -471,10 +500,11 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) else if ((ang - new_ang) > M_PI) { new_ang += 2.0 * M_PI; } - list.push_front(pix); - angle.push_front(new_ang); + m_meList.push_front(pix); + m_angleList.push_front(new_ang); if (vpDEBUG_ENABLE(3)) { - vpDisplay::displayCross(I, iP, 5, vpColor::blue); + const unsigned int crossSize = 5; + vpDisplay::displayCross(I, iP, crossSize, vpColor::blue); std::cout << "Add extremity 1, ang = " << vpMath::deg(new_ang) << std::endl; } } @@ -489,24 +519,29 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) } // Try to fill the second extremity: from alphamax + incr to alpha2 - incr/2 + pix1 = m_meList.back(); nbpts = 0; - if ((alpha2 - incr / 2.0 - m_alphamax) > 0.0) { - nbpts = static_cast(floor((alpha2 - incr / 2.0 - m_alphamax) / incr)); + if ((m_alpha2 - (incr / 2.0) - m_alphamax) > 0.0) { + nbpts = static_cast(floor((m_alpha2 - (incr / 2.0) - m_alphamax) / incr)); } + ang = m_alphamax + incr; - for (unsigned int i = 0; i < nbpts; i++) { + for (unsigned int i = 0; i < nbpts; ++i) { vpImagePoint iP; computePointOnEllipse(ang, iP); - if (!outOfImage(vpMath::round(iP.get_i()), vpMath::round(iP.get_j()), 0, nbrows, nbcols)) { + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); - pix.setDisplay(selectDisplay); + pix.setDisplay(m_selectDisplay); pix.setState(vpMeSite::NO_SUPPRESSION); - pix.track(I, me, false); + double convolution = pix.convolution(I, m_me); + double contrastThreshold = fabs(convolution) * marginRatio; + pix.setContrastThreshold(contrastThreshold, *m_me); + pix.track(I, m_me, false); if (pix.getState() == vpMeSite::NO_SUPPRESSION) { - nb_pts_added++; - iP.set_ij(pix.ifloat, pix.jfloat); + ++nb_pts_added; + iP.set_ij(pix.get_ifloat(), pix.get_jfloat()); double new_ang = computeAngleOnEllipse(iP); if ((new_ang - ang) > M_PI) { new_ang -= 2.0 * M_PI; @@ -514,17 +549,24 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) else if ((ang - new_ang) > M_PI) { new_ang += 2.0 * M_PI; } - list.push_back(pix); - angle.push_back(new_ang); + m_meList.push_back(pix); + m_angleList.push_back(new_ang); if (vpDEBUG_ENABLE(3)) { - vpDisplay::displayCross(I, iP, 5, vpColor::blue); + const unsigned int crossSize = 5; + vpDisplay::displayCross(I, iP, crossSize, vpColor::blue); std::cout << "Add extremity 2, ang = " << vpMath::deg(new_ang) << std::endl; } } } ang += incr; } - me->setRange(memory_range); + m_me->setRange(memory_range); + + if (m_meList.size() != m_angleList.size()) { + // Should never occur + throw(vpException(vpException::fatalError, "Lists are not coherent in vpMeEllipse::plugHoles(): nb MEs %ld, nb ang %ld", + m_meList.size(), m_angleList.size())); + } if (vpDEBUG_ENABLE(3)) { if (nb_pts_added > 0) { @@ -541,7 +583,8 @@ void vpMeEllipse::leastSquare(const vpImage &I, const std::vector unsigned int n = static_cast(iP.size()); if (m_trackCircle) { // we track a circle - if (n < 3) { + const unsigned int circleDims = 3; + if (n < circleDims) { throw(vpException(vpException::dimensionError, "Not enough points to compute the circle")); } // System A x = b to be solved by least squares @@ -550,25 +593,25 @@ void vpMeEllipse::leastSquare(const vpImage &I, const std::vector vpMatrix A(n, 3); vpColVector b(n); - for (unsigned int k = 0; k < n; k++) { + for (unsigned int k = 0; k < n; ++k) { // normalization so that (u,v) in [-1;1] double u = (iP[k].get_u() - um) / um; double v = (iP[k].get_v() - vm) / um; // um here to not deform the circle A[k][0] = u; A[k][1] = v; A[k][2] = 1.0; - b[k] = u * u + v * v; + b[k] = (u * u) + (v * v); } vpColVector x(3); x = A.solveBySVD(b); // A circle is a particular ellipse. Going from x for circle to K for ellipse // using inverse normalization to go back to pixel values double ratio = vm / um; - K[0] = K[1] = 1.0 / (um * um); - K[2] = 0.0; - K[3] = -(1.0 + x[0] / 2.0) / um; - K[4] = -(ratio + x[1] / 2.0) / um; - K[5] = -x[2] + 1.0 + ratio * ratio + x[0] + ratio * x[1]; + m_K[0] = (m_K[1] = 1.0 / (um * um)); + m_K[2] = 0.0; + m_K[3] = -(1.0 + (x[0] / 2.0)) / um; + m_K[4] = -(ratio + (x[1] / 2.0)) / um; + m_K[5] = -x[2] + 1.0 + (ratio * ratio) + x[0] + (ratio * x[1]); } else { // we track an ellipse if (n < 5) { @@ -587,7 +630,7 @@ void vpMeEllipse::leastSquare(const vpImage &I, const std::vector vpMatrix A(n, 6); - for (unsigned int k = 0; k < n; k++) { + for (unsigned int k = 0; k < n; ++k) { // Normalization so that (u,v) in [-1;1] double u = (iP[k].get_u() - um) / um; double v = (iP[k].get_v() - vm) / vm; @@ -603,15 +646,17 @@ void vpMeEllipse::leastSquare(const vpImage &I, const std::vector if (dim > 1) { // case with less than 5 independent points throw(vpException(vpMatrixException::rankDeficient, "Linear system for computing the ellipse equation ill conditioned")); } - for (unsigned int i = 0; i < 6; i++) - K[i] = KerA[i][0]; + unsigned int nbRows = m_K.getRows(); + for (unsigned int i = 0; i < nbRows; ++i) { + m_K[i] = KerA[i][0]; + } // inverse normalization - K[0] *= vm / um; - K[1] *= um / vm; - K[3] = K[3] * vm - K[0] * um - K[2] * vm; - K[4] = K[4] * um - K[1] * vm - K[2] * um; - K[5] = K[5] * um * vm - K[0] * um * um - K[1] * vm * vm - 2.0 * K[2] * um * vm - 2.0 * K[3] * um - 2.0 * K[4] * vm; + m_K[0] *= vm / um; + m_K[1] *= um / vm; + m_K[3] = (m_K[3] * vm) - (m_K[0] * um) - (m_K[2] * vm); + m_K[4] = (m_K[4] * um) - (m_K[1] * vm) - (m_K[2] * um); + m_K[5] = (m_K[5] * um * vm) - (m_K[0] * um * um) - (m_K[1] * vm * vm) - (2.0 * m_K[2] * um * vm) - (2.0 * m_K[3] * um) - (2.0 * m_K[4] * vm); } getParameters(); } @@ -639,26 +684,30 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) // Useful to compute the weights in the robust estimation vpColVector xp(nos), yp(nos); + std::list::const_iterator end = m_meList.end(); - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::const_iterator it = m_meList.begin(); it != end; ++it) { vpMeSite p_me = *it; if (p_me.getState() == vpMeSite::NO_SUPPRESSION) { // from (i,j) to (u,v) frame + normalization so that (u,v) in [-1;1] - double u = (p_me.jfloat - um) / um; - double v = (p_me.ifloat - vm) / um; // um to not deform the circle + double u = (p_me.get_jfloat() - um) / um; + double v = (p_me.get_ifloat() - vm) / um; // um to not deform the circle A[k][0] = u; A[k][1] = v; A[k][2] = 1.0; - b[k] = u * u + v * v; + b[k] = (u * u) + (v * v); // Useful to compute the weights in the robust estimation - xp[k] = p_me.jfloat; - yp[k] = p_me.ifloat; + xp[k] = p_me.get_jfloat(); + yp[k] = p_me.get_ifloat(); - k++; + ++k; } } - if (k < 3) { - throw(vpException(vpException::dimensionError, "Not enough moving edges %d / %d to track the circle ", k, list.size())); + + const unsigned int minRequiredNbMe = 3; + if (k < minRequiredNbMe) { + throw(vpException(vpException::dimensionError, "Not enough moving edges %d / %d to track the circle ", + k, m_meList.size())); } vpRobust r; @@ -673,9 +722,11 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) xg_prev = -10.0; // stop after 4 it or if cog variation between 2 it is more than 1 pixel - while ((iter < 4) && (var > 0.1)) { - for (unsigned int i = 0; i < k; i++) { - for (unsigned int j = 0; j < 3; j++) { + const unsigned int maxNbIter = 4; + const unsigned int widthDA = DA.getCols(); + while ((iter < maxNbIter) && (var > 0.1)) { + for (unsigned int i = 0; i < k; ++i) { + for (unsigned int j = 0; j < widthDA; ++j) { DA[i][j] = w[i] * A[i][j]; } Db[i] = w[i] * b[i]; @@ -685,11 +736,11 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) // A circle is a particular ellipse. Going from x for circle to K for ellipse // using inverse normalization to go back to pixel values double ratio = vm / um; - K[0] = K[1] = 1.0 / (um * um); - K[2] = 0.0; - K[3] = -(1.0 + x[0] / 2.0) / um; - K[4] = -(ratio + x[1] / 2.0) / um; - K[5] = -x[2] + 1.0 + ratio * ratio + x[0] + ratio * x[1]; + m_K[0] = (m_K[1] = 1.0 / (um * um)); + m_K[2] = 0.0; + m_K[3] = -(1.0 + (x[0] / 2.0)) / um; + m_K[4] = -(ratio + (x[1] / 2.0)) / um; + m_K[5] = -x[2] + 1.0 + (ratio * ratio) + x[0] + (ratio * x[1]); getParameters(); vpColVector xg(2); @@ -699,10 +750,10 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) xg_prev = xg; vpColVector residu(k); // near to geometric distance in pixel - for (unsigned int i = 0; i < k; i++) { + for (unsigned int i = 0; i < k; ++i) { double x = xp[i]; double y = yp[i]; - double sign = K[0] * x * x + K[1] * y * y + 2. * K[2] * x * y + 2. * K[3] * x + 2. * K[4] * y + K[5]; + double sign = (m_K[0] * x * x) + (m_K[1] * y * y) + (2. * m_K[2] * x * y) + (2. * m_K[3] * x) + (2. * m_K[4] * y) + m_K[5]; vpImagePoint ip1, ip2; ip1.set_uv(x, y); double ang = computeAngleOnEllipse(ip1); @@ -717,7 +768,7 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) } r.MEstimator(vpRobust::TUKEY, residu, w); - iter++; + ++iter; } } else { // we track an ellipse @@ -736,13 +787,14 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) vpMatrix A(nos, 6); // Useful to compute the weights in the robust estimation vpColVector xp(nos), yp(nos); + std::list::const_iterator end = m_meList.end(); - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::const_iterator it = m_meList.begin(); it != end; ++it) { vpMeSite p_me = *it; if (p_me.getState() == vpMeSite::NO_SUPPRESSION) { // from (i,j) to (u,v) frame + normalization so that (u,v) in [-1;1] - double u = (p_me.jfloat - um) / um; - double v = (p_me.ifloat - vm) / vm; + double u = (p_me.get_jfloat() - um) / um; + double v = (p_me.get_ifloat() - vm) / vm; A[k][0] = u * u; A[k][1] = v * v; A[k][2] = 2.0 * u * v; @@ -750,13 +802,15 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) A[k][4] = 2.0 * v; A[k][5] = 1.0; // Useful to compute the weights in the robust estimation - xp[k] = p_me.jfloat; - yp[k] = p_me.ifloat; + xp[k] = p_me.get_jfloat(); + yp[k] = p_me.get_ifloat(); - k++; + ++k; } } - if (k < 5) { + + const unsigned int minRequiredMe = 5; + if (k < minRequiredMe) { throw(vpException(vpException::dimensionError, "Not enough moving edges to track the ellipse")); } @@ -771,9 +825,11 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) xg_prev = -10.0; // Stop after 4 iterations or if cog variation between 2 iterations is more than 0.1 pixel - while ((iter < 4) && (var > 0.1)) { - for (unsigned int i = 0; i < k; i++) { - for (unsigned int j = 0; j < 6; j++) { + const unsigned int maxIter = 4; + const unsigned int widthDA = DA.getCols(); + while ((iter < maxIter) && (var > 0.1)) { + for (unsigned int i = 0; i < k; ++i) { + for (unsigned int j = 0; j < widthDA; ++j) { DA[i][j] = w[i] * A[i][j]; } } @@ -782,15 +838,17 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) throw(vpException(vpMatrixException::rankDeficient, "Linear system for computing the ellipse equation ill conditioned")); } - for (unsigned int i = 0; i < 6; i++) - K[i] = KerDA[i][0]; // norm(K) = 1 + + for (unsigned int i = 0; i < 6; ++i) { + m_K[i] = KerDA[i][0]; // norm(K) = 1 + } // inverse normalization - K[0] *= vm / um; - K[1] *= um / vm; - K[3] = K[3] * vm - K[0] * um - K[2] * vm; - K[4] = K[4] * um - K[1] * vm - K[2] * um; - K[5] = K[5] * um * vm - K[0] * um * um - K[1] * vm * vm - 2.0 * K[2] * um * vm - 2.0 * K[3] * um - 2.0 * K[4] * vm; + m_K[0] *= vm / um; + m_K[1] *= um / vm; + m_K[3] = (m_K[3] * vm) - (m_K[0] * um) - (m_K[2] * vm); + m_K[4] = (m_K[4] * um) - (m_K[1] * vm) - (m_K[2] * um); + m_K[5] = (m_K[5] * um * vm) - (m_K[0] * um * um) - (m_K[1] * vm * vm) - (2.0 * m_K[2] * um * vm) - (2.0 * m_K[3] * um) - (2.0 * m_K[4] * vm); getParameters(); // since a, b, and e are used just after vpColVector xg(2); @@ -800,10 +858,10 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) xg_prev = xg; vpColVector residu(k); - for (unsigned int i = 0; i < k; i++) { + for (unsigned int i = 0; i < k; ++i) { double x = xp[i]; double y = yp[i]; - double sign = K[0] * x * x + K[1] * y * y + 2. * K[2] * x * y + 2. * K[3] * x + 2. * K[4] * y + K[5]; + double sign = (m_K[0] * x * x) + (m_K[1] * y * y) + (2. * m_K[2] * x * y) + (2. * m_K[3] * x) + (2. * m_K[4] * y) + m_K[5]; vpImagePoint ip1, ip2; ip1.set_uv(x, y); double ang = computeAngleOnEllipse(ip1); @@ -818,7 +876,7 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) } r.MEstimator(vpRobust::TUKEY, residu, w); - iter++; + ++iter; } } // end of case ellipse @@ -826,38 +884,42 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) // Modify the angle to order the list double previous_ang = -4.0 * M_PI; k = 0; - std::list::iterator angleList = angle.begin(); - for (std::list::iterator meList = list.begin(); meList != list.end();) { + std::list::iterator angleList = m_angleList.begin(); + std::list::iterator end = m_meList.end(); + std::list::iterator meList = m_meList.begin(); + while (meList != end) { vpMeSite p_me = *meList; if (p_me.getState() != vpMeSite::NO_SUPPRESSION) { // points not selected as me double ang = *angleList; - meList = list.erase(meList); - angleList = angle.erase(angleList); + meList = m_meList.erase(meList); + angleList = m_angleList.erase(angleList); if (vpDEBUG_ENABLE(3)) { vpImagePoint iP; - iP.set_ij(p_me.ifloat, p_me.jfloat); - printf("point %d not me i : %.0f , j : %0.f, ang = %lf\n", k, p_me.ifloat, p_me.jfloat, vpMath::deg(ang)); - vpDisplay::displayCross(I, iP, 10, vpColor::blue, 1); + iP.set_ij(p_me.m_ifloat, p_me.m_jfloat); + printf("point %d not me i : %.0f , j : %0.f, ang = %lf\n", k, p_me.get_ifloat(), p_me.get_jfloat(), vpMath::deg(ang)); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, iP, crossSize, vpColor::blue, 1); } } else { - if (w[k] < thresholdWeight) { // outlier + if (w[k] < m_thresholdWeight) { // outlier double ang = *angleList; - meList = list.erase(meList); - angleList = angle.erase(angleList); + meList = m_meList.erase(meList); + angleList = m_angleList.erase(angleList); if (vpDEBUG_ENABLE(3)) { vpImagePoint iP; - iP.set_ij(p_me.ifloat, p_me.jfloat); + iP.set_ij(p_me.m_ifloat, p_me.m_jfloat); printf("point %d outlier i : %.0f , j : %0.f, ang = %lf, poids : %lf\n", - k, p_me.ifloat, p_me.jfloat, vpMath::deg(ang), w[k]); - vpDisplay::displayCross(I, iP, 10, vpColor::cyan, 1); + k, p_me.get_ifloat(), p_me.get_jfloat(), vpMath::deg(ang), w[k]); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, iP, crossSize, vpColor::cyan, 1); } } else { // good point double ang = *angleList; vpImagePoint iP; - iP.set_ij(p_me.ifloat, p_me.jfloat); + iP.set_ij(p_me.m_ifloat, p_me.m_jfloat); double new_ang = computeAngleOnEllipse(iP); if ((new_ang - ang) > M_PI) { new_ang -= 2.0 * M_PI; @@ -865,18 +927,26 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) else if ((ang - new_ang) > M_PI) { new_ang += 2.0 * M_PI; } - *angleList = previous_ang = new_ang; + previous_ang = new_ang; + *angleList = new_ang; ++meList; ++angleList; if (vpDEBUG_ENABLE(3)) { - printf("point %d inlier i : %.0f , j : %0.f, poids : %lf\n", k, p_me.ifloat, p_me.jfloat, w[k]); - vpDisplay::displayCross(I, iP, 10, vpColor::cyan, 1); + printf("point %d inlier i : %.0f , j : %0.f, poids : %lf\n", k, p_me.get_ifloat(), p_me.get_jfloat(), w[k]); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, iP, crossSize, vpColor::cyan, 1); } } - k++; + ++k; // k contains good points and outliers (used for w[k]) } } + if (m_meList.size() != m_angleList.size()) { + // Should never occur + throw(vpException(vpException::fatalError, "Lists are not coherent in vpMeEllipse::leastSquareRobust(): nb MEs %ld, nb ang %ld", + m_meList.size(), m_angleList.size())); + } + // Manage the list so that all new angles belong to [0;2Pi] bool nbdeb = false; std::list finAngle; @@ -885,40 +955,41 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) finMe.clear(); std::list::iterator debutAngleList; std::list::iterator debutMeList; - angleList = angle.begin(); - std::list::iterator meList; - for (meList = list.begin(); meList != list.end();) { + angleList = m_angleList.begin(); + meList = m_meList.begin(); + end = m_meList.end(); + while (meList != end) { vpMeSite p_me = *meList; double ang = *angleList; // Move these ones to another list to be added at the end - if (ang < alpha1) { + if (ang < m_alpha1) { ang += 2.0 * M_PI; - angleList = angle.erase(angleList); + angleList = m_angleList.erase(angleList); finAngle.push_back(ang); - meList = list.erase(meList); + meList = m_meList.erase(meList); finMe.push_back(p_me); } // Moved at the beginning of the list - else if (ang > alpha2) { + else if (ang > m_alpha2) { ang -= 2.0 * M_PI; - angleList = angle.erase(angleList); - meList = list.erase(meList); + angleList = m_angleList.erase(angleList); + meList = m_meList.erase(meList); if (!nbdeb) { - angle.push_front(ang); - debutAngleList = angle.begin(); + m_angleList.push_front(ang); + debutAngleList = m_angleList.begin(); ++debutAngleList; - list.push_front(p_me); - debutMeList = list.begin(); + m_meList.push_front(p_me); + debutMeList = m_meList.begin(); ++debutMeList; nbdeb = true; } else { - debutAngleList = angle.insert(debutAngleList, ang); + debutAngleList = m_angleList.insert(debutAngleList, ang); ++debutAngleList; - debutMeList = list.insert(debutMeList, p_me); + debutMeList = m_meList.insert(debutMeList, p_me); ++debutMeList; } } @@ -928,90 +999,104 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) } } // Fuse the lists - angleList = angle.end(); - angle.splice(angleList, finAngle); - meList = list.end(); - list.splice(meList, finMe); + angleList = m_angleList.end(); + m_angleList.splice(angleList, finAngle); + meList = m_meList.end(); + m_meList.splice(meList, finMe); unsigned int numberOfGoodPoints = 0; previous_ang = -4.0 * M_PI; // Perimeter of the ellipse using Ramanujan formula - double perim = M_PI * (3.0 * (a + b) - sqrt((3.0 * a + b) * (a + 3.0 * b))); - unsigned int nb_pt = static_cast(floor(perim / me->getSampleStep())); - double incr = 2.0 * M_PI / nb_pt; + double perim = M_PI * ((3.0 * (m_a + m_b)) - sqrt(((3.0 * m_a) + m_b) * (m_a + (3.0 * m_b)))); + unsigned int nb_pt = static_cast(floor(perim / m_me->getSampleStep())); + double incr = (2.0 * M_PI) / nb_pt; // Update of the expected density if (!m_trackArc) { // number of points for a complete ellipse m_expectedDensity = nb_pt; } else { // number of points for an arc of ellipse - m_expectedDensity *= static_cast(floor(perim / me->getSampleStep() * (alpha2 - alpha1) / (2.0 * M_PI))); + m_expectedDensity *= static_cast(floor((perim / m_me->getSampleStep()) * ((m_alpha2 - m_alpha1) / (2.0 * M_PI)))); } // Keep only the points in the interval [alpha1 ; alpha2] // and those that are not too close - angleList = angle.begin(); - for (std::list::iterator meList = list.begin(); meList != list.end();) { + angleList = m_angleList.begin(); + end = m_meList.end(); + meList = m_meList.begin(); + while (meList != end) { vpMeSite p_me = *meList; double new_ang = *angleList; - if ((new_ang >= alpha1) && (new_ang <= alpha2)) { + if ((new_ang >= m_alpha1) && (new_ang <= m_alpha2)) { if ((new_ang - previous_ang) >= (0.6 * incr)) { previous_ang = new_ang; - numberOfGoodPoints++; + ++numberOfGoodPoints; ++meList; ++angleList; if (vpDEBUG_ENABLE(3)) { vpImagePoint iP; - iP.set_ij(p_me.ifloat, p_me.jfloat); - vpDisplay::displayCross(I, iP, 10, vpColor::red, 1); + iP.set_ij(p_me.m_ifloat, p_me.m_jfloat); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, iP, crossSize, vpColor::red, 1); printf("In LQR: angle : %lf, i = %.0lf, j = %.0lf\n", vpMath::deg(new_ang), iP.get_i(), iP.get_j()); } } else { - meList = list.erase(meList); - angleList = angle.erase(angleList); + meList = m_meList.erase(meList); + angleList = m_angleList.erase(angleList); if (vpDEBUG_ENABLE(3)) { vpImagePoint iP; - iP.set_ij(p_me.ifloat, p_me.jfloat); - vpDisplay::displayCross(I, iP, 10, vpColor::orange, 1); - printf("too near : angle %lf, i %.0f , j : %0.f\n", vpMath::deg(new_ang), p_me.ifloat, p_me.jfloat); + iP.set_ij(p_me.m_ifloat, p_me.m_jfloat); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, iP, crossSize, vpColor::orange, 1); + printf("too near : angle %lf, i %.0f , j : %0.f\n", vpMath::deg(new_ang), p_me.get_ifloat(), p_me.get_jfloat()); } } } else { // point not in the interval [alpha1 ; alpha2] - meList = list.erase(meList); - angleList = angle.erase(angleList); + meList = m_meList.erase(meList); + angleList = m_angleList.erase(angleList); if (vpDEBUG_ENABLE(3)) { vpImagePoint iP; - iP.set_ij(p_me.ifloat, p_me.jfloat); - vpDisplay::displayCross(I, iP, 10, vpColor::green, 1); - printf("not in interval: angle : %lf, i %.0f , j : %0.f\n", vpMath::deg(new_ang), p_me.ifloat, p_me.jfloat); + iP.set_ij(p_me.m_ifloat, p_me.m_jfloat); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, iP, crossSize, vpColor::green, 1); + printf("not in interval: angle : %lf, i %.0f , j : %0.f\n", vpMath::deg(new_ang), p_me.get_ifloat(), p_me.get_jfloat()); } } } + + if ((m_meList.size() != numberOfGoodPoints) || (m_angleList.size() != numberOfGoodPoints)) { + // Should never occur + throw(vpException(vpException::fatalError, "Lists are not coherent at the end of vpMeEllipse::leastSquareRobust(): nb goog MEs %d and %ld, nb ang %ld", + numberOfGoodPoints, m_meList.size(), m_angleList.size())); + } + // set extremities of the angle list - m_alphamin = angle.front(); - m_alphamax = angle.back(); + m_alphamin = m_angleList.front(); + m_alphamax = m_angleList.back(); if (vpDEBUG_ENABLE(3)) { printf("alphamin : %lf, alphamax : %lf\n", vpMath::deg(m_alphamin), vpMath::deg(m_alphamax)); printf("Fin leastSquareRobust : nb pts ok = %d \n", numberOfGoodPoints); } - return(numberOfGoodPoints); + return numberOfGoodPoints; } void vpMeEllipse::display(const vpImage &I, const vpColor &col, unsigned int thickness) { - vpMeEllipse::displayEllipse(I, iPc, a, b, e, alpha1, alpha2, col, thickness); + vpMeEllipse::displayEllipse(I, m_iPc, m_a, m_b, m_e, m_alpha1, m_alpha2, col, thickness); } void vpMeEllipse::initTracking(const vpImage &I, bool trackCircle, bool trackArc) { unsigned int n = 5; // by default, 5 points for an ellipse + const unsigned int nForCircle = 3; m_trackCircle = trackCircle; - if (trackCircle) - n = 3; + if (trackCircle) { + n = nForCircle; + } std::vector iP(n); m_trackArc = trackArc; @@ -1021,10 +1106,11 @@ void vpMeEllipse::initTracking(const vpImage &I, bool trackCircle if (m_trackArc) { std::cout << "First and third points specify the extremities of the arc of circle (clockwise)" << std::endl; } - for (unsigned int k = 0; k < n; k++) { - std::cout << "Click point " << k + 1 << "/" << n << " on the circle " << std::endl; + for (unsigned int k = 0; k < n; ++k) { + std::cout << "Click point " << (k + 1) << "/" << n << " on the circle " << std::endl; vpDisplay::getClick(I, iP[k], true); - vpDisplay::displayCross(I, iP[k], 10, vpColor::red); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, iP[k], crossSize, vpColor::red); vpDisplay::flush(I); std::cout << iP[k] << std::endl; } @@ -1033,10 +1119,11 @@ void vpMeEllipse::initTracking(const vpImage &I, bool trackCircle if (m_trackArc) { std::cout << "First and fifth points specify the extremities of the arc of ellipse (clockwise)" << std::endl; } - for (unsigned int k = 0; k < n; k++) { - std::cout << "Click point " << k + 1 << "/" << n << " on the ellipse " << std::endl; + for (unsigned int k = 0; k < n; ++k) { + std::cout << "Click point " << (k + 1) << "/" << n << " on the ellipse " << std::endl; vpDisplay::getClick(I, iP[k], true); - vpDisplay::displayCross(I, iP[k], 10, vpColor::red); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, iP[k], crossSize, vpColor::red); vpDisplay::flush(I); std::cout << iP[k] << std::endl; } @@ -1045,7 +1132,7 @@ void vpMeEllipse::initTracking(const vpImage &I, bool trackCircle } void vpMeEllipse::initTracking(const vpImage &I, const std::vector &iP, - bool trackCircle, bool trackArc) + bool trackCircle, bool trackArc) { m_trackArc = trackArc; m_trackCircle = trackCircle; @@ -1053,22 +1140,22 @@ void vpMeEllipse::initTracking(const vpImage &I, const std::vecto leastSquare(I, iP); if (trackArc) { // useful for track(I): - iP1 = iP.front(); - iP2 = iP.back(); + m_iP1 = iP.front(); + m_iP2 = iP.back(); // useful for sample(I): - alpha1 = computeAngleOnEllipse(iP1); - alpha2 = computeAngleOnEllipse(iP2); - if ((alpha2 <= alpha1) || (std::fabs(alpha2 - alpha1) < m_arcEpsilon)) { - alpha2 += 2.0 * M_PI; + m_alpha1 = computeAngleOnEllipse(m_iP1); + m_alpha2 = computeAngleOnEllipse(m_iP2); + if ((m_alpha2 <= m_alpha1) || (std::fabs(m_alpha2 - m_alpha1) < m_arcEpsilon)) { + m_alpha2 += 2.0 * M_PI; } } else { - alpha1 = 0.0; - alpha2 = 2 * M_PI; + m_alpha1 = 0.0; + m_alpha2 = 2.0 * M_PI; // useful for track(I): vpImagePoint ip; - computePointOnEllipse(alpha1, ip); - iP1 = iP2 = ip; + computePointOnEllipse(m_alpha1, ip); + m_iP1 = (m_iP2 = ip); } sample(I); @@ -1078,10 +1165,10 @@ void vpMeEllipse::initTracking(const vpImage &I, const std::vecto } void vpMeEllipse::initTracking(const vpImage &I, const vpColVector ¶m, vpImagePoint *pt1, - const vpImagePoint *pt2, bool trackCircle) + const vpImagePoint *pt2, bool trackCircle) { m_trackCircle = trackCircle; - if (pt1 != nullptr && pt2 != nullptr) { + if ((pt1 != nullptr) && (pt2 != nullptr)) { m_trackArc = true; } // useful for sample(I) : uc, vc, a, b, e, Ki, alpha1, alpha2 @@ -1094,25 +1181,25 @@ void vpMeEllipse::initTracking(const vpImage &I, const vpColVecto computeKiFromNij(); if (m_trackArc) { - alpha1 = computeAngleOnEllipse(*pt1); - alpha2 = computeAngleOnEllipse(*pt2); - if ((alpha2 <= alpha1) || (std::fabs(alpha2 - alpha1) < m_arcEpsilon)) { - alpha2 += 2.0 * M_PI; + m_alpha1 = computeAngleOnEllipse(*pt1); + m_alpha2 = computeAngleOnEllipse(*pt2); + if ((m_alpha2 <= m_alpha1) || (std::fabs(m_alpha2 - m_alpha1) < m_arcEpsilon)) { + m_alpha2 += 2.0 * M_PI; } // useful for track(I) - iP1 = *pt1; - iP2 = *pt2; + m_iP1 = *pt1; + m_iP2 = *pt2; } else { - alpha1 = 0.0; - alpha2 = 2.0 * M_PI; + m_alpha1 = 0.0; + m_alpha2 = 2.0 * M_PI; // useful for track(I) vpImagePoint ip; - computePointOnEllipse(alpha1, ip); - iP1 = iP2 = ip; + computePointOnEllipse(m_alpha1, ip); + m_iP1 = (m_iP2 = ip); } // useful for display(I) so useless if no display before track(I) - iPc.set_uv(m_uc, m_vc); + m_iPc.set_uv(m_uc, m_vc); sample(I); track(I); @@ -1131,10 +1218,10 @@ void vpMeEllipse::track(const vpImage &I) // recompute alpha1 and alpha2 in case they have been changed by setEndPoints() if (m_trackArc) { - alpha1 = computeAngleOnEllipse(iP1); - alpha2 = computeAngleOnEllipse(iP2); - if ((alpha2 <= alpha1) || (std::fabs(alpha2 - alpha1) < m_arcEpsilon)) { - alpha2 += 2.0 * M_PI; + m_alpha1 = computeAngleOnEllipse(m_iP1); + m_alpha2 = computeAngleOnEllipse(m_iP2); + if ((m_alpha2 <= m_alpha1) || (std::fabs(m_alpha2 - m_alpha1) < m_arcEpsilon)) { + m_alpha2 += 2.0 * M_PI; } } // Compute the ellipse parameters from the tracked points, manage the lists, @@ -1154,7 +1241,8 @@ void vpMeEllipse::track(const vpImage &I) } } - if (m_numberOfGoodPoints <= 5) { + const unsigned int minNbGoodPoints = 5; + if (m_numberOfGoodPoints <= minNbGoodPoints) { if (vpDEBUG_ENABLE(3)) { printf("Before RESAMPLE !!! nb points %d \n", m_numberOfGoodPoints); printf("A click to continue \n"); @@ -1172,7 +1260,7 @@ void vpMeEllipse::track(const vpImage &I) } // Stop in case of failure after resample - if (m_numberOfGoodPoints <= 5) { + if (m_numberOfGoodPoints <= minNbGoodPoints) { throw(vpException(vpTrackingException::notEnoughPointError, "Impossible to track the ellipse, not enough features")); } } @@ -1184,11 +1272,11 @@ void vpMeEllipse::track(const vpImage &I) // remet a jour l'angle delta pour chaque vpMeSite de la liste updateTheta(); // not in getParameters since computed only once for each image - m00 = M_PI * a * b; + m_m00 = M_PI * m_a * m_b; // Useful only for tracking an arc of ellipse, but done to give them a value - computePointOnEllipse(alpha1, iP1); - computePointOnEllipse(alpha2, iP2); + computePointOnEllipse(m_alpha1, m_iP1); + computePointOnEllipse(m_alpha2, m_iP2); if (vpDEBUG_ENABLE(3)) { display(I, vpColor::red); @@ -1224,8 +1312,8 @@ void vpMeEllipse::track(const vpImage &I) \param thickness : Thickness of the drawings. */ void vpMeEllipse::display(const vpImage &I, const vpImagePoint ¢er, const double &A, - const double &B, const double &E, const double &smallalpha, const double &highalpha, - const vpColor &color, unsigned int thickness) + const double &B, const double &E, const double &smallalpha, const double &highalpha, + const vpColor &color, unsigned int thickness) { vpMeEllipse::displayEllipse(I, center, A, B, E, smallalpha, highalpha, color, thickness); } @@ -1258,8 +1346,8 @@ void vpMeEllipse::display(const vpImage &I, const vpImagePoint &c \sa vpDisplay::displayEllipse() */ void vpMeEllipse::display(const vpImage &I, const vpImagePoint ¢er, const double &A, const double &B, - const double &E, const double &smallalpha, const double &highalpha, - const vpColor &color, unsigned int thickness) + const double &E, const double &smallalpha, const double &highalpha, + const vpColor &color, unsigned int thickness) { vpMeEllipse::displayEllipse(I, center, A, B, E, smallalpha, highalpha, color, thickness); } diff --git a/modules/tracker/me/src/moving-edges/vpMeLine.cpp b/modules/tracker/me/src/moving-edges/vpMeLine.cpp index 737597f8ae..41501bd559 100644 --- a/modules/tracker/me/src/moving-edges/vpMeLine.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeLine.cpp @@ -87,88 +87,97 @@ static void project(double a, double b, double c, double i, double j, double &ip } vpMeLine::vpMeLine() - : rho(0.), theta(0.), delta(0.), delta_1(0.), angle(0.), angle_1(90), sign(1), _useIntensityForRho(true), a(0.), - b(0.), c(0.) + : m_rho(0.), m_theta(0.), m_delta(0.), m_delta_1(0.), m_angle(0.), m_angle_1(90), m_sign(1), + m_useIntensityForRho(true), m_a(0.), m_b(0.), m_c(0.) { } vpMeLine::vpMeLine(const vpMeLine &meline) - : vpMeTracker(meline), rho(0.), theta(0.), delta(0.), delta_1(0.), angle(0.), angle_1(90), sign(1), - _useIntensityForRho(true), a(0.), b(0.), c(0.) + : vpMeTracker(meline), m_rho(0.), m_theta(0.), m_delta(0.), m_delta_1(0.), m_angle(0.), m_angle_1(90), m_sign(1), + m_useIntensityForRho(true), m_a(0.), m_b(0.), m_c(0.) { - rho = meline.rho; - theta = meline.theta; - delta = meline.delta; - delta_1 = meline.delta_1; - angle = meline.angle; - angle_1 = meline.angle_1; - sign = meline.sign; - - a = meline.a; - b = meline.b; - c = meline.c; - _useIntensityForRho = meline._useIntensityForRho; - PExt[0] = meline.PExt[0]; - PExt[1] = meline.PExt[1]; + m_rho = meline.m_rho; + m_theta = meline.m_theta; + m_delta = meline.m_delta; + m_delta_1 = meline.m_delta_1; + m_angle = meline.m_angle; + m_angle_1 = meline.m_angle_1; + m_sign = meline.m_sign; + + m_a = meline.m_a; + m_b = meline.m_b; + m_c = meline.m_c; + m_useIntensityForRho = meline.m_useIntensityForRho; + m_PExt[0] = meline.m_PExt[0]; + m_PExt[1] = meline.m_PExt[1]; } -vpMeLine::~vpMeLine() { list.clear(); } +vpMeLine::~vpMeLine() +{ + m_meList.clear(); +} void vpMeLine::sample(const vpImage &I, bool doNotTrack) { (void)doNotTrack; - if (!me) { + if (!m_me) { vpDERROR_TRACE(2, "Tracking error: Moving edges not initialized"); throw(vpTrackingException(vpTrackingException::initializationError, "Moving edges not initialized")); } - int rows = (int)I.getHeight(); - int cols = (int)I.getWidth(); + int nbrows = static_cast(I.getHeight()); + int nbcols = static_cast(I.getWidth()); double n_sample; - if (std::fabs(me->getSampleStep()) <= std::numeric_limits::epsilon()) { + if (std::fabs(m_me->getSampleStep()) <= std::numeric_limits::epsilon()) { vpERROR_TRACE("function called with sample step = 0"); throw(vpTrackingException(vpTrackingException::fatalError, "sample step = 0")); } // i, j portions of the line_p - double diffsi = PExt[0].ifloat - PExt[1].ifloat; - double diffsj = PExt[0].jfloat - PExt[1].jfloat; + double diffsi = m_PExt[0].m_ifloat - m_PExt[1].m_ifloat; + double diffsj = m_PExt[0].m_jfloat - m_PExt[1].m_jfloat; double length_p = sqrt((vpMath::sqr(diffsi) + vpMath::sqr(diffsj))); if (std::fabs(length_p) <= std::numeric_limits::epsilon()) throw(vpTrackingException(vpTrackingException::fatalError, "points too close of each other to define a line")); // number of samples along line_p - n_sample = length_p / (double)me->getSampleStep(); + n_sample = length_p / (double)m_me->getSampleStep(); double stepi = diffsi / (double)n_sample; double stepj = diffsj / (double)n_sample; // Choose starting point - double is = PExt[1].ifloat; - double js = PExt[1].jfloat; + double is = m_PExt[1].m_ifloat; + double js = m_PExt[1].m_jfloat; // Delete old list - list.clear(); + m_meList.clear(); - // sample positions at i*me->getSampleStep() interval along the + // sample positions at i*m_me->getSampleStep() interval along the // line_p, starting at PSiteExt[0] - vpImagePoint ip; for (int i = 0; i <= vpMath::round(n_sample); i++) { + vpImagePoint iP; + iP.set_i(is); + iP.set_j(js); // If point is in the image, add to the sample list - if (!outOfImage(vpMath::round(is), vpMath::round(js), 0, rows, cols)) { - vpMeSite pix; //= list.value(); - pix.init((int)is, (int)js, delta, 0, sign); - pix.setDisplay(selectDisplay); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) + && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + vpMeSite pix; + pix.init(iP.get_i(), iP.get_j(), m_delta, 0, m_sign); + pix.setDisplay(m_selectDisplay); + pix.setState(vpMeSite::NO_SUPPRESSION); + const double marginRatio = m_me->getThresholdMarginRatio(); + double convolution = pix.convolution(I, m_me); + double contrastThreshold = fabs(convolution) * marginRatio; + pix.setContrastThreshold(contrastThreshold, *m_me); if (vpDEBUG_ENABLE(3)) { - ip.set_i(is); - ip.set_j(js); - vpDisplay::displayCross(I, ip, 2, vpColor::blue); + vpDisplay::displayCross(I, iP, 2, vpColor::blue); } - list.push_back(pix); + m_meList.push_back(pix); } is += stepi; js += stepj; @@ -180,7 +189,7 @@ void vpMeLine::sample(const vpImage &I, bool doNotTrack) void vpMeLine::display(const vpImage &I, const vpColor &color, unsigned int thickness) { - vpMeLine::displayLine(I, PExt[0], PExt[1], list, a, b, c, color, thickness); + vpMeLine::displayLine(I, m_PExt[0], m_PExt[1], m_meList, m_a, m_b, m_c, color, thickness); } void vpMeLine::initTracking(const vpImage &I) @@ -228,24 +237,24 @@ void vpMeLine::leastSquare() unsigned int nos_1 = 0; double distance = 100; - if (list.size() <= 2 || numberOfSignal() <= 2) { + if (m_meList.size() <= 2 || numberOfSignal() <= 2) { // vpERROR_TRACE("Not enough point") ; vpCDEBUG(1) << "Not enough point"; throw(vpTrackingException(vpTrackingException::notEnoughPointError, "not enough point")); } - if ((fabs(b) >= 0.9)) // Construction du systeme Ax=B + if ((fabs(m_b) >= 0.9)) // Construction du systeme Ax=B // a i + j + c = 0 // A = (i 1) B = (-j) { nos_1 = numberOfSignal(); unsigned int k = 0; - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::const_iterator it = m_meList.begin(); it != m_meList.end(); ++it) { p_me = *it; if (p_me.getState() == vpMeSite::NO_SUPPRESSION) { - A[k][0] = p_me.ifloat; + A[k][0] = p_me.m_ifloat; A[k][1] = 1; - B[k] = -p_me.jfloat; + B[k] = -p_me.m_jfloat; k++; } } @@ -274,7 +283,7 @@ void vpMeLine::leastSquare() } k = 0; - for (std::list::iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::iterator it = m_meList.begin(); it != m_meList.end(); ++it) { p_me = *it; if (p_me.getState() == vpMeSite::NO_SUPPRESSION) { if (w[k] < 0.2) { @@ -287,14 +296,14 @@ void vpMeLine::leastSquare() } // mise a jour de l'equation de la droite - a = x[0]; - b = 1; - c = x[1]; - - double s = sqrt(vpMath::sqr(a) + vpMath::sqr(b)); - a /= s; - b /= s; - c /= s; + m_a = x[0]; + m_b = 1; + m_c = x[1]; + + double s = sqrt(vpMath::sqr(m_a) + vpMath::sqr(m_b)); + m_a /= s; + m_b /= s; + m_c /= s; } else // Construction du systeme Ax=B @@ -303,12 +312,12 @@ void vpMeLine::leastSquare() { nos_1 = numberOfSignal(); unsigned int k = 0; - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::const_iterator it = m_meList.begin(); it != m_meList.end(); ++it) { p_me = *it; if (p_me.getState() == vpMeSite::NO_SUPPRESSION) { - A[k][0] = p_me.jfloat; + A[k][0] = p_me.m_jfloat; A[k][1] = 1; - B[k] = -p_me.ifloat; + B[k] = -p_me.m_ifloat; k++; } } @@ -332,7 +341,7 @@ void vpMeLine::leastSquare() } k = 0; - for (std::list::iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::iterator it = m_meList.begin(); it != m_meList.end(); ++it) { p_me = *it; if (p_me.getState() == vpMeSite::NO_SUPPRESSION) { if (w[k] < 0.2) { @@ -343,20 +352,20 @@ void vpMeLine::leastSquare() k++; } } - a = 1; - b = x[0]; - c = x[1]; - - double s = sqrt(vpMath::sqr(a) + vpMath::sqr(b)); - a /= s; - b /= s; - c /= s; + m_a = 1; + m_b = x[0]; + m_c = x[1]; + + double s = sqrt(vpMath::sqr(m_a) + vpMath::sqr(m_b)); + m_a /= s; + m_b /= s; + m_c /= s; } // mise a jour du delta - delta = atan2(a, b); + m_delta = atan2(m_a, m_b); - normalizeAngle(delta); + normalizeAngle(m_delta); } void vpMeLine::initTracking(const vpImage &I, const vpImagePoint &ip1, const vpImagePoint &ip2) @@ -375,20 +384,20 @@ void vpMeLine::initTracking(const vpImage &I, const vpImagePoint // 1. On fait ce qui concerne les droites (peut etre vide) { // Points extremites - PExt[0].ifloat = (float)ip1.get_i(); - PExt[0].jfloat = (float)ip1.get_j(); - PExt[1].ifloat = (float)ip2.get_i(); - PExt[1].jfloat = (float)ip2.get_j(); + m_PExt[0].m_ifloat = (float)ip1.get_i(); + m_PExt[0].m_jfloat = (float)ip1.get_j(); + m_PExt[1].m_ifloat = (float)ip2.get_i(); + m_PExt[1].m_jfloat = (float)ip2.get_j(); double angle_ = atan2((double)(i1s - i2s), (double)(j1s - j2s)); - a = cos(angle_); - b = sin(angle_); + m_a = cos(angle_); + m_b = sin(angle_); // Real values of a, b can have an other sign. So to get the good values // of a and b in order to initialise then c, we call track(I) just below - computeDelta(delta, i1s, j1s, i2s, j2s); - delta_1 = delta; + computeDelta(m_delta, i1s, j1s, i2s, j2s); + m_delta_1 = m_delta; // vpTRACE("a: %f b: %f c: %f -b/a: %f delta: %f", a, b, c, -(b/a), // delta); @@ -413,11 +422,11 @@ void vpMeLine::initTracking(const vpImage &I, const vpImagePoint void vpMeLine::suppressPoints() { // Loop through list of sites to track - for (std::list::iterator it = list.begin(); it != list.end();) { + for (std::list::iterator it = m_meList.begin(); it != m_meList.end();) { vpMeSite s = *it; // current reference pixel if (s.getState() != vpMeSite::NO_SUPPRESSION) - it = list.erase(it); + it = m_meList.erase(it); else ++it; } @@ -431,41 +440,41 @@ void vpMeLine::setExtremities() double jmax = -1; // Loop through list of sites to track - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::const_iterator it = m_meList.begin(); it != m_meList.end(); ++it) { vpMeSite s = *it; // current reference pixel - if (s.ifloat < imin) { - imin = s.ifloat; - jmin = s.jfloat; + if (s.m_ifloat < imin) { + imin = s.m_ifloat; + jmin = s.m_jfloat; } - if (s.ifloat > imax) { - imax = s.ifloat; - jmax = s.jfloat; + if (s.m_ifloat > imax) { + imax = s.m_ifloat; + jmax = s.m_jfloat; } } - PExt[0].ifloat = imin; - PExt[0].jfloat = jmin; - PExt[1].ifloat = imax; - PExt[1].jfloat = jmax; + m_PExt[0].m_ifloat = imin; + m_PExt[0].m_jfloat = jmin; + m_PExt[1].m_ifloat = imax; + m_PExt[1].m_jfloat = jmax; if (fabs(imin - imax) < 25) { - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::const_iterator it = m_meList.begin(); it != m_meList.end(); ++it) { vpMeSite s = *it; // current reference pixel - if (s.jfloat < jmin) { - imin = s.ifloat; - jmin = s.jfloat; + if (s.m_jfloat < jmin) { + imin = s.m_ifloat; + jmin = s.m_jfloat; } - if (s.jfloat > jmax) { - imax = s.ifloat; - jmax = s.jfloat; + if (s.m_jfloat > jmax) { + imax = s.m_ifloat; + jmax = s.m_jfloat; } } - PExt[0].ifloat = imin; - PExt[0].jfloat = jmin; - PExt[1].ifloat = imax; - PExt[1].jfloat = jmax; + m_PExt[0].m_ifloat = imin; + m_PExt[0].m_jfloat = jmin; + m_PExt[1].m_ifloat = imax; + m_PExt[1].m_jfloat = jmax; } } @@ -473,25 +482,25 @@ void vpMeLine::seekExtremities(const vpImage &I) { vpCDEBUG(1) << "begin vpMeLine::sample() : " << std::endl; - if (!me) { + if (!m_me) { vpDERROR_TRACE(2, "Tracking error: Moving edges not initialized"); throw(vpTrackingException(vpTrackingException::initializationError, "Moving edges not initialized")); } - int rows = (int)I.getHeight(); - int cols = (int)I.getWidth(); + int nbrows = static_cast(I.getHeight()); + int nbcols = static_cast(I.getWidth()); double n_sample; - // if (me->getSampleStep()==0) - if (std::fabs(me->getSampleStep()) <= std::numeric_limits::epsilon()) { + // if (m_me->getSampleStep()==0) + if (std::fabs(m_me->getSampleStep()) <= std::numeric_limits::epsilon()) { vpERROR_TRACE("function called with sample step = 0"); throw(vpTrackingException(vpTrackingException::fatalError, "sample step = 0")); } // i, j portions of the line_p - double diffsi = PExt[0].ifloat - PExt[1].ifloat; - double diffsj = PExt[0].jfloat - PExt[1].jfloat; + double diffsi = m_PExt[0].m_ifloat - m_PExt[1].m_ifloat; + double diffsj = m_PExt[0].m_jfloat - m_PExt[1].m_jfloat; double s = vpMath::sqr(diffsi) + vpMath::sqr(diffsj); @@ -501,76 +510,76 @@ void vpMeLine::seekExtremities(const vpImage &I) double length_p = sqrt((vpMath::sqr(diffsi) + vpMath::sqr(diffsj))); // number of samples along line_p - n_sample = length_p / (double)me->getSampleStep(); - double sample_step = (double)me->getSampleStep(); + n_sample = length_p / (double)m_me->getSampleStep(); + double sample_step = (double)m_me->getSampleStep(); vpMeSite P; - P.init((int)PExt[0].ifloat, (int)PExt[0].jfloat, delta_1, 0, sign); - P.setDisplay(selectDisplay); + P.init((int)m_PExt[0].m_ifloat, (int)m_PExt[0].m_jfloat, m_delta_1, 0, m_sign); + P.setDisplay(m_selectDisplay); - unsigned int memory_range = me->getRange(); - me->setRange(1); + unsigned int memory_range = m_me->getRange(); + m_me->setRange(1); - vpImagePoint ip; for (int i = 0; i < 3; i++) { - P.ifloat = P.ifloat + di * sample_step; - P.i = (int)P.ifloat; - P.jfloat = P.jfloat + dj * sample_step; - P.j = (int)P.jfloat; + P.m_ifloat = P.m_ifloat + di * sample_step; + P.m_i = (int)P.m_ifloat; + P.m_jfloat = P.m_jfloat + dj * sample_step; + P.m_j = (int)P.m_jfloat; + + vpImagePoint iP; + iP.set_i(P.m_ifloat); + iP.set_j(P.m_jfloat); - if (!outOfImage(P.i, P.j, 5, rows, cols)) { - P.track(I, me, false); + if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) + && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { - list.push_back(P); + m_meList.push_back(P); if (vpDEBUG_ENABLE(3)) { - ip.set_i(P.i); - ip.set_j(P.j); - - vpDisplay::displayCross(I, ip, 5, vpColor::green); + vpDisplay::displayCross(I, iP, 5, vpColor::green); } } else { if (vpDEBUG_ENABLE(3)) { - ip.set_i(P.i); - ip.set_j(P.j); - vpDisplay::displayCross(I, ip, 10, vpColor::blue); + vpDisplay::displayCross(I, iP, 10, vpColor::blue); } } } } - P.init((int)PExt[1].ifloat, (int)PExt[1].jfloat, delta_1, 0, sign); - P.setDisplay(selectDisplay); + P.init((int)m_PExt[1].m_ifloat, (int)m_PExt[1].m_jfloat, m_delta_1, 0, m_sign); + P.setDisplay(m_selectDisplay); for (int i = 0; i < 3; i++) { - P.ifloat = P.ifloat - di * sample_step; - P.i = (int)P.ifloat; - P.jfloat = P.jfloat - dj * sample_step; - P.j = (int)P.jfloat; + P.m_ifloat = P.m_ifloat - di * sample_step; + P.m_i = (int)P.m_ifloat; + P.m_jfloat = P.m_jfloat - dj * sample_step; + P.m_j = (int)P.m_jfloat; - if (!outOfImage(P.i, P.j, 5, rows, cols)) { - P.track(I, me, false); + vpImagePoint iP; + iP.set_i(P.m_ifloat); + iP.set_j(P.m_jfloat); + + if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) + && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { - list.push_back(P); + m_meList.push_back(P); if (vpDEBUG_ENABLE(3)) { - ip.set_i(P.i); - ip.set_j(P.j); - vpDisplay::displayCross(I, ip, 5, vpColor::green); + vpDisplay::displayCross(I, iP, 5, vpColor::green); } } else { if (vpDEBUG_ENABLE(3)) { - ip.set_i(P.i); - ip.set_j(P.j); - vpDisplay::displayCross(I, ip, 10, vpColor::blue); + vpDisplay::displayCross(I, iP, 10, vpColor::blue); } } } } - me->setRange(memory_range); + m_me->setRange(memory_range); vpCDEBUG(1) << "end vpMeLine::sample() : "; vpCDEBUG(1) << n_sample << " point inserted in the list " << std::endl; @@ -580,34 +589,32 @@ void vpMeLine::reSample(const vpImage &I) { double i1, j1, i2, j2; - if (!me) { + if (!m_me) { vpDERROR_TRACE(2, "Tracking error: Moving edges not initialized"); throw(vpTrackingException(vpTrackingException::initializationError, "Moving edges not initialized")); } - project(a, b, c, PExt[0].ifloat, PExt[0].jfloat, i1, j1); - project(a, b, c, PExt[1].ifloat, PExt[1].jfloat, i2, j2); + project(m_a, m_b, m_c, m_PExt[0].m_ifloat, m_PExt[0].m_jfloat, i1, j1); + project(m_a, m_b, m_c, m_PExt[1].m_ifloat, m_PExt[1].m_jfloat, i2, j2); // Points extremites - PExt[0].ifloat = i1; - PExt[0].jfloat = j1; - PExt[1].ifloat = i2; - PExt[1].jfloat = j2; + m_PExt[0].m_ifloat = i1; + m_PExt[0].m_jfloat = j1; + m_PExt[1].m_ifloat = i2; + m_PExt[1].m_jfloat = j2; double d = sqrt(vpMath::sqr(i1 - i2) + vpMath::sqr(j1 - j2)); unsigned int n = numberOfSignal(); - double expecteddensity = d / (double)me->getSampleStep(); + double expecteddensity = d / (double)m_me->getSampleStep(); if ((double)n < 0.9 * expecteddensity) { - double delta_new = delta; - delta = delta_1; + double delta_new = m_delta; + m_delta = m_delta_1; sample(I); - delta = delta_new; + m_delta = delta_new; // 2. On appelle ce qui n'est pas specifique - { - vpMeTracker::initTracking(I); - } + vpMeTracker::initTracking(I); } } @@ -615,7 +622,7 @@ void vpMeLine::updateDelta() { vpMeSite p_me; - double angle_ = delta + M_PI / 2; + double angle_ = m_delta + M_PI / 2; double diff = 0; while (angle_ < 0) @@ -631,30 +638,26 @@ void vpMeLine::updateDelta() } // std::cout << "angle theta : " << theta << std::endl ; - diff = fabs(angle_ - angle_1); + diff = fabs(angle_ - m_angle_1); if (diff > 90) - sign *= -1; + m_sign *= -1; - angle_1 = angle_; + m_angle_1 = angle_; - for (std::list::iterator it = list.begin(); it != list.end(); ++it) { + for (std::list::iterator it = m_meList.begin(); it != m_meList.end(); ++it) { p_me = *it; - p_me.alpha = delta; - p_me.mask_sign = sign; + p_me.setAlpha(m_delta); + p_me.m_mask_sign = m_sign; *it = p_me; } - delta_1 = delta; + m_delta_1 = m_delta; } void vpMeLine::track(const vpImage &I) { vpCDEBUG(1) << "begin vpMeLine::track()" << std::endl; - // 1. On fait ce qui concerne les droites (peut etre vide) - {} // 2. On appelle ce qui n'est pas specifique - { - vpMeTracker::track(I); - } + vpMeTracker::track(I); // 3. On revient aux droites { @@ -719,21 +722,19 @@ void vpMeLine::update_indices(double theta, int i, int j, int incr, int &i1, int void vpMeLine::computeRhoTheta(const vpImage &I) { - // rho = -c ; - // theta = atan2(a,b) ; - rho = fabs(c); - theta = atan2(b, a); + m_rho = fabs(m_c); + m_theta = atan2(m_b, m_a); - while (theta >= M_PI) - theta -= M_PI; - while (theta < 0) - theta += M_PI; + while (m_theta >= M_PI) + m_theta -= M_PI; + while (m_theta < 0) + m_theta += M_PI; - if (_useIntensityForRho) { + if (m_useIntensityForRho) { // convention pour choisir le signe de rho int i, j; - i = vpMath::round((PExt[0].ifloat + PExt[1].ifloat) / 2); - j = vpMath::round((PExt[0].jfloat + PExt[1].jfloat) / 2); + i = vpMath::round((m_PExt[0].m_ifloat + m_PExt[1].m_ifloat) / 2); + j = vpMath::round((m_PExt[0].m_jfloat + m_PExt[1].m_jfloat) / 2); int end = false; int incr = 10; @@ -743,14 +744,14 @@ void vpMeLine::computeRhoTheta(const vpImage &I) int width_ = (int)I.getWidth(); int height_ = (int)I.getHeight(); - update_indices(theta, i, j, incr, i1, i2, j1, j2); + update_indices(m_theta, i, j, incr, i1, i2, j1, j2); if (i1 < 0 || i1 >= height_ || i2 < 0 || i2 >= height_ || j1 < 0 || j1 >= width_ || j2 < 0 || j2 >= width_) { - double rho_lim1 = fabs((double)i / cos(theta)); - double rho_lim2 = fabs((double)j / sin(theta)); + double rho_lim1 = fabs((double)i / cos(m_theta)); + double rho_lim2 = fabs((double)j / sin(m_theta)); - double co_rho_lim1 = fabs(((double)(height_ - i)) / cos(theta)); - double co_rho_lim2 = fabs(((double)(width_ - j)) / sin(theta)); + double co_rho_lim1 = fabs(((double)(height_ - i)) / cos(m_theta)); + double co_rho_lim2 = fabs(((double)(width_ - j)) / sin(m_theta)); double rho_lim = std::min(rho_lim1, rho_lim2); double co_rho_lim = std::min(co_rho_lim1, co_rho_lim2); @@ -759,7 +760,7 @@ void vpMeLine::computeRhoTheta(const vpImage &I) vpERROR_TRACE("increment is too small"); throw(vpTrackingException(vpTrackingException::fatalError, "increment is too small")); } - update_indices(theta, i, j, incr, i1, i2, j1, j2); + update_indices(m_theta, i, j, incr, i1, i2, j1, j2); } while (!end) { @@ -779,29 +780,29 @@ void vpMeLine::computeRhoTheta(const vpImage &I) "sides of the line")); } } - update_indices(theta, i, j, incr, i1, i2, j1, j2); + update_indices(m_theta, i, j, incr, i1, i2, j1, j2); } - if (theta >= 0 && theta <= M_PI / 2) { + if (m_theta >= 0 && m_theta <= M_PI / 2) { if (v2 < v1) { - theta += M_PI; - rho *= -1; + m_theta += M_PI; + m_rho *= -1; } } else { double jinter; - jinter = -c / b; + jinter = -m_c / m_b; if (v2 < v1) { - theta += M_PI; + m_theta += M_PI; if (jinter > 0) { - rho *= -1; + m_rho *= -1; } } else { if (jinter < 0) { - rho *= -1; + m_rho *= -1; } } } @@ -822,27 +823,27 @@ void vpMeLine::computeRhoTheta(const vpImage &I) } } -double vpMeLine::getRho() const { return rho; } +double vpMeLine::getRho() const { return m_rho; } -double vpMeLine::getTheta() const { return theta; } +double vpMeLine::getTheta() const { return m_theta; } void vpMeLine::getExtremities(vpImagePoint &ip1, vpImagePoint &ip2) { /*Return the coordinates of the extremities of the line*/ - ip1.set_i(PExt[0].ifloat); - ip1.set_j(PExt[0].jfloat); - ip2.set_i(PExt[1].ifloat); - ip2.set_j(PExt[1].jfloat); + ip1.set_i(m_PExt[0].m_ifloat); + ip1.set_j(m_PExt[0].m_jfloat); + ip2.set_i(m_PExt[1].m_ifloat); + ip2.set_j(m_PExt[1].m_jfloat); } bool vpMeLine::intersection(const vpMeLine &line1, const vpMeLine &line2, vpImagePoint &ip) { - double a1 = line1.a; - double b1 = line1.b; - double c1 = line1.c; - double a2 = line2.a; - double b2 = line2.b; - double c2 = line2.c; + double a1 = line1.m_a; + double b1 = line1.m_b; + double c1 = line1.m_c; + double a2 = line2.m_a; + double b2 = line2.m_b; + double c2 = line2.m_c; try { double i = 0, j = 0; @@ -1038,12 +1039,12 @@ void vpMeLine::displayLine(const vpImage &I, const vpMeSite &PExt vpDisplay::displayLine(I, ip1, ip2, color); } - ip1.set_i(PExt1.ifloat); - ip1.set_j(PExt1.jfloat); + ip1.set_i(PExt1.m_ifloat); + ip1.set_j(PExt1.m_jfloat); vpDisplay::displayCross(I, ip1, 10, vpColor::green, thickness); - ip1.set_i(PExt2.ifloat); - ip1.set_j(PExt2.jfloat); + ip1.set_i(PExt2.m_ifloat); + ip1.set_j(PExt2.m_jfloat); vpDisplay::displayCross(I, ip1, 10, vpColor::green, thickness); } @@ -1079,12 +1080,12 @@ void vpMeLine::displayLine(const vpImage &I, const vpMeSite &PExt1, cons vpDisplay::displayLine(I, ip1, ip2, color); } - ip1.set_i(PExt1.ifloat); - ip1.set_j(PExt1.jfloat); + ip1.set_i(PExt1.m_ifloat); + ip1.set_j(PExt1.m_jfloat); vpDisplay::displayCross(I, ip1, 10, vpColor::green, thickness); - ip1.set_i(PExt2.ifloat); - ip1.set_j(PExt2.jfloat); + ip1.set_i(PExt2.m_ifloat); + ip1.set_j(PExt2.m_jfloat); vpDisplay::displayCross(I, ip1, 10, vpColor::green, thickness); } @@ -1096,8 +1097,8 @@ void vpMeLine::displayLine(const vpImage &I, const vpMeSite &PExt for (std::list::const_iterator it = site_list.begin(); it != site_list.end(); ++it) { vpMeSite pix = *it; - ip.set_i(pix.ifloat); - ip.set_j(pix.jfloat); + ip.set_i(pix.m_ifloat); + ip.set_j(pix.m_jfloat); if (pix.getState() == vpMeSite::M_ESTIMATOR) vpDisplay::displayCross(I, ip, 5, vpColor::green, thickness); @@ -1134,12 +1135,12 @@ void vpMeLine::displayLine(const vpImage &I, const vpMeSite &PExt vpDisplay::displayLine(I, ip1, ip2, color); } - ip1.set_i(PExt1.ifloat); - ip1.set_j(PExt1.jfloat); + ip1.set_i(PExt1.m_ifloat); + ip1.set_j(PExt1.m_jfloat); vpDisplay::displayCross(I, ip1, 10, vpColor::green, thickness); - ip1.set_i(PExt2.ifloat); - ip1.set_j(PExt2.jfloat); + ip1.set_i(PExt2.m_ifloat); + ip1.set_j(PExt2.m_jfloat); vpDisplay::displayCross(I, ip1, 10, vpColor::green, thickness); } @@ -1151,8 +1152,8 @@ void vpMeLine::displayLine(const vpImage &I, const vpMeSite &PExt1, cons for (std::list::const_iterator it = site_list.begin(); it != site_list.end(); ++it) { vpMeSite pix = *it; - ip.set_i(pix.ifloat); - ip.set_j(pix.jfloat); + ip.set_i(pix.m_ifloat); + ip.set_j(pix.m_jfloat); if (pix.getState() == vpMeSite::M_ESTIMATOR) vpDisplay::displayCross(I, ip, 5, vpColor::green, thickness); @@ -1189,11 +1190,11 @@ void vpMeLine::displayLine(const vpImage &I, const vpMeSite &PExt1, cons vpDisplay::displayLine(I, ip1, ip2, color); } - ip1.set_i(PExt1.ifloat); - ip1.set_j(PExt1.jfloat); + ip1.set_i(PExt1.m_ifloat); + ip1.set_j(PExt1.m_jfloat); vpDisplay::displayCross(I, ip1, 10, vpColor::green, thickness); - ip1.set_i(PExt2.ifloat); - ip1.set_j(PExt2.jfloat); + ip1.set_i(PExt2.m_ifloat); + ip1.set_j(PExt2.m_jfloat); vpDisplay::displayCross(I, ip1, 10, vpColor::green, thickness); } diff --git a/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp b/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp index 4d932953d7..5b1f17bf5f 100644 --- a/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp @@ -235,10 +235,10 @@ void vpMeNurbs::sample(const vpImage &I, bool doNotTrack) (void)doNotTrack; int rows = (int)I.getHeight(); int cols = (int)I.getWidth(); - double step = 1.0 / (double)me->getPointsToTrack(); + double step = 1.0 / (double)m_me->getPointsToTrack(); // Delete old list - list.clear(); + m_meList.clear(); double u = 0.0; vpImagePoint *pt = nullptr; @@ -251,12 +251,12 @@ void vpMeNurbs::sample(const vpImage &I, bool doNotTrack) // If point is in the image, add to the sample list if (!outOfImage(pt[0], 0, rows, cols) && - vpImagePoint::sqrDistance(pt[0], pt_1) >= vpMath::sqr(me->getSampleStep())) { - vpMeSite pix; //= list.value(); + vpImagePoint::sqrDistance(pt[0], pt_1) >= vpMath::sqr(m_me->getSampleStep())) { + vpMeSite pix; pix.init(pt[0].get_i(), pt[0].get_j(), delta); - pix.setDisplay(selectDisplay); + pix.setDisplay(m_selectDisplay); - list.push_back(pix); + m_meList.push_back(pix); pt_1 = pt[0]; } u = u + step; @@ -267,11 +267,11 @@ void vpMeNurbs::sample(const vpImage &I, bool doNotTrack) void vpMeNurbs::suppressPoints() { - for (std::list::iterator it = list.begin(); it != list.end();) { + for (std::list::iterator it = m_meList.begin(); it != m_meList.end();) { vpMeSite s = *it; // current reference pixel if (s.getState() != vpMeSite::NO_SUPPRESSION) { - it = list.erase(it); + it = m_meList.erase(it); } else ++it; @@ -283,14 +283,14 @@ void vpMeNurbs::updateDelta() double u = 0.0; double d = 1e6; double d_1 = 1e6; - std::list::iterator it = list.begin(); + std::list::iterator it = m_meList.begin(); vpImagePoint Cu; vpImagePoint *der = nullptr; double step = 0.01; - while (u < 1 && it != list.end()) { + while (u < 1 && it != m_meList.end()) { vpMeSite s = *it; - vpImagePoint pt(s.i, s.j); + vpImagePoint pt(s.get_i(), s.get_j()); while (d <= d_1 && u < 1) { Cu = nurbs.computeCurvePoint(u); d_1 = d; @@ -305,7 +305,7 @@ void vpMeNurbs::updateDelta() // vpImagePoint toto(der[0].get_i(),der[0].get_j()); // vpDisplay::displayCross(I,toto,4,vpColor::red); - s.alpha = computeDelta(der[1].get_i(), der[1].get_j()); + s.setAlpha(computeDelta(der[1].get_i(), der[1].get_j())); *it = s; ++it; d = 1e6; @@ -328,19 +328,19 @@ void vpMeNurbs::seekExtremities(const vpImage &I) // Check if the two extremities are not to close to eachother. double d = vpImagePoint::distance(begin[0], end[0]); - double threshold = 3 * me->getSampleStep(); - double sample_step = me->getSampleStep(); + double threshold = 3 * m_me->getSampleStep(); + double sample_step = m_me->getSampleStep(); vpImagePoint pt; - if (d > threshold /*|| (list.firstValue()).mask_sign != (list.lastValue()).mask_sign*/) { + if (d > threshold /*|| (m_meList.firstValue()).m_mask_sign != (m_meList.lastValue()).m_mask_sign*/) { vpMeSite P; // Init vpMeSite - P.init(begin[0].get_i(), begin[0].get_j(), (list.front()).alpha, 0, (list.front()).mask_sign); - P.setDisplay(selectDisplay); + P.init(begin[0].get_i(), begin[0].get_j(), (m_meList.front()).getAlpha(), 0, (m_meList.front()).m_mask_sign); + P.setDisplay(m_selectDisplay); // Set the range - unsigned int memory_range = me->getRange(); - me->setRange(2); + unsigned int memory_range = m_me->getRange(); + m_me->setRange(2); // Point at the beginning of the list bool beginPtAdded = false; @@ -351,18 +351,18 @@ void vpMeNurbs::seekExtremities(const vpImage &I) double si = vpMath::abs(sin(angle)); si = si * vpMath::sign(begin[1].get_i()); for (int i = 0; i < 3; i++) { - P.ifloat = P.ifloat - si * sample_step; - P.i = (int)P.ifloat; - P.jfloat = P.jfloat - co * sample_step; - P.j = (int)P.jfloat; - pt.set_ij(P.ifloat, P.jfloat); + P.m_ifloat = P.m_ifloat - si * sample_step; + P.m_i = (int)P.m_ifloat; + P.m_jfloat = P.m_jfloat - co * sample_step; + P.m_j = (int)P.m_jfloat; + pt.set_ij(P.m_ifloat, P.m_jfloat); if (vpImagePoint::distance(end[0], pt) < threshold) break; - if (!outOfImage(P.i, P.j, 5, rows, cols)) { - P.track(I, me, false); + if (!outOfImage(P.get_i(), P.get_j(), 5, rows, cols)) { + P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { - list.push_front(P); + m_meList.push_front(P); beginPtAdded = true; pt_max = pt; if (vpDEBUG_ENABLE(3)) { @@ -380,8 +380,8 @@ void vpMeNurbs::seekExtremities(const vpImage &I) if (!beginPtAdded) beginPtFound++; - P.init(end[0].get_i(), end[0].get_j(), (list.back()).alpha, 0, (list.back()).mask_sign); - P.setDisplay(selectDisplay); + P.init(end[0].get_i(), end[0].get_j(), (m_meList.back()).getAlpha(), 0, (m_meList.back()).m_mask_sign); + P.setDisplay(m_selectDisplay); bool endPtAdded = false; angle = atan2(end[1].get_i(), end[1].get_j()); @@ -390,18 +390,18 @@ void vpMeNurbs::seekExtremities(const vpImage &I) si = vpMath::abs(sin(angle)); si = si * vpMath::sign(end[1].get_i()); for (int i = 0; i < 3; i++) { - P.ifloat = P.ifloat + si * sample_step; - P.i = (int)P.ifloat; - P.jfloat = P.jfloat + co * sample_step; - P.j = (int)P.jfloat; - pt.set_ij(P.ifloat, P.jfloat); + P.m_ifloat = P.m_ifloat + si * sample_step; + P.m_i = (int)P.m_ifloat; + P.m_jfloat = P.m_jfloat + co * sample_step; + P.m_j = (int)P.m_jfloat; + pt.set_ij(P.m_ifloat, P.m_jfloat); if (vpImagePoint::distance(begin[0], pt) < threshold) break; - if (!outOfImage(P.i, P.j, 5, rows, cols)) { - P.track(I, me, false); + if (!outOfImage(P.get_i(), P.get_j(), 5, rows, cols)) { + P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { - list.push_back(P); + m_meList.push_back(P); endPtAdded = true; if (vpDEBUG_ENABLE(3)) { vpDisplay::displayCross(I, pt, 5, vpColor::blue); @@ -416,10 +416,10 @@ void vpMeNurbs::seekExtremities(const vpImage &I) } if (!endPtAdded) endPtFound++; - me->setRange(memory_range); + m_me->setRange(memory_range); } else { - list.pop_front(); + m_meList.pop_front(); } /*if(begin != nullptr)*/ delete[] begin; /*if(end != nullptr) */ delete[] end; @@ -427,10 +427,10 @@ void vpMeNurbs::seekExtremities(const vpImage &I) void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) { - vpMeSite pt = list.front(); - vpImagePoint firstPoint(pt.ifloat, pt.jfloat); - pt = list.back(); - vpImagePoint lastPoint(pt.ifloat, pt.jfloat); + vpMeSite pt = m_meList.front(); + vpImagePoint firstPoint(pt.m_ifloat, pt.m_jfloat); + pt = m_meList.back(); + vpImagePoint lastPoint(pt.m_ifloat, pt.m_jfloat); if (beginPtFound >= 3 && farFromImageEdge(I, firstPoint)) { vpImagePoint *begin = nullptr; begin = nurbs.computeCurveDersPoint(0.0, 1); @@ -498,17 +498,17 @@ void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) } if (findCenterPoint(&ip_edges_list)) { - for (std::list::iterator it = list.begin(); it != list.end(); + for (std::list::iterator it = m_meList.begin(); it != m_meList.end(); /*++it*/) { vpMeSite s = *it; - vpImagePoint iP(s.ifloat, s.jfloat); + vpImagePoint iP(s.m_ifloat, s.m_jfloat); if (inRectangle(iP, rect)) - it = list.erase(it); + it = m_meList.erase(it); else break; } - std::list::iterator itList = list.begin(); + std::list::iterator itList = m_meList.begin(); double convlt; double delta = 0; unsigned int nbr = 0; @@ -520,19 +520,19 @@ void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) vpMeSite pix; pix.init(iPtemp.get_i(), iPtemp.get_j(), delta); dist = vpMeSite::sqrDistance(s, pix); - if (dist >= vpMath::sqr(me->getSampleStep()) /*25*/) { + if (dist >= vpMath::sqr(m_me->getSampleStep()) /*25*/) { bool exist = false; for (std::list::const_iterator itAdd = addedPt.begin(); itAdd != addedPt.end(); ++itAdd) { dist = vpMeSite::sqrDistance(pix, *itAdd); - if (dist < vpMath::sqr(me->getSampleStep()) /*25*/) + if (dist < vpMath::sqr(m_me->getSampleStep()) /*25*/) exist = true; } if (!exist) { - findAngle(I, iPtemp, me, delta, convlt); + findAngle(I, iPtemp, m_me, delta, convlt); pix.init(iPtemp.get_i(), iPtemp.get_j(), delta, convlt); - pix.setDisplay(selectDisplay); + pix.setDisplay(m_selectDisplay); --itList; - list.insert(itList, pix); + m_meList.insert(itList, pix); ++itList; addedPt.push_front(pix); nbr++; @@ -540,16 +540,16 @@ void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) } } - unsigned int memory_range = me->getRange(); - me->setRange(3); - std::list::iterator itList2 = list.begin(); + unsigned int memory_range = m_me->getRange(); + m_me->setRange(3); + std::list::iterator itList2 = m_meList.begin(); for (unsigned int j = 0; j < nbr; j++) { vpMeSite s = *itList2; - s.track(I, me, false); + s.track(I, m_me, false); *itList2 = s; ++itList2; } - me->setRange(memory_range); + m_me->setRange(memory_range); } /* if (begin != nullptr) */ delete[] begin; @@ -625,20 +625,19 @@ void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) } if (findCenterPoint(&ip_edges_list)) { - // list.end(); vpMeSite s; - for (std::list::iterator it = list.begin(); it!=list.end(); ++it) { + for (std::list::iterator it = m_meList.begin(); it!=m_meList.end(); ++it) { s = *it; - vpImagePoint iP(s.ifloat, s.jfloat); + vpImagePoint iP(s.m_ifloat, s.m_jfloat); if (inRectangle(iP, rect)) { - list.erase(it); + m_meList.erase(it); } else break; } - std::list::iterator itList = list.end(); + std::list::iterator itList = m_meList.end(); --itList; // Move on the last element double convlt; double delta; @@ -651,35 +650,35 @@ void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) vpMeSite pix; pix.init(iPtemp.get_i(), iPtemp.get_j(), 0); dist = vpMeSite::sqrDistance(s, pix); - if (dist >= vpMath::sqr(me->getSampleStep())) { + if (dist >= vpMath::sqr(m_me->getSampleStep())) { bool exist = false; for (std::list::const_iterator itAdd = addedPt.begin(); itAdd != addedPt.end(); ++itAdd) { dist = vpMeSite::sqrDistance(pix, *itAdd); - if (dist < vpMath::sqr(me->getSampleStep())) + if (dist < vpMath::sqr(m_me->getSampleStep())) exist = true; } if (!exist) { - findAngle(I, iPtemp, me, delta, convlt); + findAngle(I, iPtemp, m_me, delta, convlt); pix.init(iPtemp.get_i(), iPtemp.get_j(), delta, convlt); - pix.setDisplay(selectDisplay); - list.push_back(pix); + pix.setDisplay(m_selectDisplay); + m_meList.push_back(pix); addedPt.push_back(pix); nbr++; } } } - unsigned int memory_range = me->getRange(); - me->setRange(3); - std::list::iterator itList2 = list.end(); + unsigned int memory_range = m_me->getRange(); + m_me->setRange(3); + std::list::iterator itList2 = m_meList.end(); --itList2; // Move to the last element for (unsigned int j = 0; j < nbr; j++) { vpMeSite me_s = *itList2; - me_s.track(I, me, false); + me_s.track(I, m_me, false); *itList2 = me_s; --itList2; } - me->setRange(memory_range); + m_me->setRange(memory_range); } /* if (end != nullptr) */ delete[] end; @@ -690,7 +689,7 @@ void vpMeNurbs::seekExtremitiesCanny(const vpImage &I) void vpMeNurbs::reSample(const vpImage &I) { unsigned int n = numberOfSignal(); - double nbPt = floor(dist / me->getSampleStep()); + double nbPt = floor(dist / m_me->getSampleStep()); if ((double)n < 0.7 * nbPt) { sample(I); @@ -706,23 +705,22 @@ void vpMeNurbs::localReSample(const vpImage &I) int n = (int)numberOfSignal(); - // list.front(); - std::list::iterator it = list.begin(); - std::list::iterator itNext = list.begin(); + std::list::iterator it = m_meList.begin(); + std::list::iterator itNext = m_meList.begin(); ++itNext; - unsigned int range_tmp = me->getRange(); - me->setRange(2); + unsigned int range_tmp = m_me->getRange(); + m_me->setRange(2); - while (itNext != list.end() && n <= me->getPointsToTrack()) { + while (itNext != m_meList.end() && n <= m_me->getPointsToTrack()) { vpMeSite s = *it; // current reference pixel vpMeSite s_next = *itNext; // current reference pixel double d = vpMeSite::sqrDistance(s, s_next); - if (d > 4 * vpMath::sqr(me->getSampleStep()) && d < 1600) { - vpImagePoint iP0(s.ifloat, s.jfloat); - vpImagePoint iPend(s_next.ifloat, s_next.jfloat); - vpImagePoint iP_1(s.ifloat, s.jfloat); + if (d > 4 * vpMath::sqr(m_me->getSampleStep()) && d < 1600) { + vpImagePoint iP0(s.m_ifloat, s.m_jfloat); + vpImagePoint iPend(s_next.m_ifloat, s_next.m_jfloat); + vpImagePoint iP_1(s.m_ifloat, s.m_jfloat); double u = 0.0; double ubegin = 0.0; @@ -751,22 +749,22 @@ void vpMeNurbs::localReSample(const vpImage &I) (std::fabs(uend - 1.0) > std::fabs(vpMath::maximum(uend, 1.0)) * std::numeric_limits::epsilon())) { iP = nurbs.computeCurveDersPoint(u, 1); - while (vpImagePoint::sqrDistance(iP[0], iPend) > vpMath::sqr(me->getSampleStep()) && u < uend) { + while (vpImagePoint::sqrDistance(iP[0], iPend) > vpMath::sqr(m_me->getSampleStep()) && u < uend) { u += 0.01; /*if (iP!=nullptr)*/ { delete[] iP; iP = nullptr; } iP = nurbs.computeCurveDersPoint(u, 1); - if (vpImagePoint::sqrDistance(iP[0], iP_1) > vpMath::sqr(me->getSampleStep()) && + if (vpImagePoint::sqrDistance(iP[0], iP_1) > vpMath::sqr(m_me->getSampleStep()) && !outOfImage(iP[0], 0, rows, cols)) { double delta = computeDelta(iP[1].get_i(), iP[1].get_j()); - vpMeSite pix; //= list.value(); + vpMeSite pix; pix.init(iP[0].get_i(), iP[0].get_j(), delta); - pix.setDisplay(selectDisplay); - pix.track(I, me, false); + pix.setDisplay(m_selectDisplay); + pix.track(I, m_me, false); if (pix.getState() == vpMeSite::NO_SUPPRESSION) { - list.insert(it, pix); + m_meList.insert(it, pix); iP_1 = iP[0]; } } @@ -780,43 +778,25 @@ void vpMeNurbs::localReSample(const vpImage &I) ++it; ++itNext; } - me->setRange(range_tmp); + m_me->setRange(range_tmp); } void vpMeNurbs::supressNearPoints() { -#if 0 - // Loop through list of sites to track - list.front(); - while (!list.nextOutside()) { - vpMeSite s = list.value();//current reference pixel - vpMeSite s_next = list.nextValue();//current reference pixel - - if (vpMeSite::sqrDistance(s, s_next) < vpMath::sqr(me->getSampleStep())) { - s_next.setState(vpMeSite::TOO_NEAR); - - list.next(); - list.modify(s_next); - if (!list.nextOutside()) list.next(); - } - else - list.next(); - } -#endif - std::list::const_iterator it = list.begin(); - std::list::iterator itNext = list.begin(); + std::list::const_iterator it = m_meList.begin(); + std::list::iterator itNext = m_meList.begin(); ++itNext; - for (; itNext != list.end();) { + for (; itNext != m_meList.end();) { vpMeSite s = *it; // current reference pixel vpMeSite s_next = *itNext; // current reference pixel - if (vpMeSite::sqrDistance(s, s_next) < vpMath::sqr(me->getSampleStep())) { + if (vpMeSite::sqrDistance(s, s_next) < vpMath::sqr(m_me->getSampleStep())) { s_next.setState(vpMeSite::TOO_NEAR); *itNext = s_next; ++it; ++itNext; - if (itNext != list.end()) { + if (itNext != m_meList.end()) { ++it; ++itNext; } @@ -839,12 +819,12 @@ void vpMeNurbs::track(const vpImage &I) // Suppressions des points ejectes par le tracking suppressPoints(); - if (list.size() == 1) + if (m_meList.size() == 1) throw(vpTrackingException(vpTrackingException::notEnoughPointError, "Not enough valid me to track")); // Recalcule les parametres - // nurbs.globalCurveInterp(list); - nurbs.globalCurveApprox(list, nbControlPoints); + // nurbs.globalCurveInterp(m_meList); + nurbs.globalCurveApprox(m_meList, nbControlPoints); // On resample localement localReSample(I); @@ -853,8 +833,8 @@ void vpMeNurbs::track(const vpImage &I) if (enableCannyDetection) seekExtremitiesCanny(I); - // nurbs.globalCurveInterp(list); - nurbs.globalCurveApprox(list, nbControlPoints); + // nurbs.globalCurveInterp(m_meList); + nurbs.globalCurveApprox(m_meList, nbControlPoints); double u = 0.0; vpImagePoint pt; diff --git a/modules/tracker/me/src/moving-edges/vpMeSite.cpp b/modules/tracker/me/src/moving-edges/vpMeSite.cpp index 695b1b13b0..913805f3ad 100644 --- a/modules/tracker/me/src/moving-edges/vpMeSite.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeSite.cpp @@ -46,135 +46,147 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS static bool horsImage(int i, int j, int half, int rows, int cols) { - // return((i < half + 1) || ( i > (rows - half - 3) )||(j < half + 1) || (j - // > (cols - half - 3) )) ; int half_1 = half + 1; int half_3 = half + 3; - // return((i < half + 1) || ( i > (rows - half - 3) )||(j < half + 1) || (j - // > (cols - half - 3) )) ; - return ((0 < (half_1 - i)) || ((i - rows + half_3) > 0) || (0 < (half_1 - j)) || ((j - cols + half_3) > 0)); + return ((0 < (half_1 - i)) || (((i - rows) + half_3) > 0) || (0 < (half_1 - j)) || (((j - cols) + half_3) > 0)); } #endif void vpMeSite::init() { // Site components - alpha = 0.0; - convlt = 0.0; - weight = -1; + m_alpha = 0.0; + m_convlt = 0.0; + m_weight = -1; + m_contrastThreshold = 10000.0; m_selectDisplay = NONE; // Pixel components - i = 0; - j = 0; - ifloat = i; - jfloat = j; + m_i = 0; + m_j = 0; + m_ifloat = m_i; + m_jfloat = m_j; - mask_sign = 1; + m_mask_sign = 1; - normGradient = 0; + m_normGradient = 0; m_state = NO_SUPPRESSION; } vpMeSite::vpMeSite() - : i(0), j(0), ifloat(0), jfloat(0), mask_sign(1), alpha(0.), convlt(0.), normGradient(0), - weight(1), m_selectDisplay(NONE), m_state(NO_SUPPRESSION) + : m_i(0), m_j(0), m_ifloat(0), m_jfloat(0), m_mask_sign(1), m_alpha(0.), m_convlt(0.), m_normGradient(0), + m_weight(1), m_contrastThreshold(10000.0), m_selectDisplay(NONE), m_state(NO_SUPPRESSION) { } -vpMeSite::vpMeSite(double ip, double jp) - : i(0), j(0), ifloat(0), jfloat(0), mask_sign(1), alpha(0.), convlt(0.), normGradient(0), - weight(1), m_selectDisplay(NONE), m_state(NO_SUPPRESSION) +vpMeSite::vpMeSite(const double &ip, const double &jp) + : m_i(0), m_j(0), m_ifloat(0), m_jfloat(0), m_mask_sign(1), m_alpha(0.), m_convlt(0.), m_normGradient(0), + m_weight(1), m_contrastThreshold(10000.0), m_selectDisplay(NONE), m_state(NO_SUPPRESSION) { - i = vpMath::round(ip); - j = vpMath::round(jp); - ifloat = ip; - jfloat = jp; + m_i = vpMath::round(ip); + m_j = vpMath::round(jp); + m_ifloat = ip; + m_jfloat = jp; } vpMeSite::vpMeSite(const vpMeSite &mesite) - : i(0), j(0), ifloat(0), jfloat(0), mask_sign(1), alpha(0.), convlt(0.), normGradient(0), - weight(1), m_selectDisplay(NONE), m_state(NO_SUPPRESSION) + : m_i(0), m_j(0), m_ifloat(0), m_jfloat(0), m_mask_sign(1), m_alpha(0.), m_convlt(0.), m_normGradient(0), + m_weight(1), m_contrastThreshold(10000.0), m_selectDisplay(NONE), m_state(NO_SUPPRESSION) { *this = mesite; } // More an Update than init // For points in meter form (to avoid approximations) -void vpMeSite::init(double ip, double jp, double alphap) +void vpMeSite::init(const double &ip, const double &jp, const double &alphap) { - // Note: keep old value of convlt and contrast + // Note: keep old value of m_convlt, contrast and threshold m_selectDisplay = NONE; - ifloat = ip; - i = vpMath::round(ip); - jfloat = jp; - j = vpMath::round(jp); - alpha = alphap; - mask_sign = 1; + m_ifloat = ip; + m_i = vpMath::round(ip); + m_jfloat = jp; + m_j = vpMath::round(jp); + m_alpha = alphap; + m_mask_sign = 1; } // initialise with convolution() -void vpMeSite::init(double ip, double jp, double alphap, double convltp) +void vpMeSite::init(const double &ip, const double &jp, const double &alphap, const double &convltp) { m_selectDisplay = NONE; - ifloat = ip; - i = (int)ip; - jfloat = jp; - j = (int)jp; - alpha = alphap; - convlt = convltp; - mask_sign = 1; + m_ifloat = ip; + m_i = static_cast(ip); + m_jfloat = jp; + m_j = static_cast(jp); + m_alpha = alphap; + m_convlt = convltp; + m_mask_sign = 1; } // initialise with convolution and sign -void vpMeSite::init(double ip, double jp, double alphap, double convltp, int sign) +void vpMeSite::init(const double &ip, const double &jp, const double &alphap, const double &convltp, const int &sign) { m_selectDisplay = NONE; - ifloat = ip; - i = (int)ip; - jfloat = jp; - j = (int)jp; - alpha = alphap; - convlt = convltp; - mask_sign = sign; + m_ifloat = ip; + m_i = static_cast(ip); + m_jfloat = jp; + m_j = static_cast(jp); + m_alpha = alphap; + m_convlt = convltp; + m_mask_sign = sign; +} + +// initialise with convolution and sign +void vpMeSite::init(const double &ip, const double &jp, const double &alphap, const double &convltp, const int &sign, const double &contrastThreshold) +{ + m_selectDisplay = NONE; + m_ifloat = ip; + m_i = static_cast(ip); + m_jfloat = jp; + m_j = static_cast(jp); + m_alpha = alphap; + m_convlt = convltp; + m_mask_sign = sign; + m_contrastThreshold = contrastThreshold; } vpMeSite &vpMeSite::operator=(const vpMeSite &m) { - i = m.i; - j = m.j; - ifloat = m.ifloat; - jfloat = m.jfloat; - mask_sign = m.mask_sign; - alpha = m.alpha; - convlt = m.convlt; - normGradient = m.normGradient; - weight = m.weight; + m_i = m.m_i; + m_j = m.m_j; + m_ifloat = m.m_ifloat; + m_jfloat = m.m_jfloat; + m_mask_sign = m.m_mask_sign; + m_alpha = m.m_alpha; + m_convlt = m.m_convlt; + m_normGradient = m.m_normGradient; + m_weight = m.m_weight; + m_contrastThreshold = m.m_contrastThreshold; m_selectDisplay = m.m_selectDisplay; m_state = m.m_state; return *this; } -vpMeSite *vpMeSite::getQueryList(const vpImage &I, const int range) +vpMeSite *vpMeSite::getQueryList(const vpImage &I, const int &range) const { unsigned int range_ = static_cast(range); // Size of query list includes the point on the line - vpMeSite *list_query_pixels = new vpMeSite[2 * range_ + 1]; + vpMeSite *list_query_pixels = new vpMeSite[(2 * range_) + 1]; // range : +/- the range within which the pixel's // correspondent will be sought - double salpha = sin(alpha); - double calpha = cos(alpha); + double salpha = sin(m_alpha); + double calpha = cos(m_alpha); int n = 0; vpImagePoint ip; - for (int k = -range; k <= range; k++) { - double ii = (ifloat + k * salpha); - double jj = (jfloat + k * calpha); + for (int k = -range; k <= range; ++k) { + double ii = m_ifloat + (k * salpha); + double jj = m_jfloat + (k * calpha); // Display if ((m_selectDisplay == RANGE_RESULT) || (m_selectDisplay == RANGE)) { @@ -185,15 +197,15 @@ vpMeSite *vpMeSite::getQueryList(const vpImage &I, const int rang // Copy parent's convolution vpMeSite pel; - pel.init(ii, jj, alpha, convlt, mask_sign); + pel.init(ii, jj, m_alpha, m_convlt, m_mask_sign, m_contrastThreshold); pel.setDisplay(m_selectDisplay); // Display // Add site to the query list list_query_pixels[n] = pel; - n++; + ++n; } - return (list_query_pixels); + return list_query_pixels; } // Specific function for ME @@ -205,51 +217,54 @@ double vpMeSite::convolution(const vpImage &I, const vpMe *me) double conv = 0.0; unsigned int msize = me->getMaskSize(); - half = (static_cast(msize) - 1) >> 1; + half = static_cast((msize - 1) >> 1); - if (horsImage(i, j, half + me->getStrip(), height_, width_)) { + if (horsImage(m_i, m_j, half + me->getStrip(), height_, width_)) { conv = 0.0; - i = 0; - j = 0; + m_i = 0; + m_j = 0; } else { // Calculate tangent angle from normal - double theta = alpha + M_PI / 2; + double theta = m_alpha + (M_PI / 2); // Move tangent angle to within 0->M_PI for a positive // mask index - while (theta < 0) + while (theta < 0) { theta += M_PI; - while (theta > M_PI) + } + while (theta > M_PI) { theta -= M_PI; + } // Convert radians to degrees - int thetadeg = vpMath::round(theta * 180 / M_PI); + int thetadeg = vpMath::round((theta * 180) / M_PI); - if (abs(thetadeg) == 180) { + const int flatAngle = 180; + if (abs(thetadeg) == flatAngle) { thetadeg = 0; } - unsigned int index_mask = (unsigned int)(thetadeg / (double)me->getAngleStep()); + unsigned int index_mask = static_cast(thetadeg / static_cast(me->getAngleStep())); - unsigned int i_ = static_cast(i); - unsigned int j_ = static_cast(j); + unsigned int i_ = static_cast(m_i); + unsigned int j_ = static_cast(m_j); unsigned int half_ = static_cast(half); unsigned int ihalf = i_ - half_; unsigned int jhalf = j_ - half_; - for (unsigned int a = 0; a < msize; a++) { + for (unsigned int a = 0; a < msize; ++a) { unsigned int ihalfa = ihalf + a; - for (unsigned int b = 0; b < msize; b++) { - conv += mask_sign * me->getMask()[index_mask][a][b] * I(ihalfa, jhalf + b); + for (unsigned int b = 0; b < msize; ++b) { + conv += m_mask_sign * me->getMask()[index_mask][a][b] * I(ihalfa, jhalf + b); } } } - return (conv); + return conv; } -void vpMeSite::track(const vpImage &I, const vpMe *me, bool test_contrast) +void vpMeSite::track(const vpImage &I, const vpMe *me, const bool &test_contrast) { int max_rank = -1; double max_convolution = 0; @@ -260,53 +275,64 @@ void vpMeSite::track(const vpImage &I, const vpMe *me, bool test_ // of the current pixel will be sought unsigned int range = me->getRange(); - vpMeSite *list_query_pixels = getQueryList(I, (int)range); + vpMeSite *list_query_pixels = getQueryList(I, static_cast(range)); double contrast_max = 1 + me->getMu2(); double contrast_min = 1 - me->getMu1(); // array in which likelihood ratios will be stored - double *likelihood = new double[2 * range + 1]; - - double threshold; - if (me->getLikelihoodThresholdType() == vpMe::NORMALIZED_THRESHOLD) { - threshold = 2.0 * me->getThreshold(); - } - else { - double n_d = me->getMaskSize(); - threshold = me->getThreshold() / (100.0 * n_d * trunc(n_d / 2.0)); - } + double *likelihood = new double[(2 * range) + 1]; if (test_contrast) { double diff = 1e6; - for (unsigned int n = 0; n < 2 * range + 1; n++) { + for (unsigned int n = 0; n < ((2 * range) + 1); ++n) { // convolution results double convolution_ = list_query_pixels[n].convolution(I, me); + double threshold = list_query_pixels[n].getContrastThreshold(); + + if (me->getLikelihoodThresholdType() == vpMe::NORMALIZED_THRESHOLD) { + threshold = 2.0 * threshold; + } + else { + double n_d = me->getMaskSize(); + threshold = threshold / (100.0 * n_d * trunc(n_d / 2.0)); + } // luminance ratio of reference pixel to potential correspondent pixel // the luminance must be similar, hence the ratio value should // lay between, for instance, 0.5 and 1.5 (parameter tolerance) - likelihood[n] = fabs(convolution_ + convlt); + likelihood[n] = fabs(convolution_ + m_convlt); + if (likelihood[n] > threshold) { - contrast = convolution_ / convlt; - if ((contrast > contrast_min) && (contrast < contrast_max) && fabs(1 - contrast) < diff) { + contrast = convolution_ / m_convlt; + if ((contrast > contrast_min) && (contrast < contrast_max) && (fabs(1 - contrast) < diff)) { diff = fabs(1 - contrast); max_convolution = convolution_; max = likelihood[n]; - max_rank = (int)n; + max_rank = static_cast(n); } } } } else { // test on contrast only - for (unsigned int n = 0; n < 2 * range + 1; n++) { + for (unsigned int n = 0; n < ((2 * range) + 1); ++n) { + double threshold = list_query_pixels[n].getContrastThreshold(); + + if (me->getLikelihoodThresholdType() == vpMe::NORMALIZED_THRESHOLD) { + threshold = 2.0 * threshold; + } + else { + double n_d = me->getMaskSize(); + threshold = threshold / (100.0 * n_d * trunc(n_d / 2.0)); + } + // convolution results double convolution_ = list_query_pixels[n].convolution(I, me); likelihood[n] = fabs(2 * convolution_); - if (likelihood[n] > max && likelihood[n] > threshold) { + if ((likelihood[n] > max) && (likelihood[n] > threshold)) { max_convolution = convolution_; max = likelihood[n]; - max_rank = (int)n; + max_rank = static_cast(n); } } } @@ -315,16 +341,16 @@ void vpMeSite::track(const vpImage &I, const vpMe *me, bool test_ if (max_rank >= 0) { if ((m_selectDisplay == RANGE_RESULT) || (m_selectDisplay == RESULT)) { - ip.set_i(list_query_pixels[max_rank].i); - ip.set_j(list_query_pixels[max_rank].j); + ip.set_i(list_query_pixels[max_rank].m_i); + ip.set_j(list_query_pixels[max_rank].m_j); vpDisplay::displayPoint(I, ip, vpColor::red); } *this = list_query_pixels[max_rank]; // The vpMeSite2 is replaced by the // vpMeSite2 of max likelihood - normGradient = vpMath::sqr(max_convolution); + m_normGradient = vpMath::sqr(max_convolution); - convlt = max_convolution; + m_convlt = max_convolution; delete[] list_query_pixels; delete[] likelihood; @@ -332,59 +358,62 @@ void vpMeSite::track(const vpImage &I, const vpMe *me, bool test_ else // none of the query sites is better than the threshold { if ((m_selectDisplay == RANGE_RESULT) || (m_selectDisplay == RESULT)) { - ip.set_i(list_query_pixels[0].i); - ip.set_j(list_query_pixels[0].j); + ip.set_i(list_query_pixels[0].m_i); + ip.set_j(list_query_pixels[0].m_j); vpDisplay::displayPoint(I, ip, vpColor::green); } - normGradient = 0; - if (std::fabs(contrast) > std::numeric_limits::epsilon()) + m_normGradient = 0; + if (std::fabs(contrast) > std::numeric_limits::epsilon()) { m_state = CONTRAST; // contrast suppression - else + } + else { m_state = THRESHOLD; // threshold suppression + } delete[] list_query_pixels; delete[] likelihood; // modif portage } } -int vpMeSite::operator!=(const vpMeSite &m) { return ((m.i != i) || (m.j != j)); } +int vpMeSite::operator!=(const vpMeSite &m) { return ((m.m_i != m_i) || (m.m_j != m_j)); } VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpMeSite &vpMeS) { - return (os << "Alpha: " << vpMeS.alpha << " Convolution: " << vpMeS.convlt << " Weight: " << vpMeS.weight); + return (os << "Alpha: " << vpMeS.m_alpha << " Convolution: " << vpMeS.m_convlt << " Weight: " << vpMeS.m_weight << " Threshold: " << vpMeS.m_contrastThreshold); } -void vpMeSite::display(const vpImage &I) { vpMeSite::display(I, ifloat, jfloat, m_state); } +void vpMeSite::display(const vpImage &I) { vpMeSite::display(I, m_ifloat, m_jfloat, m_state); } -void vpMeSite::display(const vpImage &I) { vpMeSite::display(I, ifloat, jfloat, m_state); } +void vpMeSite::display(const vpImage &I) { vpMeSite::display(I, m_ifloat, m_jfloat, m_state); } // Static functions void vpMeSite::display(const vpImage &I, const double &i, const double &j, const vpMeSiteState &state) { + const unsigned int crossSize = 3; switch (state) { case NO_SUPPRESSION: - vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::green, 1); + vpDisplay::displayCross(I, vpImagePoint(i, j), crossSize, vpColor::green, 1); break; case CONTRAST: - vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::blue, 1); + vpDisplay::displayCross(I, vpImagePoint(i, j), crossSize, vpColor::blue, 1); break; case THRESHOLD: - vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::purple, 1); + vpDisplay::displayCross(I, vpImagePoint(i, j), crossSize, vpColor::purple, 1); break; case M_ESTIMATOR: - vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::red, 1); + vpDisplay::displayCross(I, vpImagePoint(i, j), crossSize, vpColor::red, 1); break; - case TOO_NEAR: - vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::cyan, 1); + case OUTSIDE_ROI_MASK: + vpDisplay::displayCross(I, vpImagePoint(i, j), crossSize, vpColor::cyan, 1); break; default: - vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::yellow, 1); + vpDisplay::displayCross(I, vpImagePoint(i, j), crossSize, vpColor::yellow, 1); } } @@ -407,7 +436,7 @@ void vpMeSite::display(const vpImage &I, const double &i, const double & vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::red, 1); break; - case TOO_NEAR: + case OUTSIDE_ROI_MASK: vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::cyan, 1); break; diff --git a/modules/tracker/me/src/moving-edges/vpMeTracker.cpp b/modules/tracker/me/src/moving-edges/vpMeTracker.cpp index 111a5f2e02..dcbc578560 100644 --- a/modules/tracker/me/src/moving-edges/vpMeTracker.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeTracker.cpp @@ -51,59 +51,42 @@ void vpMeTracker::init() { vpTracker::init(); p.resize(2); - selectDisplay = vpMeSite::NONE; + m_selectDisplay = vpMeSite::NONE; } vpMeTracker::vpMeTracker() - : list(), me(nullptr), init_range(1), nGoodElement(0), m_mask(nullptr), selectDisplay(vpMeSite::NONE) -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - , - query_range(0), display_point(false) -#endif + : m_meList(), m_me(nullptr), m_init_range(1), m_nGoodElement(0), m_mask(nullptr), m_maskCandidates(nullptr), m_selectDisplay(vpMeSite::NONE) { init(); } vpMeTracker::vpMeTracker(const vpMeTracker &meTracker) - : vpTracker(meTracker), list(), me(nullptr), init_range(1), nGoodElement(0), m_mask(nullptr), selectDisplay(vpMeSite::NONE) -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - , - query_range(0), display_point(false) -#endif + : vpTracker(meTracker), m_meList(), m_me(nullptr), m_init_range(1), m_nGoodElement(0), m_mask(nullptr), m_maskCandidates(nullptr), m_selectDisplay(vpMeSite::NONE) { init(); - me = meTracker.me; - list = meTracker.list; - nGoodElement = meTracker.nGoodElement; - init_range = meTracker.init_range; - selectDisplay = meTracker.selectDisplay; - -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - display_point = meTracker.display_point; - query_range = meTracker.query_range; -#endif + m_me = meTracker.m_me; + m_meList = meTracker.m_meList; + m_nGoodElement = meTracker.m_nGoodElement; + m_init_range = meTracker.m_init_range; + m_selectDisplay = meTracker.m_selectDisplay; } void vpMeTracker::reset() { - nGoodElement = 0; - list.clear(); + m_nGoodElement = 0; + m_meList.clear(); } vpMeTracker::~vpMeTracker() { reset(); } -vpMeTracker &vpMeTracker::operator=(vpMeTracker &p_me) +vpMeTracker &vpMeTracker::operator=(vpMeTracker &meTracker) { - list = p_me.list; - me = p_me.me; - selectDisplay = p_me.selectDisplay; - init_range = p_me.init_range; - nGoodElement = p_me.nGoodElement; -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - query_range = p_me.query_range; - display_point = p_me.display_point; -#endif + m_meList = meTracker.m_meList; + m_me = meTracker.m_me; + m_selectDisplay = meTracker.m_selectDisplay; + m_init_range = meTracker.m_init_range; + m_nGoodElement = meTracker.m_nGoodElement; return *this; } @@ -114,121 +97,168 @@ unsigned int vpMeTracker::numberOfSignal() unsigned int number_signal = 0; // Loop through all the points tracked from the contour - number_signal = static_cast(std::count_if(list.begin(), list.end(), isSuppressZero)); + number_signal = static_cast(std::count_if(m_meList.begin(), m_meList.end(), isSuppressZero)); return number_signal; } -unsigned int vpMeTracker::totalNumberOfSignal() { return (unsigned int)list.size(); } +unsigned int vpMeTracker::totalNumberOfSignal() { return static_cast(m_meList.size()); } -bool vpMeTracker::inMask(const vpImage *mask, unsigned int i, unsigned int j) +bool vpMeTracker::inRoiMask(const vpImage *mask, unsigned int i, unsigned int j) { try { - return (mask == nullptr || mask->getValue(i, j)); + return ((mask == nullptr) || (mask->getValue(i, j))); } catch (vpException &) { return false; } } -int vpMeTracker::outOfImage(int i, int j, int half, int rows, int cols) +bool vpMeTracker::inMeMaskCandidates(const vpImage *meMaskCandidates, unsigned int i, unsigned int j) +{ + if (meMaskCandidates == nullptr) { + return true; + } + else { + const unsigned int kernelSize = 3; + const unsigned int halfKernelSize = (kernelSize - 1) / 2; + const unsigned int nbRows = meMaskCandidates->getRows(); + const unsigned int nbCols = meMaskCandidates->getCols(); + + if ((i >= nbRows) || (j >= nbCols)) { + // The asked point is outside the mask + return false; + } + if ((*meMaskCandidates)[i][j]) { + // The asked point is a candidate + return true; + } + unsigned int iStart = 0, jStart = 0; + unsigned int iStop = nbRows - 1, jStop = nbCols - 1; + // Ensuring we won't go outside the limits of the mask + if (i >= halfKernelSize) { + iStart = i - halfKernelSize; + } + if (j >= halfKernelSize) { + jStart = j - halfKernelSize; + } + if ((i + halfKernelSize) < nbRows) { + iStop = i + halfKernelSize; + } + if ((j + halfKernelSize) < nbCols) { + jStop = j + halfKernelSize; + } + // Looking in its neighborhood + bool isACandidate = false; + unsigned int iter_i = iStart, iter_j = jStart; + + while ((!isACandidate) && (iter_i <= iStop)) { + iter_j = jStart; + while ((!isACandidate) && (iter_j <= jStop)) { + isACandidate = (*meMaskCandidates)[iter_i][iter_j]; + ++iter_j; + } + ++iter_i; + } + + return isACandidate; + } +} + +bool vpMeTracker::outOfImage(int i, int j, int border, int nrows, int ncols) { - return (!((i > half + 2) && (i < rows - (half + 2)) && (j > half + 2) && (j < cols - (half + 2)))); + int borderWith2SparedPixels = border + 2; + return (!((i > borderWith2SparedPixels) && (i < (nrows - borderWith2SparedPixels)) + && (j > borderWith2SparedPixels) && (j < (ncols - borderWith2SparedPixels)) + )); } -int vpMeTracker::outOfImage(const vpImagePoint &iP, int half, int rows, int cols) +bool vpMeTracker::outOfImage(const vpImagePoint &iP, int border, int nrows, int ncols) { + const int borderPlus2 = border + 2; int i = vpMath::round(iP.get_i()); int j = vpMath::round(iP.get_j()); - return (!((i > half + 2) && (i < rows - (half + 2)) && (j > half + 2) && (j < cols - (half + 2)))); + return (!((i > borderPlus2) && (i < (nrows - borderPlus2)) && (j > borderPlus2) && (j < (ncols - borderPlus2)))); } void vpMeTracker::initTracking(const vpImage &I) { - if (!me) { + if (!m_me) { vpDERROR_TRACE(2, "Tracking error: Moving edges not initialized"); throw(vpTrackingException(vpTrackingException::initializationError, "Moving edges not initialized")); } // Must set range to 0 - unsigned int range_tmp = me->getRange(); - me->setRange(init_range); + unsigned int range_tmp = m_me->getRange(); + m_me->setRange(m_init_range); - nGoodElement = 0; + m_nGoodElement = 0; // Loop through list of sites to track - for (std::list::iterator it = list.begin(); it != list.end(); ++it) { + std::list::iterator end = m_meList.end(); + for (std::list::iterator it = m_meList.begin(); it != end; ++it) { vpMeSite refp = *it; // current reference pixel // If element hasn't been suppressed if (refp.getState() == vpMeSite::NO_SUPPRESSION) { - try { - refp.track(I, me, false); - } - catch (...) { - // EM verifier quel signal est de sortie !!! - vpERROR_TRACE("Error caught"); - throw; + + refp.track(I, m_me, false); + + if (refp.getState() == vpMeSite::NO_SUPPRESSION) { + ++m_nGoodElement; } - if (refp.getState() == vpMeSite::NO_SUPPRESSION) - nGoodElement++; } *it = refp; } - me->setRange(range_tmp); + m_me->setRange(range_tmp); } void vpMeTracker::track(const vpImage &I) { - if (!me) { + if (!m_me) { vpDERROR_TRACE(2, "Tracking error: Moving edges not initialized"); throw(vpTrackingException(vpTrackingException::initializationError, "Moving edges not initialized")); } - if (list.empty()) { + if (m_meList.empty()) { vpDERROR_TRACE(2, "Tracking error: too few pixel to track"); throw(vpTrackingException(vpTrackingException::notEnoughPointError, "Too few pixel to track")); } - nGoodElement = 0; + m_nGoodElement = 0; // Loop through list of sites to track - std::list::iterator it = list.begin(); - while (it != list.end()) { + std::list::iterator it = m_meList.begin(); + std::list::iterator end = m_meList.end(); + while (it != end) { vpMeSite s = *it; // current reference pixel // If element hasn't been suppressed if (s.getState() == vpMeSite::NO_SUPPRESSION) { + s.track(I, m_me, true); - try { - s.track(I, me, true); - } - catch (...) { - s.setState(vpMeSite::THRESHOLD); - } - if (vpMeTracker::inMask(m_mask, s.i, s.j)) { - if (s.getState() != vpMeSite::THRESHOLD) { - nGoodElement++; + if (vpMeTracker::inRoiMask(m_mask, s.get_i(), s.get_j())) { + if (s.getState() == vpMeSite::NO_SUPPRESSION) { + ++m_nGoodElement; } - *it = s; - ++it; } else { - // Site outside mask: it is no more tracked. - it = list.erase(it); + // Site outside mask + s.setState(vpMeSite::OUTSIDE_ROI_MASK); } } - else { - ++it; - } + + *it = s; + ++it; } } void vpMeTracker::display(const vpImage &I) { - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + std::list::const_iterator end = m_meList.end(); + for (std::list::const_iterator it = m_meList.begin(); it != end; ++it) { vpMeSite p_me = *it; p_me.display(I); } @@ -236,7 +266,8 @@ void vpMeTracker::display(const vpImage &I) void vpMeTracker::display(const vpImage &I) { - for (std::list::const_iterator it = list.begin(); it != list.end(); ++it) { + std::list::const_iterator end = m_meList.end(); + for (std::list::const_iterator it = m_meList.begin(); it != end; ++it) { vpMeSite p_me = *it; p_me.display(I); } @@ -244,12 +275,13 @@ void vpMeTracker::display(const vpImage &I) void vpMeTracker::display(const vpImage &I, vpColVector &w, unsigned int &index_w) { - for (std::list::iterator it = list.begin(); it != list.end(); ++it) { + std::list::iterator end = m_meList.end(); + for (std::list::iterator it = m_meList.begin(); it != end; ++it) { vpMeSite P = *it; if (P.getState() == vpMeSite::NO_SUPPRESSION) { - P.weight = w[index_w]; - index_w++; + P.setWeight(w[index_w]); + ++index_w; } *it = P; diff --git a/modules/tracker/me/src/moving-edges/vpNurbs.cpp b/modules/tracker/me/src/moving-edges/vpNurbs.cpp index 5a8dd1a08f..3eac4dff37 100644 --- a/modules/tracker/me/src/moving-edges/vpNurbs.cpp +++ b/modules/tracker/me/src/moving-edges/vpNurbs.cpp @@ -542,13 +542,13 @@ void vpNurbs::globalCurveInterp(vpList &l_crossingPoints) std::vector v_crossingPoints; l_crossingPoints.front(); vpMeSite s = l_crossingPoints.value(); - vpImagePoint pt(s.ifloat, s.jfloat); + vpImagePoint pt(s.get_ifloat(), s.get_jfloat()); vpImagePoint pt_1 = pt; v_crossingPoints.push_back(pt); l_crossingPoints.next(); while (!l_crossingPoints.outside()) { s = l_crossingPoints.value(); - pt.set_ij(s.ifloat, s.jfloat); + pt.set_ij(s.get_ifloat(), s.get_jfloat()); if (vpImagePoint::distance(pt_1, pt) >= 10) { v_crossingPoints.push_back(pt); pt_1 = pt; @@ -572,13 +572,13 @@ void vpNurbs::globalCurveInterp(const std::list &l_crossingPoints) { std::vector v_crossingPoints; vpMeSite s = l_crossingPoints.front(); - vpImagePoint pt(s.ifloat, s.jfloat); + vpImagePoint pt(s.get_ifloat(), s.get_jfloat()); vpImagePoint pt_1 = pt; v_crossingPoints.push_back(pt); std::list::const_iterator it = l_crossingPoints.begin(); ++it; for (; it != l_crossingPoints.end(); ++it) { - vpImagePoint pt_tmp(it->ifloat, it->jfloat); + vpImagePoint pt_tmp(it->get_ifloat(), it->get_jfloat()); if (vpImagePoint::distance(pt_1, pt_tmp) >= 10) { v_crossingPoints.push_back(pt_tmp); pt_1 = pt_tmp; @@ -714,7 +714,7 @@ void vpNurbs::globalCurveApprox(vpList &l_crossingPoints, unsigned int l_crossingPoints.front(); while (!l_crossingPoints.outside()) { vpMeSite s = l_crossingPoints.value(); - vpImagePoint pt(s.ifloat, s.jfloat); + vpImagePoint pt(s.get_ifloat(), s.get_jfloat()); v_crossingPoints.push_back(pt); l_crossingPoints.next(); } @@ -735,7 +735,7 @@ void vpNurbs::globalCurveApprox(const std::list &l_crossingPoints, uns { std::vector v_crossingPoints; for (std::list::const_iterator it = l_crossingPoints.begin(); it != l_crossingPoints.end(); ++it) { - vpImagePoint pt(it->ifloat, it->jfloat); + vpImagePoint pt(it->get_ifloat(), it->get_jfloat()); v_crossingPoints.push_back(pt); } globalCurveApprox(v_crossingPoints, p, n, knots, controlPoints, weights); diff --git a/modules/tracker/me/test/testJsonMe.cpp b/modules/tracker/me/test/testJsonMe.cpp index 8d0ef208f5..18edc7d6ea 100644 --- a/modules/tracker/me/test/testJsonMe.cpp +++ b/modules/tracker/me/test/testJsonMe.cpp @@ -100,8 +100,8 @@ class RandomMeGenerator : public Catch::Generators::IGenerator static_cast(next()); } - vpMe const &get() const override { return current; } - bool next() override + vpMe const &get() const vp_override { return current; } + bool next() vp_override { current.setThreshold(m_dist(m_rand) * 255); current.setMaskNumber(m_int_dist(m_rand) * 10); diff --git a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMI.h b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMI.h index 5bd1206e53..2dfd9a5ab9 100644 --- a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMI.h +++ b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMI.h @@ -115,7 +115,7 @@ class VISP_EXPORT vpTemplateTrackerMI : public vpTemplateTracker void computeMI(double &MI); void computeProba(int &nbpoint); - double getCost(const vpImage &I, const vpColVector &tp) override; + double getCost(const vpImage &I, const vpColVector &tp) vp_override; double getCost(const vpImage &I) { return getCost(I, p); } double getNormalizedCost(const vpImage &I, const vpColVector &tp); double getNormalizedCost(const vpImage &I) { return getNormalizedCost(I, p); } @@ -151,7 +151,7 @@ class VISP_EXPORT vpTemplateTrackerMI : public vpTemplateTracker m_dB(), m_d2u(), m_d2v(), m_dA() { } explicit vpTemplateTrackerMI(vpTemplateTrackerWarp *_warp); - virtual ~vpTemplateTrackerMI() override; + virtual ~vpTemplateTrackerMI() vp_override; vpMatrix getCovarianceMatrix() const { return covarianceMatrix; } double getMI() const { return MI_postEstimation; } double getMI(const vpImage &I, int &nc, const int &bspline, vpColVector &tp); diff --git a/modules/vision/include/visp3/vision/vpPose.h b/modules/vision/include/visp3/vision/vpPose.h index 3c8a60589c..db4e32dfc3 100644 --- a/modules/vision/include/visp3/vision/vpPose.h +++ b/modules/vision/include/visp3/vision/vpPose.h @@ -52,7 +52,6 @@ #include #include #include -#include // Check if std:c++17 or higher. // Here we cannot use (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) in the declaration of the class diff --git a/modules/vision/include/visp3/vision/vpPoseException.h b/modules/vision/include/visp3/vision/vpPoseException.h index 57be1d404d..ed749e1d82 100644 --- a/modules/vision/include/visp3/vision/vpPoseException.h +++ b/modules/vision/include/visp3/vision/vpPoseException.h @@ -37,7 +37,7 @@ #include #include -#include +#include /*! * \class vpPoseException diff --git a/modules/vision/include/visp3/vision/vpPoseFeatures.h b/modules/vision/include/visp3/vision/vpPoseFeatures.h index 0a621cccab..2e4324bc48 100644 --- a/modules/vision/include/visp3/vision/vpPoseFeatures.h +++ b/modules/vision/include/visp3/vision/vpPoseFeatures.h @@ -34,9 +34,6 @@ /*! \file vpPose.h \brief Tools for pose computation from any feature. - - \author Aurelien Yol - \date June, 5 2012 */ #ifndef vpPoseFeatures_HH @@ -63,6 +60,8 @@ #include #include + +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #ifndef DOXYGEN_SHOULD_SKIP_THIS @@ -302,21 +301,29 @@ class vpPoseSpecificFeatureTemplate : public vpPoseSpecificFeature func_ptr = f_ptr; // std::move(f_ptr); m_tuple = new std::tuple(args...); } + virtual ~vpPoseSpecificFeatureTemplate() vp_override + { + delete m_tuple; + } - virtual ~vpPoseSpecificFeatureTemplate() override { delete m_tuple; } - - virtual void createDesired() override { buildDesiredFeatureWithTuple(m_desiredFeature, func_ptr, *m_tuple); } + virtual void createDesired() vp_override + { + buildDesiredFeatureWithTuple(m_desiredFeature, func_ptr, *m_tuple); + } - virtual vpColVector error() override + virtual vpColVector error() vp_override { // std::cout << "Getting S... : " << std::get<0>(*tuple).get_s() << // std::endl; return m_currentFeature.error(m_desiredFeature); } - virtual vpMatrix currentInteraction() override { return m_currentFeature.interaction(); } + virtual vpMatrix currentInteraction() vp_override + { + return m_currentFeature.interaction(); + } - virtual void createCurrent(const vpHomogeneousMatrix &cMo) override + virtual void createCurrent(const vpHomogeneousMatrix &cMo) vp_override { buildCurrentFeatureWithTuple(m_currentFeature, cMo, func_ptr, *m_tuple); } @@ -351,20 +358,33 @@ class vpPoseSpecificFeatureTemplateObject : public vpPoseSpecificFeature m_obj = o; } - virtual ~vpPoseSpecificFeatureTemplateObject() override { delete m_tuple; } + virtual ~vpPoseSpecificFeatureTemplateObject() vp_override + { + delete m_tuple; + } - virtual void createDesired() override { buildDesiredFeatureObjectWithTuple(m_obj, m_desiredFeature, func_ptr, *m_tuple); } + virtual void createDesired() vp_override + { + buildDesiredFeatureObjectWithTuple(m_obj, m_desiredFeature, func_ptr, *m_tuple); + } - virtual vpColVector error() override { return m_currentFeature.error(m_desiredFeature); } + virtual vpColVector error() vp_override + { + return m_currentFeature.error(m_desiredFeature); + } - virtual vpMatrix currentInteraction() override { return m_currentFeature.interaction(); } + virtual vpMatrix currentInteraction() vp_override + { + return m_currentFeature.interaction(); + } - virtual void createCurrent(const vpHomogeneousMatrix &cMo) override + virtual void createCurrent(const vpHomogeneousMatrix &cMo) vp_override { buildCurrentFeatureObjectWithTuple(m_obj, m_currentFeature, cMo, func_ptr, *m_tuple); } }; #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS +#endif // (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! * \class vpPoseFeatures @@ -474,6 +494,7 @@ class VISP_EXPORT vpPoseFeatures */ void addFeatureSegment(vpPoint &, vpPoint &); +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher /*! * Add a specific feature for the pose computation. */ @@ -485,6 +506,7 @@ class VISP_EXPORT vpPoseFeatures */ template void addSpecificFeature(ObjType *obj, RetType(ObjType:: *fct_ptr)(ArgsFunc...), Args &&...args); +#endif /*! * Clear all the features @@ -611,16 +633,19 @@ 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. - * - * \param cMo : Current Pose. - * \param err : Resulting error vector. - * \param L : Resulting interaction matrix. - */ +/*! + * Get the error vector and L matrix from all the features. + * + * \param cMo : Current Pose. + * \param err : Resulting error vector. + * \param L : Resulting interaction matrix. + */ void error_and_interaction(vpHomogeneousMatrix &cMo, vpColVector &err, vpMatrix &L); /*! @@ -641,6 +666,7 @@ class VISP_EXPORT vpPoseFeatures void computePoseRobustVVS(vpHomogeneousMatrix &cMo); }; +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher /*! * Add a specific feature for the pose computation. * @@ -786,7 +812,7 @@ 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 #endif diff --git a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp index 2a60c93ba9..603b1b156d 100644 --- a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp +++ b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp @@ -453,8 +453,10 @@ void vpPose::poseDementhonPlan(vpHomogeneousMatrix &cMo) vpColVector sv; vpMatrix Ap, imA, imAt, kAt; bool isRankEqualTo3 = false; // Indicates if the rank of A is the expected one - double logNofSvdThresh = std::log(m_dementhonSvThresh)/lnOfSvdFactorUsed; // Get the log_n(m_dementhonSvThresh), where n is the factor by which we will multiply it if the svd decomposition fails. - int nbMaxIter = static_cast(std::max(std::ceil(logNOfSvdThresholdLimit - logNofSvdThresh), 1.)); // Ensure that if the user chose a threshold > svdThresholdLimit, at least 1 iteration of svd decomposition is performed + // Get the log_n(m_dementhonSvThresh), where n is the factor by which we will multiply it if the svd decomposition fails. + double logNofSvdThresh = std::log(m_dementhonSvThresh)/lnOfSvdFactorUsed; + // Ensure that if the user chose a threshold > svdThresholdLimit, at least 1 iteration of svd decomposition is performed + int nbMaxIter = static_cast(std::max(std::ceil(logNOfSvdThresholdLimit - logNofSvdThresh), 1.)); double svdThreshold = m_dementhonSvThresh; int irank = 0; for (int i = 0; i < nbMaxIter && !isRankEqualTo3; i++) { diff --git a/modules/vision/src/pose-estimation/vpPoseFeatures.cpp b/modules/vision/src/pose-estimation/vpPoseFeatures.cpp index 2550ab73ba..958bf2b998 100644 --- a/modules/vision/src/pose-estimation/vpPoseFeatures.cpp +++ b/modules/vision/src/pose-estimation/vpPoseFeatures.cpp @@ -81,9 +81,11 @@ 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; @@ -303,12 +305,14 @@ 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/vpPoseRGBD.cpp b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp index 260855c0fd..8de618bc7e 100644 --- a/modules/vision/src/pose-estimation/vpPoseRGBD.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp @@ -39,7 +39,7 @@ namespace { - // See also vpPlaneEstimation.cpp that implements the same functionaly in c++17 +// See also vpPlaneEstimation.cpp that implements the same functionaly in c++17 void estimatePlaneEquationSVD(const std::vector &point_cloud_face, vpPlane &plane_equation_estimated, vpColVector ¢roid, double &normalized_weights) { diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index 2a746200d8..500b6760b8 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -49,7 +49,9 @@ #include #include +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include +#endif #define eps 1e-6 @@ -227,7 +229,7 @@ bool vpPose::vpRansacFunctor::poseRansacImpl() } } else { - // No post filtering on pose, so copy cMo_temp to cMo + // No post filtering on pose, so copy cMo_temp to cMo m_cMo = cMo_tmp; } @@ -339,7 +341,7 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo } } else { - // No prefiltering + // No prefiltering listOfUniquePoints = listOfPoints; size_t index_pt = 0; @@ -353,10 +355,15 @@ 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(); @@ -368,11 +375,13 @@ 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; @@ -400,6 +409,7 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo bool successRansac = false; size_t best_consensus_size = 0; + for (auto &worker : ransacWorkers) { if (worker.getResult()) { successRansac = true; @@ -413,11 +423,12 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo } foundSolution = successRansac; +#endif } else { - // Sequential RANSAC + // Sequential RANSAC vpRansacFunctor sequentialRansac(cMo, ransacNbInlierConsensus, ransacMaxTrials, ransacThreshold, 0, - checkDegeneratePoints, listOfUniquePoints, func); + checkDegeneratePoints, listOfUniquePoints, func); sequentialRansac(); foundSolution = sequentialRansac.getResult(); diff --git a/modules/vision/test/pose/testPoseFeatures.cpp b/modules/vision/test/pose/testPoseFeatures.cpp index de359cc12d..3388fa9573 100644 --- a/modules/vision/test/pose/testPoseFeatures.cpp +++ b/modules/vision/test/pose/testPoseFeatures.cpp @@ -52,6 +52,7 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) class vp_createPointClass { public: @@ -71,6 +72,7 @@ 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) { @@ -151,6 +153,7 @@ int test_pose(bool use_robust) pose.addFeatureEllipse(circle); +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpFeaturePoint fp; vpFeatureLine fl; vpFeatureSegment fs; @@ -160,6 +163,7 @@ 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); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h b/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h index 7b4e1ae37f..d6ac1ea3dd 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h @@ -175,11 +175,11 @@ class VISP_EXPORT vpFeatureDepth : public vpBasicFeature void buildFrom(double x, double y, double Z, double LogZoverZstar); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; - vpFeatureDepth *duplicate() const override; - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + unsigned int thickness = 1) const vp_override; + vpFeatureDepth *duplicate() const vp_override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; double get_x() const; @@ -189,10 +189,10 @@ class VISP_EXPORT vpFeatureDepth : public vpBasicFeature double get_LogZoverZstar() const; - void init() override; - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; + void init() vp_override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; + void print(unsigned int select = FEATURE_ALL) const vp_override; - void print(unsigned int select = FEATURE_ALL) const override; void set_x(double x); void set_y(double y); @@ -205,9 +205,3 @@ class VISP_EXPORT vpFeatureDepth : public vpBasicFeature }; #endif - -/* - * Local variables: - * c-basic-offset: 2 - * End: - */ diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h b/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h index 6dc382d56b..9a84490a62 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h @@ -76,15 +76,15 @@ class VISP_EXPORT vpFeatureEllipse : public vpBasicFeature void buildFrom(double x, double y, double n20, double n11, double n02, double A, double B, double C); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; //! Feature duplication - vpFeatureEllipse *duplicate() const override; + vpFeatureEllipse *duplicate() const vp_override; //! compute the error between two visual features from a subset //! a the possible features - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; /*! * Returns the visual feature corresponding to the ellipse centroid coordinate along camera x-axis. @@ -111,12 +111,12 @@ class VISP_EXPORT vpFeatureEllipse : public vpBasicFeature double get_n02() const { return s[4]; } //! Default initialization. - void init() override; + void init() vp_override; //! compute the interaction matrix from a subset a the possible features - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; //! Print the name of the feature - void print(unsigned int select = FEATURE_ALL) const override; + void print(unsigned int select = FEATURE_ALL) const vp_override; void set_x(double x); void set_y(double y); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h b/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h index 807b732fa2..225fe8b78d 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h @@ -204,12 +204,11 @@ class VISP_EXPORT vpFeatureLine : public vpBasicFeature void buildFrom(double rho, double theta, double A, double B, double C, double D); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; - vpFeatureLine *duplicate() const override; - - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + unsigned int thickness = 1) const vp_override; + vpFeatureLine *duplicate() const vp_override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; /*! * Return the \f$ \rho \f$ subset value of the visual feature \f$ s \f$. @@ -221,10 +220,9 @@ class VISP_EXPORT vpFeatureLine : public vpBasicFeature */ double getTheta() const { return s[1]; } - void init() override; - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; - - void print(unsigned int select = FEATURE_ALL) const override; + void init() vp_override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; + void print(unsigned int select = FEATURE_ALL) const vp_override; void setRhoTheta(double rho, double theta); void setABCD(double A, double B, double C, double D); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h index 5fc3e56f5b..8316b9cc05 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h @@ -91,31 +91,33 @@ class VISP_EXPORT vpFeatureLuminance : public vpBasicFeature public: vpFeatureLuminance(); vpFeatureLuminance(const vpFeatureLuminance &f); + //! Destructor. - virtual ~vpFeatureLuminance() override; + virtual ~vpFeatureLuminance() vp_override; void buildFrom(vpImage &I); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; - vpFeatureLuminance *duplicate() const override; + vpFeatureLuminance *duplicate() const vp_override; - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; void error(const vpBasicFeature &s_star, vpColVector &e); double get_Z() const; - void init() override; void init(unsigned int _nbr, unsigned int _nbc, double _Z); - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; + + void init() vp_override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; void interaction(vpMatrix &L); + void print(unsigned int select = FEATURE_ALL) const vp_override; vpFeatureLuminance &operator=(const vpFeatureLuminance &f); - void print(unsigned int select = FEATURE_ALL) const override; void setCameraParameters(vpCameraParameters &_cam); void set_Z(double Z); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h index 6022914d71..b387404617 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h @@ -207,15 +207,17 @@ class VISP_EXPORT vpFeatureMoment : public vpBasicFeature /** @name Inherited functionalities from vpFeatureMoment */ //@{ virtual void compute_interaction(void); - vpBasicFeature *duplicate() const override; + + vpBasicFeature *duplicate() const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; int getDimension(unsigned int select = FEATURE_ALL) const; - void init(void) override; - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; + void init(void) vp_override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; + void linkTo(vpFeatureMomentDatabase &featureMoments); /*! @@ -229,7 +231,7 @@ class VISP_EXPORT vpFeatureMoment : public vpBasicFeature */ virtual const std::string name() const = 0; - void print(unsigned int select = FEATURE_ALL) const override; + void print(unsigned int select = FEATURE_ALL) const vp_override; virtual void printDependencies(std::ostream &os) const; void update(double A, double B, double C); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h index eed6971d19..ed7de38ddc 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h @@ -114,18 +114,23 @@ class VISP_EXPORT vpFeatureMomentAlpha : public vpFeatureMoment : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 1) { } - void compute_interaction() override; - + void compute_interaction() vp_override; /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentAlpha"; } + const std::string momentName() const vp_override + { + return "vpMomentAlpha"; + } - /*! - * Feature name. - */ - const std::string name() const override { return "vpFeatureMomentAlpha"; } +/*! + * Feature name. + */ + const std::string name() const vp_override + { + return "vpFeatureMomentAlpha"; + } - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; }; #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h index b862c3182d..7281bbf156 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h @@ -69,15 +69,22 @@ class VISP_EXPORT vpFeatureMomentArea : public vpFeatureMoment : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 1) { } - void compute_interaction() override; + void compute_interaction() vp_override; + /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentArea"; } + const std::string momentName() const vp_override + { + return "vpMomentArea"; + } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentArea"; } + const std::string name() const vp_override + { + return "vpFeatureMomentArea"; + } }; #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h index 3e9e46fb07..1e7401a609 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h @@ -94,17 +94,24 @@ class VISP_EXPORT vpFeatureMomentAreaNormalized : public vpFeatureMoment vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(database, A_, B_, C_, featureMoments, 1) { } - void compute_interaction() override; + + void compute_interaction() vp_override; /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentAreaNormalized"; } + const std::string momentName() const vp_override + { + return "vpMomentAreaNormalized"; + } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentAreaNormalized"; } + const std::string name() const vp_override + { + return "vpFeatureMomentAreaNormalized"; + } }; #else @@ -189,17 +196,24 @@ class VISP_EXPORT vpFeatureMomentAreaNormalized : public vpFeatureMoment vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 1) { } - void compute_interaction() override; + + void compute_interaction() vp_override; /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentAreaNormalized"; } + const std::string momentName() const vp_override + { + return "vpMomentAreaNormalized"; + } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentAreaNormalized"; } + const std::string name() const vp_override + { + return "vpFeatureMomentAreaNormalized"; + } }; #endif #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h index 235c1249b7..9c8c2dff92 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h @@ -81,11 +81,12 @@ class VISP_EXPORT vpFeatureMomentBasic : public vpFeatureMoment public: vpFeatureMomentBasic(vpMomentDatabase &moments, double A, double B, double C, vpFeatureMomentDatabase *featureMoments = nullptr); - void compute_interaction() override; + + void compute_interaction() vp_override; #ifndef DOXYGEN_SHOULD_SKIP_THIS /* Add function due to pure virtual definition in vpBasicFeature.h */ - vpMatrix interaction(unsigned int /* select = FEATURE_ALL */) override + vpMatrix interaction(unsigned int /* select = FEATURE_ALL */) vp_override { throw vpException(vpException::functionNotImplementedError, "Not implemented!"); } @@ -96,11 +97,17 @@ class VISP_EXPORT vpFeatureMomentBasic : public vpFeatureMoment /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentBasic"; } + const std::string momentName() const vp_override + { + return "vpMomentBasic"; + } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentBasic"; } + const std::string name() const vp_override + { + return "vpFeatureMomentBasic"; + } }; #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h index ed01b28183..96a9c299d5 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h @@ -103,17 +103,24 @@ class VISP_EXPORT vpFeatureMomentCInvariant : public vpFeatureMoment vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(moments, A, B, C, featureMoments, 16) { } - void compute_interaction() override; + + void compute_interaction() vp_override; /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentCInvariant"; } + const std::string momentName() const vp_override + { + return "vpMomentCInvariant"; + } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentCInvariant"; } + const std::string name() const vp_override + { + return "vpFeatureMomentCInvariant"; + } /*! * Shortcut selector for \f$C_1\f$. @@ -242,15 +249,21 @@ class VISP_EXPORT vpFeatureMomentCInvariant : public vpFeatureMoment : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 16), LI(16) { } - void compute_interaction() override; + void compute_interaction() vp_override; /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentCInvariant"; } + const std::string momentName() const vp_override + { + return "vpMomentCInvariant"; + } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentCInvariant"; } + const std::string name() const vp_override + { + return "vpFeatureMomentCInvariant"; + } /*! * Shortcut selector for \f$C_1\f$. diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h index 1e3f957b68..dd035e8005 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h @@ -85,11 +85,12 @@ class VISP_EXPORT vpFeatureMomentCentered : public vpFeatureMoment public: vpFeatureMomentCentered(vpMomentDatabase &moments, double A, double B, double C, vpFeatureMomentDatabase *featureMoments = nullptr); - void compute_interaction() override; + + void compute_interaction() vp_override; #ifndef DOXYGEN_SHOULD_SKIP_THIS /* Add function due to pure virtual definition in vpBasicFeature.h */ - vpMatrix interaction(unsigned int /* select = FEATURE_ALL */) override + vpMatrix interaction(unsigned int /* select = FEATURE_ALL */) vp_override { throw vpException(vpException::functionNotImplementedError, "Not implemented!"); } @@ -100,12 +101,18 @@ class VISP_EXPORT vpFeatureMomentCentered : public vpFeatureMoment /*! * Associated moment name */ - const std::string momentName() const override { return "vpMomentCentered"; } + const std::string momentName() const vp_override + { + return "vpMomentCentered"; + } /*! * Feature name */ - const std::string name() const override { return "vpFeatureMomentCentered"; } + const std::string name() const vp_override + { + return "vpFeatureMomentCentered"; + } friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpFeatureMomentCentered &v); }; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h index 942ee4f6fd..71351a164a 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h @@ -161,17 +161,17 @@ class VISP_EXPORT vpFeatureMomentGravityCenter : public vpFeatureMoment : vpFeatureMoment(database, A_, B_, C_, featureMoments, 2) { } - void compute_interaction() override; + void compute_interaction() vp_override; /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentGravityCenter"; } + const std::string momentName() const vp_override { return "vpMomentGravityCenter"; } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentGravityCenter"; } + const std::string name() const vp_override { return "vpFeatureMomentGravityCenter"; } /*! * Shortcut selector for \f$x_g\f$. @@ -233,17 +233,17 @@ class VISP_EXPORT vpFeatureMomentGravityCenter : public vpFeatureMoment : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 2) { } - void compute_interaction() override; + void compute_interaction() vp_override; /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentGravityCenter"; } + const std::string momentName() const vp_override { return "vpMomentGravityCenter"; } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentGravityCenter"; } + const std::string name() const vp_override { return "vpFeatureMomentGravityCenter"; } /*! * Shortcut selector for \f$x_g\f$. diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h index 24e2a10480..a2cef02fd9 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h @@ -101,17 +101,18 @@ class VISP_EXPORT vpFeatureMomentGravityCenterNormalized : public vpFeatureMomen vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(database, A_, B_, C_, featureMoments, 2) { } - void compute_interaction() override; + + void compute_interaction() vp_override; /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentGravityCenterNormalized"; } + const std::string momentName() const vp_override { return "vpMomentGravityCenterNormalized"; } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentGravityCenterNormalized"; } + const std::string name() const vp_override { return "vpFeatureMomentGravityCenterNormalized"; } /*! * Shortcut selector for \f$x_n\f$. @@ -255,17 +256,17 @@ class VISP_EXPORT vpFeatureMomentGravityCenterNormalized : public vpFeatureMomen vpFeatureMomentDatabase *featureMoments = nullptr) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments, 2) { } - void compute_interaction() override; + void compute_interaction() vp_override; /*! * Associated moment name. */ - const std::string momentName() const override { return "vpMomentGravityCenterNormalized"; } + const std::string momentName() const vp_override { return "vpMomentGravityCenterNormalized"; } /*! * Feature name. */ - const std::string name() const override { return "vpFeatureMomentGravityCenterNormalized"; } + const std::string name() const vp_override { return "vpFeatureMomentGravityCenterNormalized"; } /*! * Shortcut selector for \f$x_n\f$. diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h index 5949fab755..3b24e42101 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h @@ -184,13 +184,13 @@ class VISP_EXPORT vpFeaturePoint : public vpBasicFeature void buildFrom(double x, double y, double Z); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; - vpFeaturePoint *duplicate() const override; + vpFeaturePoint *duplicate() const vp_override; - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; double get_x() const; @@ -198,10 +198,9 @@ class VISP_EXPORT vpFeaturePoint : public vpBasicFeature double get_Z() const; - void init() override; - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; - - void print(unsigned int select = FEATURE_ALL) const override; + void init() vp_override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; + void print(unsigned int select = FEATURE_ALL) const vp_override; void set_x(double x); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h index 52908f7da3..a9a110ae59 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h @@ -214,16 +214,16 @@ class VISP_EXPORT vpFeaturePoint3D : public vpBasicFeature void buildFrom(double X, double Y, double Z); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; // feature duplication - vpFeaturePoint3D *duplicate() const override; + vpFeaturePoint3D *duplicate() const vp_override; // compute the error between two visual features from a subset // a the possible features - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; // get the point X-coordinates double get_X() const; @@ -233,14 +233,14 @@ class VISP_EXPORT vpFeaturePoint3D : public vpBasicFeature double get_Z() const; // basic construction - void init() override; + void init() vp_override; // compute the interaction matrix from a subset a the possible features - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; // print the name of the feature - void print(unsigned int select = FEATURE_ALL) const override; + void print(unsigned int select = FEATURE_ALL) const vp_override; - // set the point X-coordinates +// set the point X-coordinates void set_X(double X); // set the point Y-coordinates void set_Y(double Y); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h index cee08b8a78..f80e292e75 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h @@ -262,19 +262,19 @@ class VISP_EXPORT vpFeaturePointPolar : public vpBasicFeature void buildFrom(double rho, double theta, double Z); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; // feature duplication - vpFeaturePointPolar *duplicate() const override; + vpFeaturePointPolar *duplicate() const vp_override; // compute the error between two visual features from a subset // a the possible features - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; // basic construction - void init() override; + void init() vp_override; // get the point rho-coordinates double get_rho() const; @@ -284,10 +284,10 @@ class VISP_EXPORT vpFeaturePointPolar : public vpBasicFeature double get_Z() const; // compute the interaction matrix from a subset a the possible features - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; // print the name of the feature - void print(unsigned int select = FEATURE_ALL) const override; + void print(unsigned int select = FEATURE_ALL) const vp_override; // set the point rho-coordinates void set_rho(double rho); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h b/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h index fa074df8eb..6ea14acc4a 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h @@ -71,14 +71,14 @@ class VISP_EXPORT vpFeatureSegment : public vpBasicFeature void buildFrom(double x1, double y1, double Z1, double x2, double y2, double Z2); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; //! Feature duplication. - vpFeatureSegment *duplicate() const override; + vpFeatureSegment *duplicate() const vp_override; // compute the error between two visual features from a subset // a the possible features - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; /*! * Get the x coordinate of the segment center in the image plane. @@ -130,12 +130,12 @@ class VISP_EXPORT vpFeatureSegment : public vpBasicFeature inline double getZ2() const { return Z2_; } // Basic construction. - void init() override; + void init() vp_override; // compute the interaction matrix from a subset a the possible features - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; - void print(unsigned int select = FEATURE_ALL) const override; + void print(unsigned int select = FEATURE_ALL) const vp_override; /*! * Indicates if the normalized features are considered. diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h b/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h index 35356cabbb..cf50898a69 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h @@ -258,16 +258,16 @@ class VISP_EXPORT vpFeatureThetaU : public vpBasicFeature void buildFrom(const vpHomogeneousMatrix &M); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; //! Feature duplication. - vpFeatureThetaU *duplicate() const override; + vpFeatureThetaU *duplicate() const vp_override; // compute the error between two visual features from a subset // a the possible features - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; vpFeatureThetaURotationRepresentationType getFeatureThetaURotationType() const; @@ -276,11 +276,10 @@ class VISP_EXPORT vpFeatureThetaU : public vpBasicFeature double get_TUz() const; // Basic construction. - void init() override; + void init() vp_override; // compute the interaction matrix from a subset a the possible features - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; - - void print(unsigned int select = FEATURE_ALL) const override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; + void print(unsigned int select = FEATURE_ALL) const vp_override; void set_TUx(double tu_x); void set_TUy(double tu_y); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h b/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h index 91ea77ca9b..776abaf685 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h @@ -300,16 +300,16 @@ class VISP_EXPORT vpFeatureTranslation : public vpBasicFeature void buildFrom(const vpHomogeneousMatrix &f2Mf1); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; //! Feature duplication - vpFeatureTranslation *duplicate() const override; + vpFeatureTranslation *duplicate() const vp_override; // compute the error between two visual features from a subset // a the possible features - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; vpFeatureTranslationRepresentationType getFeatureTranslationType() const; @@ -318,12 +318,12 @@ class VISP_EXPORT vpFeatureTranslation : public vpBasicFeature double get_Tz() const; // basic construction - void init() override; + void init() vp_override; // compute the interaction matrix from a subset a the possible features - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; // print the name of the feature - void print(unsigned int select = FEATURE_ALL) const override; + void print(unsigned int select = FEATURE_ALL) const vp_override; void set_Tx(double t_x); void set_Ty(double t_y); diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h b/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h index be90bfa0fb..3af4acd106 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h @@ -82,13 +82,11 @@ class VISP_EXPORT vpFeatureVanishingPoint : public vpBasicFeature void buildFrom(double x, double y); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; - - vpFeatureVanishingPoint *duplicate() const override; - - vpColVector error(const vpBasicFeature &s_star, unsigned int select = (vpFeatureVanishingPoint::selectX() | vpFeatureVanishingPoint::selectY())) override; + unsigned int thickness = 1) const vp_override; + vpFeatureVanishingPoint *duplicate() const vp_override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = (vpFeatureVanishingPoint::selectX() | vpFeatureVanishingPoint::selectY())) vp_override; double get_x() const; double get_y() const; @@ -96,10 +94,9 @@ class VISP_EXPORT vpFeatureVanishingPoint : public vpBasicFeature double getOneOverRho() const; double getAlpha() const; - void init() override; - vpMatrix interaction(unsigned int select = (vpFeatureVanishingPoint::selectX() | vpFeatureVanishingPoint::selectY())) override; - - void print(unsigned int select = (vpFeatureVanishingPoint::selectX() | vpFeatureVanishingPoint::selectY())) const override; + void init() vp_override; + vpMatrix interaction(unsigned int select = (vpFeatureVanishingPoint::selectX() | vpFeatureVanishingPoint::selectY())) vp_override; + void print(unsigned int select = (vpFeatureVanishingPoint::selectX() | vpFeatureVanishingPoint::selectY())) const vp_override; void set_x(double x); void set_y(double y); diff --git a/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h b/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h index 0af2b86297..f8a811eda4 100644 --- a/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h +++ b/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h @@ -181,13 +181,11 @@ class VISP_EXPORT vpGenericFeature : public vpBasicFeature explicit vpGenericFeature(unsigned int dim); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; + unsigned int thickness = 1) const vp_override; void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, - unsigned int thickness = 1) const override; - - vpGenericFeature *duplicate() const override; - - vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) override; + unsigned int thickness = 1) const vp_override; + vpGenericFeature *duplicate() const vp_override; + vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; vpColVector error(unsigned int select = FEATURE_ALL); @@ -197,11 +195,9 @@ class VISP_EXPORT vpGenericFeature : public vpBasicFeature void get_s(double &s0, double &s1) const; void get_s(double &s0, double &s1, double &s2) const; - void init() override; - - vpMatrix interaction(unsigned int select = FEATURE_ALL) override; - - void print(unsigned int select = FEATURE_ALL) const override; + void init() vp_override; + vpMatrix interaction(unsigned int select = FEATURE_ALL) vp_override; + void print(unsigned int select = FEATURE_ALL) const vp_override; void setInteractionMatrix(const vpMatrix &L); void setError(const vpColVector &error_vector); void set_s(const vpColVector &s); diff --git a/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp b/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp index 7c48ad5000..f730ed8bd7 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp @@ -137,8 +137,9 @@ vpFeatureLuminance &vpFeatureLuminance::operator=(const vpFeatureLuminance &f) */ vpFeatureLuminance::~vpFeatureLuminance() { - if (pixInfo != nullptr) + if (pixInfo != nullptr) { delete[] pixInfo; + } } /*! diff --git a/tutorial/grabber/tutorial-grabber-1394.cpp b/tutorial/grabber/tutorial-grabber-1394.cpp index 8b5794cf30..8593aeca02 100644 --- a/tutorial/grabber/tutorial-grabber-1394.cpp +++ b/tutorial/grabber/tutorial-grabber-1394.cpp @@ -58,7 +58,7 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_DC1394) +#if defined(VISP_HAVE_DC1394) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { std::string opt_seqname; int opt_record_mode = 0; @@ -180,5 +180,8 @@ 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 4b267054ba..244e93e047 100644 --- a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp +++ b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp @@ -73,7 +73,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_PYLON) +#if defined(VISP_HAVE_PYLON) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { unsigned int opt_device = 0; std::string opt_type("GigE"); @@ -202,5 +202,8 @@ 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 f88bd769c3..e7c14dbb53 100644 --- a/tutorial/grabber/tutorial-grabber-bebop2.cpp +++ b/tutorial/grabber/tutorial-grabber-bebop2.cpp @@ -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) +#if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_FFMPEG) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { std::string opt_seqname; int opt_record_mode = 0; @@ -198,7 +198,10 @@ 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 -#endif // #if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_FFMPEG) +#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) + std::cout << "This tutorial should be built with c++11 support" << std::endl; +#endif +#endif } #else int main() { std::cout << "This tutorial needs visp_robot module that is not built." << std::endl; } diff --git a/tutorial/grabber/tutorial-grabber-flycapture.cpp b/tutorial/grabber/tutorial-grabber-flycapture.cpp index fcf4b75c12..d3251c0480 100644 --- a/tutorial/grabber/tutorial-grabber-flycapture.cpp +++ b/tutorial/grabber/tutorial-grabber-flycapture.cpp @@ -60,7 +60,7 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_FLYCAPTURE) +#if defined(VISP_HAVE_FLYCAPTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { std::string opt_seqname; int opt_record_mode = 0; @@ -186,5 +186,8 @@ 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 b52ba492ce..635fa29fa2 100644 --- a/tutorial/grabber/tutorial-grabber-ids-ueye.cpp +++ b/tutorial/grabber/tutorial-grabber-ids-ueye.cpp @@ -107,7 +107,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_UEYE) +#if defined(VISP_HAVE_UEYE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { unsigned int opt_device = 0; std::string opt_seqname; @@ -369,5 +369,8 @@ 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 7f7fd8bcd3..c086ec8974 100644 --- a/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp +++ b/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp @@ -12,7 +12,8 @@ int main(int argc, char **argv) { -#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) +#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) \ + && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) std::vector > type_serial_nb; std::vector cam_found; @@ -127,6 +128,9 @@ int main(int argc, char **argv) "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 return EXIT_SUCCESS; } diff --git a/tutorial/grabber/tutorial-grabber-opencv.cpp b/tutorial/grabber/tutorial-grabber-opencv.cpp index 5113934a3b..0a0d14133a 100644 --- a/tutorial/grabber/tutorial-grabber-opencv.cpp +++ b/tutorial/grabber/tutorial-grabber-opencv.cpp @@ -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) +#if defined(HAVE_OPENCV_VIDEOIO) && defined(HAVE_OPENCV_HIGHGUI) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { cv::VideoCapture cap(opt_device); // open the default camera if (!cap.isOpened()) { // check if we succeeded @@ -186,5 +186,8 @@ 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 193075629d..6b0b06c2e3 100644 --- a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp @@ -56,7 +56,8 @@ 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)) +#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) \ + && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { std::string opt_seqname_left = "left-%04d.png", opt_seqname_right = "right-%04d.png"; int opt_record_mode = 0; @@ -177,5 +178,8 @@ 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 a4644a250b..424c1f23bf 100644 --- a/tutorial/grabber/tutorial-grabber-realsense.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense.cpp @@ -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) +#if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { std::string opt_seqname; int opt_record_mode = 0; @@ -208,5 +208,8 @@ 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 971a599138..442aa99755 100644 --- a/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp +++ b/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp @@ -12,7 +12,7 @@ */ int main(int argc, char **argv) { -#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_OCCIPITAL_STRUCTURE) +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) // Both cameras can stream color and depth in 640x480 resolution. unsigned int width = 640, height = 480; @@ -79,5 +79,8 @@ 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 2bfd2ecd0b..25799e790f 100644 --- a/tutorial/grabber/tutorial-grabber-structure-core.cpp +++ b/tutorial/grabber/tutorial-grabber-structure-core.cpp @@ -72,7 +72,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { std::string opt_seqname_visible = "visible-%04d.png", opt_seqname_depth = "depth-%04d.png"; int opt_record_mode = 0; @@ -230,5 +230,8 @@ 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 64ecb33ad2..36fba4330e 100644 --- a/tutorial/grabber/tutorial-grabber-v4l2.cpp +++ b/tutorial/grabber/tutorial-grabber-v4l2.cpp @@ -76,7 +76,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_V4L2) +#if defined(VISP_HAVE_V4L2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { int opt_device = 0; unsigned int opt_scale = 1; // Default value is 2 in the constructor. Turn @@ -200,6 +200,9 @@ 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/image/tutorial-image-colormap.cpp b/tutorial/image/tutorial-image-colormap.cpp index b4bc0ff063..0145bab17c 100644 --- a/tutorial/image/tutorial-image-colormap.cpp +++ b/tutorial/image/tutorial-image-colormap.cpp @@ -10,6 +10,7 @@ int main() { +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) try { std::map colormaps_str = { {vpColormap::COLORMAP_AUTUMN, "Colormap Autumn"}, @@ -153,6 +154,8 @@ int main() catch (const vpException &e) { std::cerr << "Catch an exception: " << e << std::endl; } - +#else + std::cout << "This tutorial should be built with c++11 support" << 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 b8a112ca78..6b4effe999 100644 --- a/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp +++ b/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp @@ -30,7 +30,16 @@ bool run_detection(const vpImage &I_src, vpCircleHoughTransform & vpImageConvert::convert(I_src, I_disp); unsigned int id = 0; +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) std::vector v_colors = { vpColor::red, vpColor::purple, vpColor::orange, vpColor::yellow, vpColor::blue }; +#else + std::vector v_colors; + v_colors.push_back(vpColor::red); + v_colors.push_back(vpColor::purple); + v_colors.push_back(vpColor::orange); + v_colors.push_back(vpColor::yellow); + v_colors.push_back(vpColor::blue); +#endif unsigned int idColor = 0; //! [Iterate detections] const unsigned int nbCircle = detectedCircles.size(); @@ -71,7 +80,7 @@ bool run_detection(const vpImage &I_src, vpCircleHoughTransform & unsigned int nbVotedCircles = opt_votingPoints->size(); for (unsigned int idCircle = 0; idCircle < nbVotedCircles; ++idCircle) { // Get the voting points of a detected circle - const std::vector> &votingPoints = (*opt_votingPoints)[idCircle]; + const std::vector > &votingPoints = (*opt_votingPoints)[idCircle]; unsigned int nbVotingPoints = votingPoints.size(); for (unsigned int idPoint = 0; idPoint < nbVotingPoints; ++idPoint) { // Draw the voting points diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp index 6d3c26596f..8191a7ffe8 100755 --- a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp +++ b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp @@ -6,7 +6,8 @@ #include #include -#if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(HAVE_OPENCV_HIGHGUI) +#if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(HAVE_OPENCV_HIGHGUI)) \ + && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) namespace { // https://en.cppreference.com/w/cpp/io/c/fprintf @@ -35,7 +36,8 @@ std::unique_ptr make_unique_compat(Args&&... args) int main(int argc, char *argv[]) { -#if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(HAVE_OPENCV_HIGHGUI) +#if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(HAVE_OPENCV_HIGHGUI)) \ + && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) bool opencv_backend = false; std::string npz_filename = "npz_tracking_teabox.npz"; bool print_cMo = false; diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp index 446fc693af..efd53106c7 100755 --- a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp +++ b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp @@ -3,12 +3,15 @@ #include #include + +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) namespace { std::vector poseToVec(const vpHomogeneousMatrix &cMo) { vpThetaUVector tu = cMo.getThetaUVector(); vpTranslationVector t = cMo.getTranslationVector(); + std::vector vec { t[0], t[1], t[2], tu[0], tu[1], tu[2] }; return vec; @@ -203,3 +206,12 @@ int main(int argc, char **argv) return EXIT_SUCCESS; } + +#else +#include + +int main() +{ + std::cout << "This tutorial needs c++11 flags" << std::endl; +} +#endif From eb7ee0aa492c36c57532b8faaa172141b4a4414a Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 31 Jan 2024 12:15:30 +0100 Subject: [PATCH 06/12] Fix nullptr check --- cmake/AddExtraCompilationFlags.cmake | 4 ++++ cmake/templates/VISPConfig.cmake.in | 1 + doc/config-doxygen.in | 1 + 3 files changed, 6 insertions(+) diff --git a/cmake/AddExtraCompilationFlags.cmake b/cmake/AddExtraCompilationFlags.cmake index 03061fbc03..de1baea4a0 100644 --- a/cmake/AddExtraCompilationFlags.cmake +++ b/cmake/AddExtraCompilationFlags.cmake @@ -95,6 +95,10 @@ elseif(MSVC) endif() endif() +if(NOT VISP_HAVE_NULLPTR AND VISP_CXX_STANDARD EQUAL VISP_CXX_STANDARD_98) + add_extra_compiler_option("-Wno-c++11-compat") +endif() + # Note here ViSPDetectPlatform.cmake should be called before this file to set ARM var if((CMAKE_CXX_COMPILER_ID MATCHES "GNU") AND (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 6.0) AND (CMAKE_CXX_COMPILER_VERSION VERSION_LESS 9.0) AND ARM) # Here to disable warnings due to gcc bug introduced in gcc 7 on arm. diff --git a/cmake/templates/VISPConfig.cmake.in b/cmake/templates/VISPConfig.cmake.in index 58607a222e..b51ca8afa2 100644 --- a/cmake/templates/VISPConfig.cmake.in +++ b/cmake/templates/VISPConfig.cmake.in @@ -230,6 +230,7 @@ set(VISP_HAVE_LIBUSB_1 "@VISP_HAVE_LIBUSB_1@") set(VISP_HAVE_MAVSDK "@VISP_HAVE_MAVSDK@") set(VISP_HAVE_MKL "@VISP_HAVE_MKL@") set(VISP_HAVE_NETLIB "@VISP_HAVE_NETLIB@") +set(VISP_HAVE_NULLPTR "@VISP_HAVE_NULLPTR@") set(VISP_HAVE_OCCIPITAL_STRUCTURE "@VISP_HAVE_OCCIPITAL_STRUCTURE@") set(VISP_HAVE_OGRE "@VISP_HAVE_OGRE@") set(VISP_HAVE_OIS "@VISP_HAVE_OIS@") diff --git a/doc/config-doxygen.in b/doc/config-doxygen.in index 3dbcca0aaa..0f98afd95e 100644 --- a/doc/config-doxygen.in +++ b/doc/config-doxygen.in @@ -2390,6 +2390,7 @@ PREDEFINED = @DOXYGEN_SHOULD_SKIP_THIS@ \ VISP_HAVE_LIBUSB_1 \ VISP_HAVE_MAVSDK \ VISP_HAVE_NLOHMANN_JSON \ + VISP_HAVE_NULLPTR \ VISP_HAVE_OCCIPITAL_STRUCTURE \ VISP_HAVE_OGRE \ VISP_HAVE_OGRE_PLUGINS_PATH \ From c6e9adb8dbc5d24893613cb9b253c1b029805b6e Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 31 Jan 2024 16:55:22 +0100 Subject: [PATCH 07/12] Fixes for compat with cxx98 --- CMakeLists.txt | 22 ++++++++++- .../visp-compute-hand-eye-calibration.cpp | 4 ++ .../framegrabber/grabV4l2MultiCpp11Thread.cpp | 2 +- modules/core/include/visp3/core/vpIoTools.h | 5 ++- modules/core/src/tools/file/vpIoTools.cpp | 14 ++++++- .../core/test/image/testImageOwnership.cpp | 3 ++ modules/core/test/math/testMatrix.cpp | 2 + modules/io/include/visp3/io/vpImageQueue.h | 3 ++ .../include/visp3/io/vpImageStorageWorker.h | 3 ++ modules/io/src/image/private/vpImageIoStb.cpp | 13 +++++++ modules/io/src/image/vpImageIo.cpp | 8 ++++ .../mbt/src/depth/vpMbtFaceDepthDense.cpp | 4 +- .../mbt/src/depth/vpMbtFaceDepthNormal.cpp | 2 +- .../tracker/mbt/src/edge/vpMbEdgeTracker.cpp | 2 +- modules/tracker/mbt/src/vpMbTracker.cpp | 24 ++++++++++++ .../testGenericTracker.cpp | 6 +++ .../testGenericTrackerDepth.cpp | 8 +++- tutorial/image/tutorial-canny.cpp | 39 +++++++++++++++++++ .../hough-transform/tutorial-circle-hough.cpp | 12 ++++++ 19 files changed, 166 insertions(+), 10 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e9ab927636..18f9b81221 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -598,7 +598,7 @@ if(NOT USE_THREADS) endif() endif() -VP_OPTION(USE_XML2 XML2 "" "Include xml support" "" ON IF NOT WINRT) +VP_OPTION(USE_XML2 XML2 "" "Include libxml2 support" "" ON IF NOT WINRT) if(CMAKE_TOOLCHAIN_FILE) # Find opencv2.framework for ios and naoqi VP_OPTION(USE_OPENCV "MyOpenCV" QUIET "Include OpenCV support" "OpenCV_DIR;OpenCV_FOUND;OPENCV_FOUND" ON) @@ -680,6 +680,26 @@ if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_11) unset(USE_REALSENSE2) set(USE_REALSENSE2 OFF CACHE BOOL "Include librealsense2 support" FORCE) endif() + if(USE_XML2) + message(WARNING "libxml2 3rd party was detected and needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable libxml2 usage turning USE_XML2=OFF.") + unset(USE_XML2) + set(USE_XML2 OFF CACHE BOOL "Include libxml2 support" FORCE) + endif() + if(USE_QUALISYS) + message(WARNING "Qualisys SDK 3rd party was detected and needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable qualisys usage turning USE_QUALISYS=OFF.") + unset(USE_QUALISYS) + set(USE_QUALISYS OFF CACHE BOOL "Include Qualisys SDK support" FORCE) + endif() + if(USE_BICLOPS) + message(WARNING "Biclops SDK 3rd party was detected and needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable biclops usage turning USE_BICLOPS=OFF.") + unset(USE_BICLOPS) + set(USE_BICLOPS OFF CACHE BOOL "Include biclops support" FORCE) + endif() + if(USE_ARSDK) + message(WARNING "Parrot ARSDK 3rd party was detected and needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable ARSDK usage turning USE_ARSDK=OFF.") + unset(USE_ARSDK) + set(USE_ARSDK OFF CACHE BOOL "Include Parrot ARSDK support" FORCE) + endif() endif() # ---------------------------------------------------------------------------- diff --git a/apps/calibration/visp-compute-hand-eye-calibration.cpp b/apps/calibration/visp-compute-hand-eye-calibration.cpp index 1ed28ed68c..9e89402dab 100644 --- a/apps/calibration/visp-compute-hand-eye-calibration.cpp +++ b/apps/calibration/visp-compute-hand-eye-calibration.cpp @@ -188,7 +188,11 @@ int main(int argc, const char *argv[]) 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_98) std::ofstream file_eMc(name_we); +#else + std::ofstream file_eMc(name_we.c_str()); +#endif eMc.save(file_eMc); diff --git a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp index 0753400e97..32fc56ae73 100644 --- a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp +++ b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp @@ -45,7 +45,7 @@ #include -#if 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)) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include diff --git a/modules/core/include/visp3/core/vpIoTools.h b/modules/core/include/visp3/core/vpIoTools.h index f0b1210d93..76cafa88fd 100644 --- a/modules/core/include/visp3/core/vpIoTools.h +++ b/modules/core/include/visp3/core/vpIoTools.h @@ -55,6 +55,7 @@ #include #include +#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 namespace visp { // https://github.com/BinomialLLC/basis_universal/blob/ad9386a4a1cf2a248f7bbd45f543a7448db15267/encoder/basisu_miniz.h#L665 @@ -122,10 +123,9 @@ struct NpyArray size_t num_vals; }; -#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 using npz_t = std::map; VISP_EXPORT npz_t npz_load(std::string fname); -#endif + VISP_EXPORT char BigEndianTest(); VISP_EXPORT char map_type(const std::type_info &t); @@ -386,6 +386,7 @@ template std::vector create_npy_header(const std::vector VISP_CXX_STANDARD_98 #define USE_ZLIB_API 0 #if !USE_ZLIB_API @@ -329,7 +331,6 @@ visp::cnpy::NpyArray load_the_npz_array(FILE *fp, uint32_t compr_bytes, uint32_t return array; } -#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 /*! Load the specified \p fname filepath as arrays of data. This function is similar to the numpy.load function. @@ -387,7 +388,6 @@ visp::cnpy::npz_t visp::cnpy::npz_load(std::string fname) fclose(fp); return arrays; } -#endif /*! Load the specified \p varname array of data from the \p fname npz file. This function is similar to the @@ -468,6 +468,8 @@ visp::cnpy::NpyArray visp::cnpy::npy_load(std::string fname) return arr; } +#endif + std::string vpIoTools::baseName = ""; std::string vpIoTools::baseDir = ""; std::string vpIoTools::configFile = ""; @@ -2061,7 +2063,11 @@ 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_98 for (std::string::const_iterator it = input.cbegin(); it != input.cend(); it++) { +#else + for (std::string::const_iterator it = input.begin(); it != input.end(); it++) { +#endif out += std::tolower(*it); } return out; @@ -2078,7 +2084,11 @@ 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_98 for (std::string::const_iterator it = input.cbegin(); it != input.cend(); it++) { +#else + for (std::string::const_iterator it = input.begin(); it != input.end(); it++) { +#endif out += std::toupper(*it); } return out; diff --git a/modules/core/test/image/testImageOwnership.cpp b/modules/core/test/image/testImageOwnership.cpp index be80db7ead..ed08454cb5 100644 --- a/modules/core/test/image/testImageOwnership.cpp +++ b/modules/core/test/image/testImageOwnership.cpp @@ -138,6 +138,8 @@ 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)); @@ -156,6 +158,7 @@ int main(int /* argc */, const char ** /* argv */) } delete[] bitmap; } +#endif } catch (const std::exception &e) { std::cerr << "Exception: " << e.what() << std::endl; diff --git a/modules/core/test/math/testMatrix.cpp b/modules/core/test/math/testMatrix.cpp index f32ded2b3a..8e2cafff56 100644 --- a/modules/core/test/math/testMatrix.cpp +++ b/modules/core/test/math/testMatrix.cpp @@ -669,6 +669,7 @@ 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); @@ -683,6 +684,7 @@ int main(int argc, char *argv[]) res2 = A + B; std::cout << "\n2) A+B:\n" << res2 << std::endl; } +#endif { std::cout << "\n------------------------" << std::endl; diff --git a/modules/io/include/visp3/io/vpImageQueue.h b/modules/io/include/visp3/io/vpImageQueue.h index 8a8f9e318c..75381cd77a 100644 --- a/modules/io/include/visp3/io/vpImageQueue.h +++ b/modules/io/include/visp3/io/vpImageQueue.h @@ -36,6 +36,8 @@ #include +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + #include #include #include @@ -282,3 +284,4 @@ template class vpImageQueue }; #endif +#endif diff --git a/modules/io/include/visp3/io/vpImageStorageWorker.h b/modules/io/include/visp3/io/vpImageStorageWorker.h index a69fe16750..9fc16fab51 100644 --- a/modules/io/include/visp3/io/vpImageStorageWorker.h +++ b/modules/io/include/visp3/io/vpImageStorageWorker.h @@ -36,6 +36,8 @@ #include +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + #include #include @@ -132,3 +134,4 @@ template class vpImageStorageWorker }; #endif +#endif diff --git a/modules/io/src/image/private/vpImageIoStb.cpp b/modules/io/src/image/private/vpImageIoStb.cpp index 77ab6492b6..33dc4afa26 100644 --- a/modules/io/src/image/private/vpImageIoStb.cpp +++ b/modules/io/src/image/private/vpImageIoStb.cpp @@ -178,8 +178,13 @@ void readPNGfromMemStb(const std::vector &buffer, vpImage } else { STBI_FREE(buffer_read); + +#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 std::string message = "Wrong number of channels for the input buffer: " + std::to_string(comp); throw(vpImageException(vpImageException::ioError, message)); +#else + throw(vpImageException(vpImageException::ioError, "Wrong number of channels for the input buffer: %d", comp)); +#endif } STBI_FREE(buffer_read); @@ -209,8 +214,12 @@ void writePNGtoMemStb(const vpImage &I, std::vector VISP_CXX_STANDARD_98 std::string message = "Cannot write png to memory, result: " + std::to_string(result); throw(vpImageException(vpImageException::ioError, message)); +#else + throw(vpImageException(vpImageException::ioError, "Cannot write png to memory, result: %d", result)); +#endif } } @@ -249,8 +258,12 @@ void writePNGtoMemStb(const vpImage &I_color, std::vector buffer.resize(context.last_pos); } else { +#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 std::string message = "Cannot write png to memory, result: " + std::to_string(result); throw(vpImageException(vpImageException::ioError, message)); +#else + throw(vpImageException(vpImageException::ioError, "Cannot write png to memory, result: %d", result)); +#endif } } #endif diff --git a/modules/io/src/image/vpImageIo.cpp b/modules/io/src/image/vpImageIo.cpp index 9d388879e8..567969e0d3 100644 --- a/modules/io/src/image/vpImageIo.cpp +++ b/modules/io/src/image/vpImageIo.cpp @@ -1562,8 +1562,12 @@ void vpImageIo::writePNGtoMem(const vpImage &I, std::vector VISP_CXX_STANDARD_98 const std::string message = "The " + std::to_string(backend) + " backend is not available."; throw(vpImageException(vpImageException::ioError, message)); +#else + throw(vpImageException(vpImageException::ioError, "The %d backend is not available", backend)); +#endif } } @@ -1621,7 +1625,11 @@ void vpImageIo::writePNGtoMem(const vpImage &I, std::vector VISP_CXX_STANDARD_98 const std::string message = "The " + std::to_string(backend) + " backend is not available."; throw(vpImageException(vpImageException::ioError, message)); +#else + throw(vpImageException(vpImageException::ioError, "The %d backend is not available", backend)); +#endif } } diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp index 066b4817fb..c8f7e5db7d 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp @@ -81,7 +81,9 @@ #endif #if !USE_OPENCV_HAL && (USE_SSE || USE_NEON) +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include +#endif namespace { @@ -174,7 +176,7 @@ vpMbtFaceDepthDense::~vpMbtFaceDepthDense() Add a line belonging to the \f$ index \f$ the polygon to the list of lines. It is defined by its two extremities. - If the line already exists, the ploygone's index is added to the list of + If the line already exists, the polygon's index is added to the list of polygon to which it belongs. \param P1 : The first extremity of the line. diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp index de946581c5..6e36717e74 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp @@ -76,7 +76,7 @@ vpMbtFaceDepthNormal::~vpMbtFaceDepthNormal() Add a line belonging to the \f$ index \f$ the polygon to the list of lines. It is defined by its two extremities. - If the line already exists, the ploygone's index is added to the list of + If the line already exists, the polygon's index is added to the list of polygon to which it belongs. \param P1 : The first extremity of the line. diff --git a/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp b/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp index 914447f4da..4524da9981 100644 --- a/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp +++ b/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp @@ -1978,7 +1978,7 @@ void vpMbEdgeTracker::resetMovingEdge() Add a line belonging to the \f$ index \f$ the polygon to the list of lines. It is defined by its two extremities. - If the line already exists, the ploygone's index is added to the list of + If the line already exists, the polygon's index is added to the list of polygon to which it belongs. \param P1 : The first extremity of the line. diff --git a/modules/tracker/mbt/src/vpMbTracker.cpp b/modules/tracker/mbt/src/vpMbTracker.cpp index 3b39848dab..4f973fe94e 100644 --- a/modules/tracker/mbt/src/vpMbTracker.cpp +++ b/modules/tracker/mbt/src/vpMbTracker.cpp @@ -93,13 +93,17 @@ #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 /*! Structure to store info about segment in CAO model files. */ @@ -353,7 +357,11 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage } std::cout << "Load 3D points from: " << ss.str() << std::endl; +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) 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()); @@ -1830,7 +1838,9 @@ 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; } @@ -1877,7 +1887,9 @@ 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; } @@ -1957,7 +1969,9 @@ 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; } @@ -2044,7 +2058,9 @@ 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; } @@ -2115,7 +2131,9 @@ 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; } @@ -2195,7 +2213,9 @@ 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; } @@ -2258,7 +2278,9 @@ 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; @@ -2268,7 +2290,9 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) 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; diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp index bf51f2b0ac..0562bfde6d 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp @@ -46,7 +46,9 @@ #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 @@ -185,8 +187,10 @@ 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 @@ -254,8 +258,10 @@ 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; diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp index 234eeebc29..d331aacc41 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp @@ -45,7 +45,9 @@ #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 @@ -163,8 +165,10 @@ 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 @@ -228,9 +232,11 @@ 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!"); - // Initialise a display +#endif +// Initialise a display #if defined(VISP_HAVE_X11) vpDisplayX display1, display2; #elif defined(VISP_HAVE_GDI) diff --git a/tutorial/image/tutorial-canny.cpp b/tutorial/image/tutorial-canny.cpp index 94d1aab72e..993557ad53 100644 --- a/tutorial/image/tutorial-canny.cpp +++ b/tutorial/image/tutorial-canny.cpp @@ -83,13 +83,31 @@ void setGradientOutsideClass(const vpImage &I, const int &gaussia // Display the gradients float mean, max, stdev; computeMeanMaxStdev(dIx, mean, max, stdev); + +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::string title = "Gradient along the horizontal axis. Mean = " + std::to_string(mean) + "+/-" + std::to_string(stdev) + " Max = " + std::to_string(max); +#else + std::string title; + { + std::stringstream ss; + ss << "Gradient along the horizontal axis. Mean = " << mean<< "+/-" << stdev<< " Max = " << max; + title = ss.str(); + } +#endif vpImageConvert::convert(dIx, dIx_uchar); drawingHelpers::display(dIx_uchar, title); computeMeanMaxStdev(dIy, mean, max, stdev); +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) title = "Gradient along the horizontal axis. Mean = " + std::to_string(mean) + "+/-" + std::to_string(stdev) + " Max = " + std::to_string(max); +#else + { + std::stringstream ss; + ss << "Gradient along the horizontal axis. Mean = " << mean<< "+/-" << stdev<< " Max = " << max; + title = ss.str(); + } +#endif vpImageConvert::convert(dIy, dIy_uchar); drawingHelpers::display(dIy_uchar, title); } @@ -217,11 +235,23 @@ int main(int argc, const char *argv[]) std::string configAsTxt("Canny Configuration:\n"); configAsTxt += "\tFiltering + gradient operators = " + vpImageFilter::vpCannyFilteringAndGradientTypeToString(opt_filteringType) + "\n"; +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) configAsTxt += "\tGaussian filter kernel size = " + std::to_string(opt_gaussianKernelSize) + "\n"; configAsTxt += "\tGaussian filter standard deviation = " + std::to_string(opt_gaussianStdev) + "\n"; configAsTxt += "\tGradient filter kernel size = " + std::to_string(opt_apertureSize) + "\n"; configAsTxt += "\tCanny edge filter thresholds = [" + std::to_string(opt_lowerThresh) + " ; " + std::to_string(opt_upperThresh) + "]\n"; configAsTxt += "\tCanny edge filter thresholds ratio (for auto-thresholding) = [" + std::to_string(opt_lowerThreshRatio) + " ; " + std::to_string(opt_upperThreshRatio) + "]\n"; +#else + { + std::stringstream ss; + ss << "\tGaussian filter kernel size = " << opt_gaussianKernelSize << "\n"; + ss << "\tGaussian filter standard deviation = " << opt_gaussianStdev << "\n"; + ss << "\tGradient filter kernel size = " << opt_apertureSize << "\n"; + ss << "\tCanny edge filter thresholds = [" << opt_lowerThresh << " ; " << opt_upperThresh << "]\n"; + ss << "\tCanny edge filter thresholds ratio (for auto-thresholding) = [" << opt_lowerThreshRatio << " ; " << opt_upperThreshRatio << "]\n"; + configAsTxt += ss.str(); + } +#endif std::cout << configAsTxt << std::endl; vpCannyEdgeDetection cannyDetector(opt_gaussianKernelSize, opt_gaussianStdev, opt_apertureSize, @@ -264,7 +294,16 @@ int main(int argc, const char *argv[]) I_canny_visp = cannyDetector.detect(I_canny_input); float mean, max, stdev; computeMeanMaxStdev(I_canny_input, mean, max, stdev); +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::string title("Input of the Canny edge detector. Mean = " + std::to_string(mean) + "+/-" + std::to_string(stdev) + " Max = " + std::to_string(max)); +#else + std::string title; + { + std::stringstream ss; + ss << "Input of the Canny edge detector. Mean = " << mean << "+/-" << stdev << " Max = " << max; + title = ss.str(); + } +#endif drawingHelpers::display(I_canny_input, title); drawingHelpers::display(I_canny_visp, "Canny results on image " + opt_img); diff --git a/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp b/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp index 6b4effe999..090bd3d96c 100644 --- a/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp +++ b/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp @@ -314,7 +314,11 @@ int main(int argc, char **argv) << "\t [--upper-canny-ratio ]" << " (default: " << def_upperCannyThreshRatio << ")" << std::endl << "\t [--expected-nb-centers ]" +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) << " (default: " << (def_expectedNbCenters < 0 ? "no limits" : std::to_string(def_expectedNbCenters)) << ")" << std::endl +#else + << std::endl +#endif << "\t [--visibility-ratio-thresh ]" << " (default: " << def_visibilityRatioThresh << ")" << std::endl << "\t [--record-voting-points]" << std::endl @@ -430,12 +434,20 @@ int main(int argc, char **argv) << "\t--expected-nb-centers" << std::endl << "\t\tPermit to choose the maximum number of centers having more votes than the threshold that are kept." << std::endl << "\t\tA negative value makes that all the centers having more votes than the threshold are kept." << std::endl +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) << "\t\tDefault: " << (def_expectedNbCenters < 0 ? "no limits" : std::to_string(def_expectedNbCenters)) << std::endl +#else + << std::endl +#endif << std::endl << "\t--expected-nb-centers" << std::endl << "\t\tPermit to choose the maximum number of centers having more votes than the threshold that are kept." << std::endl << "\t\tA negative value makes that all the centers having more votes than the threshold are kept." << std::endl +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) << "\t\tDefault: " << (def_expectedNbCenters < 0 ? "no limits" : std::to_string(def_expectedNbCenters)) << std::endl +#else + << std::endl +#endif << std::endl << "\t--record-voting-points" << std::endl << "\t\tPermit to display the edge map used to detect the circles" << std::endl From a8719f193dd1a9d4898d973d9532b31c48d09afd Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 31 Jan 2024 17:07:19 +0100 Subject: [PATCH 08/12] Change strategy to detect cxx standard in order to better identify changes between cxx98 and cxx11 - When there is an alternative between cxx98 and cxx11 use VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 - When there is no alternative code in cxx 98 use rather VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 --- modules/core/include/visp3/core/vpException.h | 2 +- .../core/include/visp3/core/vpFrameGrabber.h | 2 +- .../core/include/visp3/core/vpRectOriented.h | 4 ++-- modules/core/include/visp3/core/vpTime.h | 3 +-- .../src/camera/vpColorDepthConversion.cpp | 10 +++++----- modules/core/src/tools/time/vpTime.cpp | 2 +- .../core/test/image/testImageOwnership.cpp | 2 +- modules/core/test/math/testMatrix.cpp | 2 +- .../visp3/detection/vpDetectorQRCode.h | 4 ---- .../imgproc/src/vpCircleHoughTransform.cpp | 20 +++++++++---------- .../testOccipitalStructure_Core_imu.cpp | 2 +- .../mbt/src/depth/vpMbtFaceDepthNormal.cpp | 4 ++-- .../mbt/src/edge/vpMbtDistanceCircle.cpp | 2 +- .../mbt/src/edge/vpMbtDistanceCylinder.cpp | 6 +++--- .../mbt/src/edge/vpMbtDistanceLine.cpp | 4 ++-- .../src/pose-estimation/vpPoseRansac.cpp | 2 +- 16 files changed, 33 insertions(+), 38 deletions(-) diff --git a/modules/core/include/visp3/core/vpException.h b/modules/core/include/visp3/core/vpException.h index 03f3965e4e..2047cab45e 100644 --- a/modules/core/include/visp3/core/vpException.h +++ b/modules/core/include/visp3/core/vpException.h @@ -104,7 +104,7 @@ class VISP_EXPORT vpException : public std::exception Basic destructor. Do nothing but implemented to fit the inheritance from std::exception */ -#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) virtual ~vpException() { } #else virtual ~vpException() throw() { } diff --git a/modules/core/include/visp3/core/vpFrameGrabber.h b/modules/core/include/visp3/core/vpFrameGrabber.h index b13fa3bd19..c92e2a6e33 100644 --- a/modules/core/include/visp3/core/vpFrameGrabber.h +++ b/modules/core/include/visp3/core/vpFrameGrabber.h @@ -111,7 +111,7 @@ class VISP_EXPORT vpFrameGrabber public: vpFrameGrabber() : init(false), height(0), width(0) { }; -#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) virtual ~vpFrameGrabber() = default; #else virtual ~vpFrameGrabber() { } diff --git a/modules/core/include/visp3/core/vpRectOriented.h b/modules/core/include/visp3/core/vpRectOriented.h index 517939dac5..241db96d97 100644 --- a/modules/core/include/visp3/core/vpRectOriented.h +++ b/modules/core/include/visp3/core/vpRectOriented.h @@ -47,7 +47,7 @@ class VISP_EXPORT vpRectOriented { public: vpRectOriented(); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) vpRectOriented(const vpRectOriented &rect) = default; #else vpRectOriented(const vpRectOriented &rect); @@ -57,7 +57,7 @@ class VISP_EXPORT vpRectOriented vpRectOriented(const vpRect &rect); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) vpRectOriented &operator=(const vpRectOriented &rect) = default; #else vpRectOriented &operator=(const vpRectOriented &rect); diff --git a/modules/core/include/visp3/core/vpTime.h b/modules/core/include/visp3/core/vpTime.h index 472b8bdd5b..78a3649b7f 100644 --- a/modules/core/include/visp3/core/vpTime.h +++ b/modules/core/include/visp3/core/vpTime.h @@ -93,8 +93,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 (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) && (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/src/camera/vpColorDepthConversion.cpp b/modules/core/src/camera/vpColorDepthConversion.cpp index 2b44d0211d..43fbc333e9 100644 --- a/modules/core/src/camera/vpColorDepthConversion.cpp +++ b/modules/core/src/camera/vpColorDepthConversion.cpp @@ -59,7 +59,7 @@ namespace */ vpImagePoint adjust2DPointToBoundary(const vpImagePoint &ip, double width, double height) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#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)); @@ -75,7 +75,7 @@ vpImagePoint adjust2DPointToBoundary(const vpImagePoint &ip, double width, doubl */ vpColVector transform(const vpHomogeneousMatrix &extrinsics_params, vpColVector from_point) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#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 }; @@ -95,7 +95,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_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) vpImagePoint iP {}; #else vpImagePoint iP; @@ -115,7 +115,7 @@ 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_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) double x { 0. }, y { 0. }; vpPixelMeterConversion::convertPoint(intrinsic_cam_params, pixel, x, y); return { x * depth, y * depth, depth }; @@ -179,7 +179,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_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) vpImagePoint depth_pixel {}; // Find line start pixel diff --git a/modules/core/src/tools/time/vpTime.cpp b/modules/core/src/tools/time/vpTime.cpp index 408f0c87ab..fd78ac22fa 100644 --- a/modules/core/src/tools/time/vpTime.cpp +++ b/modules/core/src/tools/time/vpTime.cpp @@ -39,7 +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 && \ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ (defined(_MSC_VER) && _MSC_VER >= 1900 /* VS2015 */ || !defined(_MSC_VER)) #define USE_CXX11_CHRONO 1 #else diff --git a/modules/core/test/image/testImageOwnership.cpp b/modules/core/test/image/testImageOwnership.cpp index ed08454cb5..9c3a1770b4 100644 --- a/modules/core/test/image/testImageOwnership.cpp +++ b/modules/core/test/image/testImageOwnership.cpp @@ -139,7 +139,7 @@ int main(int /* argc */, const char ** /* argv */) delete[] bitmap; } -#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { unsigned char *bitmap = new unsigned char[12]; vpImage I = std::move(vpImage(bitmap, 3, 4, false)); diff --git a/modules/core/test/math/testMatrix.cpp b/modules/core/test/math/testMatrix.cpp index 8e2cafff56..65f6f0b6c4 100644 --- a/modules/core/test/math/testMatrix.cpp +++ b/modules/core/test/math/testMatrix.cpp @@ -669,7 +669,7 @@ int main(int argc, char *argv[]) std::cout << "juxtaposeM:\n" << juxtaposeM << std::endl; } -#if VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11 +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) { std::vector vec_mat; vec_mat.emplace_back(5, 5); diff --git a/modules/detection/include/visp3/detection/vpDetectorQRCode.h b/modules/detection/include/visp3/detection/vpDetectorQRCode.h index 2369dc3ffe..654283a1d8 100644 --- a/modules/detection/include/visp3/detection/vpDetectorQRCode.h +++ b/modules/detection/include/visp3/detection/vpDetectorQRCode.h @@ -113,11 +113,7 @@ class VISP_EXPORT vpDetectorQRCode : public vpDetectorBase public: vpDetectorQRCode(); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) bool detect(const vpImage &I) vp_override; -#else - bool detect(const vpImage &I); -#endif }; #endif diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index 02a6464af7..19ae63040a 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -389,7 +389,7 @@ void vpCircleHoughTransform::computeVotingMask(const vpImage &I, *opt_votingPoints = new std::vector > >(); #endif -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) for (const auto &detection : detections) #else const size_t nbDetections = detections.size(); @@ -402,7 +402,7 @@ void vpCircleHoughTransform::computeVotingMask(const vpImage &I, // Looking for a circle that was detected and is similar to the one given to the function while ((id < nbPreviouslyDetected) && (!hasFoundSimilarCircle)) { vpImageCircle previouslyDetected = m_finalCircles[id]; -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) if (previouslyDetected == detection) #else if (previouslyDetected == detections[i]) @@ -889,14 +889,14 @@ vpCircleHoughTransform::computeCircleCandidates() radiusActualValueList.clear(); radiusActualValueList.resize(nbBins, 0.); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) for (auto edgePoint : m_edgePointsList) #else for (size_t e = 0; e < m_edgePointsList.size(); ++e) #endif { // For each center candidate CeC_i, compute the distance with each edge point EP_j d_ij = dist(CeC_i; EP_j) -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) float rx = edgePoint.second - centerCandidate.second; float ry = edgePoint.first - centerCandidate.first; #else @@ -905,7 +905,7 @@ vpCircleHoughTransform::computeCircleCandidates() #endif float r2 = (rx * rx) + (ry * ry); if ((r2 > rmin2) && (r2 < rmax2)) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) float gx = m_dIx[edgePoint.first][edgePoint.second]; float gy = m_dIy[edgePoint.first][edgePoint.second]; #else @@ -927,7 +927,7 @@ vpCircleHoughTransform::computeCircleCandidates() radiusAccumList[r_bin] += 1.f; radiusActualValueList[r_bin] += r; if (m_algoParams.m_recordVotingPoints) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) votingPoints[r_bin].push_back(edgePoint); #else votingPoints[r_bin].push_back(m_edgePointsList[e]); @@ -948,7 +948,7 @@ vpCircleHoughTransform::computeCircleCandidates() radiusAccumList[r_bin + 1] += voteNextBin; radiusActualValueList[r_bin + 1] += r * voteNextBin; if (m_algoParams.m_recordVotingPoints) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) votingPoints[r_bin].push_back(edgePoint); votingPoints[r_bin + 1].push_back(edgePoint); #else @@ -966,7 +966,7 @@ vpCircleHoughTransform::computeCircleCandidates() radiusAccumList[r_bin - 1] += votePrevBin; radiusActualValueList[r_bin - 1] += r * votePrevBin; if (m_algoParams.m_recordVotingPoints) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) votingPoints[r_bin].push_back(edgePoint); votingPoints[r_bin - 1].push_back(edgePoint); #else @@ -1016,7 +1016,7 @@ vpCircleHoughTransform::computeCircleCandidates() if (m_algoParams.m_recordVotingPoints) { // Move elements from votingPoints[idCandidate] to votingPoints_effective. // votingPoints[idCandidate] is left in undefined but safe-to-destruct state. -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) votingPoints_effective.insert( votingPoints_effective.end(), std::make_move_iterator(votingPoints[idCandidate].begin()), @@ -1150,7 +1150,7 @@ vpCircleHoughTransform::mergeCandidates(std::vector &circleCandid circleCandidatesProba[i] = newProba; circleCandidatesProba[j] = circleCandidatesProba[nbCandidates - 1]; if (m_algoParams.m_recordVotingPoints) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) votingPoints[i].insert( votingPoints[i].end(), std::make_move_iterator(votingPoints[j].begin()), diff --git a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp index 8e80daacec..57f4f386b1 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_STRUCTUR ) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp index 6e36717e74..aa69ae31d6 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp @@ -1699,7 +1699,7 @@ 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) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::vector params = { 2, //desired normal im_centroid.get_i(), im_centroid.get_j(), @@ -1739,7 +1739,7 @@ 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) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::vector params = { 3, //normal at current pose im_centroid.get_i(), im_centroid.get_j(), diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp index edd86cc12d..c0d6e8563a 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp @@ -321,7 +321,7 @@ 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) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::vector params = { 0, //ME p_me.get_ifloat(), p_me.get_jfloat(), diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp index ac273e55e3..3213e9b607 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp @@ -579,7 +579,7 @@ 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) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::vector params = { 0, //ME p_me.get_ifloat(), p_me.get_jfloat(), @@ -600,7 +600,7 @@ 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) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::vector params = { 0, //ME p_me.get_ifloat(), p_me.get_jfloat(), @@ -684,7 +684,7 @@ std::vector > vpMbtDistanceCylinder::getModelForDisplay(unsi ip21.set_ij(i21, j21); ip22.set_ij(i22, j22); -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::vector params1 = { 0, ip11.get_i(), ip11.get_j(), diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp index b51cf1547d..78ea9a7e93 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp @@ -705,7 +705,7 @@ std::vector > vpMbtDistanceLine::getFeaturesForDisplay() if (me_l != nullptr) { 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) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::vector params = { 0, //ME p_me_l.get_ifloat(), p_me_l.get_jfloat(), @@ -778,7 +778,7 @@ 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) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) std::vector params = { 0, //0 for line parameters ip1.get_i(), ip1.get_j(), diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index 500b6760b8..5eaef2c574 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -355,7 +355,7 @@ 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) +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) unsigned int nbThreads = 1; bool executeParallelVersion = useParallelRansac; #else From 38286441e6ea06c3d303f6053bd8e08ec3b3b6c6 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Thu, 1 Feb 2024 07:43:34 +0100 Subject: [PATCH 09/12] Fix nullptr detection with msvc --- cmake/AddExtraCompilationFlags.cmake | 2 +- cmake/VISPDetectCXXStandard.cmake | 6 ++++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/cmake/AddExtraCompilationFlags.cmake b/cmake/AddExtraCompilationFlags.cmake index de1baea4a0..0cec5eef4e 100644 --- a/cmake/AddExtraCompilationFlags.cmake +++ b/cmake/AddExtraCompilationFlags.cmake @@ -95,7 +95,7 @@ elseif(MSVC) endif() endif() -if(NOT VISP_HAVE_NULLPTR AND VISP_CXX_STANDARD EQUAL VISP_CXX_STANDARD_98) +if((NOT VISP_HAVE_NULLPTR) AND (VISP_CXX_STANDARD EQUAL VISP_CXX_STANDARD_98) AND (NOT MSVC)) add_extra_compiler_option("-Wno-c++11-compat") endif() diff --git a/cmake/VISPDetectCXXStandard.cmake b/cmake/VISPDetectCXXStandard.cmake index 1db6f2b962..950b1bee36 100644 --- a/cmake/VISPDetectCXXStandard.cmake +++ b/cmake/VISPDetectCXXStandard.cmake @@ -168,4 +168,10 @@ else() set(VISP_CXX_STANDARD ${VISP_CXX_STANDARD_17}) endif() endif() + + set(CMAKE_CXX_EXTENSIONS OFF) # use -std=c++11 instead of -std=gnu++11 + + # Additional check for nullptr that is available with clang but not with g++ when cxx98 standard is enabled + vp_check_compiler_flag(CXX "" HAVE_NULLPTR "${PROJECT_SOURCE_DIR}/cmake/checks/nullptr.cpp") + mark_as_advanced(HAVE_NULLPTR) endif() From ef03a1b81633b4aee4afec4d5456d7811759fc4a Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Thu, 1 Feb 2024 08:52:15 +0100 Subject: [PATCH 10/12] Fix wrong code auto indentation --- cmake/templates/vpConfig.h.in | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/templates/vpConfig.h.in b/cmake/templates/vpConfig.h.in index 9f8ab7efb5..45d8918a21 100644 --- a/cmake/templates/vpConfig.h.in +++ b/cmake/templates/vpConfig.h.in @@ -104,7 +104,7 @@ #define VISP_VERSION_PATCH ${VISP_VERSION_PATCH} // ViSP version with dots "${VISP_VERSION_MAJOR}.${VISP_VERSION_MINOR}.${VISP_VERSION_PATCH}". -#cmakedefine VISP_VERSION $ { VISP_VERSION } +#cmakedefine VISP_VERSION ${VISP_VERSION} // ViSP version as an integer #define VP_VERSION_INT(a, b, c) (a<<16 | b<<8 | c) @@ -115,7 +115,7 @@ // Enable debug and trace printings #cmakedefine VP_TRACE #cmakedefine VP_DEBUG -#cmakedefine VP_DEBUG_MODE $ { VP_DEBUG_MODE } +#cmakedefine VP_DEBUG_MODE ${VP_DEBUG_MODE} // ViSP library is either compiled static or shared // Used to set declspec(import, export) in headers if required under Windows From 34a4f31f96da367bcfa6ade71e29b55ba9497ed0 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Thu, 1 Feb 2024 09:23:42 +0100 Subject: [PATCH 11/12] Fix warnings detected with clang on windows --- modules/core/include/visp3/core/vpArray2D.h | 2 +- modules/core/include/visp3/core/vpException.h | 6 +- .../include/visp3/core/vpForceTwistMatrix.h | 2 +- modules/core/include/visp3/core/vpMath.h | 12 +-- .../core/include/visp3/core/vpPoseVector.h | 2 +- .../src/camera/vpPixelMeterConversion.cpp | 76 +++++++++++-------- 6 files changed, 55 insertions(+), 45 deletions(-) diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index 409c882ded..5847aca8db 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -156,7 +156,7 @@ template class vpArray2D #endif { resize(A.rowNum, A.colNum, false, false); - memcpy(data, A.data, (size_t)rowNum * (size_t)colNum * sizeof(Type)); + memcpy(data, A.data, static_cast(rowNum) * static_cast(colNum) * sizeof(Type)); } /*! diff --git a/modules/core/include/visp3/core/vpException.h b/modules/core/include/visp3/core/vpException.h index 2047cab45e..b42c2c541f 100644 --- a/modules/core/include/visp3/core/vpException.h +++ b/modules/core/include/visp3/core/vpException.h @@ -104,9 +104,7 @@ class VISP_EXPORT vpException : public std::exception Basic destructor. Do nothing but implemented to fit the inheritance from std::exception */ -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) - virtual ~vpException() { } -#else +#if (VISP_CXX_STANDARD == VISP_CXX_STANDARD_98) virtual ~vpException() throw() { } #endif /*! @@ -138,7 +136,7 @@ class VISP_EXPORT vpException : public std::exception * * \return pointer on the array of \e char related to the error string. */ - const char *what() const throw(); + const char *what() const vp_override throw(); //@} /*! diff --git a/modules/core/include/visp3/core/vpForceTwistMatrix.h b/modules/core/include/visp3/core/vpForceTwistMatrix.h index 8f01f4ce91..2f9270af95 100644 --- a/modules/core/include/visp3/core/vpForceTwistMatrix.h +++ b/modules/core/include/visp3/core/vpForceTwistMatrix.h @@ -195,7 +195,7 @@ class VISP_EXPORT vpForceTwistMatrix : public vpArray2D // copy operator from vpMatrix (handle with care) vpForceTwistMatrix &operator=(const vpForceTwistMatrix &H); - int print(std::ostream &s, unsigned int length, char const *intro = 0) const; + int print(std::ostream &s, unsigned int length, char const *intro = nullptr) const; /*! This function is not applicable to a velocity twist matrix that is always diff --git a/modules/core/include/visp3/core/vpMath.h b/modules/core/include/visp3/core/vpMath.h index 75727fbdd1..4b50e8ae9a 100644 --- a/modules/core/include/visp3/core/vpMath.h +++ b/modules/core/include/visp3/core/vpMath.h @@ -515,7 +515,7 @@ template <> inline unsigned char vpMath::saturate(unsigned int v) template <> inline unsigned char vpMath::saturate(float v) { - int iv = vpMath::round(v); + int iv = vpMath::round(static_cast(v)); return saturate(iv); } @@ -543,7 +543,7 @@ template <> inline char vpMath::saturate(int v) template <> inline char vpMath::saturate(short v) { - return saturate((int)v); + return saturate(static_cast(v)); } template <> inline char vpMath::saturate(unsigned int v) @@ -594,7 +594,7 @@ template <> inline unsigned short vpMath::saturate(unsigned int template <> inline unsigned short vpMath::saturate(float v) { - int iv = vpMath::round(v); + int iv = vpMath::round(static_cast(v)); return vpMath::saturate(iv); } @@ -619,7 +619,7 @@ template <> inline short vpMath::saturate(unsigned int v) } template <> inline short vpMath::saturate(float v) { - int iv = vpMath::round(v); + int iv = vpMath::round(static_cast(v)); return vpMath::saturate(iv); } template <> inline short vpMath::saturate(double v) @@ -631,7 +631,7 @@ template <> inline short vpMath::saturate(double v) // int template <> inline int vpMath::saturate(float v) { - return vpMath::round(v); + return vpMath::round(static_cast(v)); } template <> inline int vpMath::saturate(double v) @@ -644,7 +644,7 @@ template <> inline int vpMath::saturate(double v) // make -1 become 0xffffffff etc. template <> inline unsigned int vpMath::saturate(float v) { - return static_cast(vpMath::round(v)); + return static_cast(vpMath::round(static_cast(v))); } template <> inline unsigned int vpMath::saturate(double v) diff --git a/modules/core/include/visp3/core/vpPoseVector.h b/modules/core/include/visp3/core/vpPoseVector.h index 0491d38df4..b03a5a768c 100644 --- a/modules/core/include/visp3/core/vpPoseVector.h +++ b/modules/core/include/visp3/core/vpPoseVector.h @@ -279,7 +279,7 @@ class VISP_EXPORT vpPoseVector : public vpArray2D (void)ncols; (void)flagNullify; throw(vpException(vpException::fatalError, "Cannot resize a pose vector")); - }; + } // Save an homogeneous matrix in a file void save(std::ofstream &f) const; diff --git a/modules/core/src/camera/vpPixelMeterConversion.cpp b/modules/core/src/camera/vpPixelMeterConversion.cpp index ba0b8ac767..670e1cf131 100644 --- a/modules/core/src/camera/vpPixelMeterConversion.cpp +++ b/modules/core/src/camera/vpPixelMeterConversion.cpp @@ -134,35 +134,41 @@ void vpPixelMeterConversion::convertMoment(const vpCameraParameters &cam, unsign double yc = -cam.m_v0; double xc = -cam.m_u0; - for (unsigned int k = 0; k < order; k++) // iteration correspondant e l'ordre du moment - { - for (unsigned int p = 0; p < order; p++) // iteration en X - for (unsigned int q = 0; q < order; q++) // iteration en Y - if (p + q == k) // on est bien dans la matrice triangulaire superieure - { + for (unsigned int k = 0; k < order; k++) { // iteration correspondant e l'ordre du moment + for (unsigned int p = 0; p < order; p++) { // iteration en X + for (unsigned int q = 0; q < order; q++) { // iteration en Y + if (p + q == k) { // on est bien dans la matrice triangulaire superieure m[p][q] = 0; // initialisation e 0 - for (unsigned int r = 0; r <= p; r++) // somme externe - for (unsigned int t = 0; t <= q; t++) // somme interne - { + for (unsigned int r = 0; r <= p; r++) { // somme externe + for (unsigned int t = 0; t <= q; t++) { // somme interne m[p][q] += static_cast(vpMath::comb(p, r)) * static_cast(vpMath::comb(q, t)) * - pow(xc, (int)(p - r)) * pow(yc, (int)(q - t)) * moment_pixel[r][t]; + pow(xc, static_cast(p - r)) * pow(yc, static_cast(q - t)) * moment_pixel[r][t]; } + } } + } + } } - for (unsigned int k = 0; k < order; k++) // iteration correspondant e l'ordre du moment - for (unsigned int p = 0; p < order; p++) - for (unsigned int q = 0; q < order; q++) + for (unsigned int k = 0; k < order; k++) { // iteration correspondant e l'ordre du moment + for (unsigned int p = 0; p < order; p++) { + for (unsigned int q = 0; q < order; q++) { if (p + q == k) { - m[p][q] *= pow(cam.m_inv_px, (int)(1 + p)) * pow(cam.m_inv_py, (int)(1 + q)); + m[p][q] *= pow(cam.m_inv_px, static_cast(1 + p)) * pow(cam.m_inv_py, static_cast(1 + q)); } + } + } + } - for (unsigned int k = 0; k < order; k++) // iteration correspondant e l'ordre du moment - for (unsigned int p = 0; p < order; p++) - for (unsigned int q = 0; q < order; q++) + for (unsigned int k = 0; k < order; k++) { // iteration correspondant e l'ordre du moment + for (unsigned int p = 0; p < order; p++) { + for (unsigned int q = 0; q < order; q++) { if (p + q == k) { moment_meter[p][q] = m[p][q]; } + } + } + } } #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_CALIB3D) && defined(HAVE_OPENCV_IMGPROC) @@ -243,35 +249,41 @@ void vpPixelMeterConversion::convertMoment(const cv::Mat &cameraMatrix, unsigned double yc = -v0; double xc = -u0; - for (unsigned int k = 0; k < order; k++) // iteration correspondant e l'ordre du moment - { - for (unsigned int p = 0; p < order; p++) // iteration en X - for (unsigned int q = 0; q < order; q++) // iteration en Y - if (p + q == k) // on est bien dans la matrice triangulaire superieure - { + for (unsigned int k = 0; k < order; k++) { // iteration correspondant e l'ordre du moment + for (unsigned int p = 0; p < order; p++) { // iteration en X + for (unsigned int q = 0; q < order; q++) { // iteration en Y + if (p + q == k) { // on est bien dans la matrice triangulaire superieure m[p][q] = 0; // initialisation e 0 - for (unsigned int r = 0; r <= p; r++) // somme externe - for (unsigned int t = 0; t <= q; t++) // somme interne - { + for (unsigned int r = 0; r <= p; r++) { // somme externe + for (unsigned int t = 0; t <= q; t++) { // somme interne m[p][q] += static_cast(vpMath::comb(p, r)) * static_cast(vpMath::comb(q, t)) * pow(xc, static_cast(p - r)) * pow(yc, static_cast(q - t)) * moment_pixel[r][t]; } + } } + } + } } - for (unsigned int k = 0; k < order; k++) // iteration correspondant e l'ordre du moment - for (unsigned int p = 0; p < order; p++) - for (unsigned int q = 0; q < order; q++) + for (unsigned int k = 0; k < order; k++) { // iteration correspondant e l'ordre du moment + for (unsigned int p = 0; p < order; p++) { + for (unsigned int q = 0; q < order; q++) { if (p + q == k) { m[p][q] *= pow(inv_px, static_cast(1 + p)) * pow(inv_py, static_cast(1 + q)); } + } + } + } - for (unsigned int k = 0; k < order; k++) // iteration correspondant e l'ordre du moment - for (unsigned int p = 0; p < order; p++) - for (unsigned int q = 0; q < order; q++) + for (unsigned int k = 0; k < order; k++) { // iteration correspondant e l'ordre du moment + for (unsigned int p = 0; p < order; p++) { + for (unsigned int q = 0; q < order; q++) { if (p + q == k) { moment_meter[p][q] = m[p][q]; } + } + } + } } /*! From 6e4c53e37f916b8eccbb5a9136c7483ef6caaaf9 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Thu, 1 Feb 2024 13:56:48 +0100 Subject: [PATCH 12/12] Revert changes in vpException using vp_override that breaks the build on ubuntu --- modules/core/include/visp3/core/vpException.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/core/include/visp3/core/vpException.h b/modules/core/include/visp3/core/vpException.h index b42c2c541f..0eedfb374c 100644 --- a/modules/core/include/visp3/core/vpException.h +++ b/modules/core/include/visp3/core/vpException.h @@ -136,7 +136,7 @@ class VISP_EXPORT vpException : public std::exception * * \return pointer on the array of \e char related to the error string. */ - const char *what() const vp_override throw(); + const char *what() const throw(); //@} /*!