diff --git a/.vscode/settings.json b/.vscode/settings.json index 8536ebc9b7..fdb73f9c6c 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -117,7 +117,27 @@ "stop_token": "cpp", "view": "cpp", "mixinvector": "cpp", - "charconv": "cpp" + "charconv": "cpp", + "coroutine": "cpp", + "resumable": "cpp", + "format": "cpp", + "ranges": "cpp", + "span": "cpp", + "xfacet": "cpp", + "xhash": "cpp", + "xiosbase": "cpp", + "xlocale": "cpp", + "xlocbuf": "cpp", + "xlocinfo": "cpp", + "xlocmes": "cpp", + "xlocmon": "cpp", + "xlocnum": "cpp", + "xloctime": "cpp", + "xmemory": "cpp", + "xstring": "cpp", + "xtr1common": "cpp", + "xtree": "cpp", + "xutility": "cpp" }, "C_Cpp.vcFormat.indent.namespaceContents": false, "editor.formatOnSave": true, diff --git a/3rdparty/simdlib/Simd/SimdAlignment.h b/3rdparty/simdlib/Simd/SimdAlignment.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAllocator.hpp b/3rdparty/simdlib/Simd/SimdAllocator.hpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdArray.h b/3rdparty/simdlib/Simd/SimdArray.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx1.h b/3rdparty/simdlib/Simd/SimdAvx1.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx1Cpu.cpp b/3rdparty/simdlib/Simd/SimdAvx1Cpu.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx1Resizer.cpp b/3rdparty/simdlib/Simd/SimdAvx1Resizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2.h b/3rdparty/simdlib/Simd/SimdAvx2.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgrToBgra.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgrToBgra.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgrToGray.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgrToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgrToRgb.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgrToRgb.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgraToBgr.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgraToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgraToGray.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgraToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2Cpu.cpp b/3rdparty/simdlib/Simd/SimdAvx2Cpu.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2Deinterleave.cpp b/3rdparty/simdlib/Simd/SimdAvx2Deinterleave.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2GaussianBlur.cpp b/3rdparty/simdlib/Simd/SimdAvx2GaussianBlur.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2Reduce.cpp b/3rdparty/simdlib/Simd/SimdAvx2Reduce.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ReduceGray2x2.cpp b/3rdparty/simdlib/Simd/SimdAvx2ReduceGray2x2.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ReduceGray3x3.cpp b/3rdparty/simdlib/Simd/SimdAvx2ReduceGray3x3.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ReduceGray4x4.cpp b/3rdparty/simdlib/Simd/SimdAvx2ReduceGray4x4.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ReduceGray5x5.cpp b/3rdparty/simdlib/Simd/SimdAvx2ReduceGray5x5.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ResizeBilinear.cpp b/3rdparty/simdlib/Simd/SimdAvx2ResizeBilinear.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2Resizer.cpp b/3rdparty/simdlib/Simd/SimdAvx2Resizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBase.h b/3rdparty/simdlib/Simd/SimdBase.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgrToBgra.cpp b/3rdparty/simdlib/Simd/SimdBaseBgrToBgra.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgrToGray.cpp b/3rdparty/simdlib/Simd/SimdBaseBgrToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgrToRgb.cpp b/3rdparty/simdlib/Simd/SimdBaseBgrToRgb.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgraToBgr.cpp b/3rdparty/simdlib/Simd/SimdBaseBgraToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgraToGray.cpp b/3rdparty/simdlib/Simd/SimdBaseBgraToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseCpu.cpp b/3rdparty/simdlib/Simd/SimdBaseCpu.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseDeinterleave.cpp b/3rdparty/simdlib/Simd/SimdBaseDeinterleave.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseGaussianBlur.cpp b/3rdparty/simdlib/Simd/SimdBaseGaussianBlur.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseResizer.cpp b/3rdparty/simdlib/Simd/SimdBaseResizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdConfig.h b/3rdparty/simdlib/Simd/SimdConfig.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdConst.h b/3rdparty/simdlib/Simd/SimdConst.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdConversion.h b/3rdparty/simdlib/Simd/SimdConversion.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdCopyPixel.h b/3rdparty/simdlib/Simd/SimdCopyPixel.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdCpu.h b/3rdparty/simdlib/Simd/SimdCpu.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdDefs.h b/3rdparty/simdlib/Simd/SimdDefs.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdEnable.h b/3rdparty/simdlib/Simd/SimdEnable.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdExp.h b/3rdparty/simdlib/Simd/SimdExp.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdExtract.h b/3rdparty/simdlib/Simd/SimdExtract.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdFrame.hpp b/3rdparty/simdlib/Simd/SimdFrame.hpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdInit.h b/3rdparty/simdlib/Simd/SimdInit.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLib.cpp b/3rdparty/simdlib/Simd/SimdLib.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLib.h b/3rdparty/simdlib/Simd/SimdLib.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLib.hpp b/3rdparty/simdlib/Simd/SimdLib.hpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLoad.h b/3rdparty/simdlib/Simd/SimdLoad.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLoadBlock.h b/3rdparty/simdlib/Simd/SimdLoadBlock.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLog.h b/3rdparty/simdlib/Simd/SimdLog.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdMath.h b/3rdparty/simdlib/Simd/SimdMath.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdMemory.h b/3rdparty/simdlib/Simd/SimdMemory.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeon.h b/3rdparty/simdlib/Simd/SimdNeon.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgrToBgra.cpp b/3rdparty/simdlib/Simd/SimdNeonBgrToBgra.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgrToGray.cpp b/3rdparty/simdlib/Simd/SimdNeonBgrToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgrToRgb.cpp b/3rdparty/simdlib/Simd/SimdNeonBgrToRgb.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgraToBgr.cpp b/3rdparty/simdlib/Simd/SimdNeonBgraToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgraToGray.cpp b/3rdparty/simdlib/Simd/SimdNeonBgraToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonDeinterleave.cpp b/3rdparty/simdlib/Simd/SimdNeonDeinterleave.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonGaussianBlur.cpp b/3rdparty/simdlib/Simd/SimdNeonGaussianBlur.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonResizer.cpp b/3rdparty/simdlib/Simd/SimdNeonResizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdPixel.hpp b/3rdparty/simdlib/Simd/SimdPixel.hpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdPow.h b/3rdparty/simdlib/Simd/SimdPow.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdResizer.h b/3rdparty/simdlib/Simd/SimdResizer.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdResizerCommon.h b/3rdparty/simdlib/Simd/SimdResizerCommon.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdRuntime.h b/3rdparty/simdlib/Simd/SimdRuntime.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSet.h b/3rdparty/simdlib/Simd/SimdSet.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41.h b/3rdparty/simdlib/Simd/SimdSse41.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41BgrToBgra.cpp b/3rdparty/simdlib/Simd/SimdSse41BgrToBgra.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41BgrToGray.cpp b/3rdparty/simdlib/Simd/SimdSse41BgrToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41BgrToRgb.cpp b/3rdparty/simdlib/Simd/SimdSse41BgrToRgb.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41BgraToBgr.cpp b/3rdparty/simdlib/Simd/SimdSse41BgraToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41Cpu.cpp b/3rdparty/simdlib/Simd/SimdSse41Cpu.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41GaussianBlur.cpp b/3rdparty/simdlib/Simd/SimdSse41GaussianBlur.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41GrayToBgr.cpp b/3rdparty/simdlib/Simd/SimdSse41GrayToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41Reduce.cpp b/3rdparty/simdlib/Simd/SimdSse41Reduce.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41ReduceGray2x2.cpp b/3rdparty/simdlib/Simd/SimdSse41ReduceGray2x2.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41ReduceGray4x4.cpp b/3rdparty/simdlib/Simd/SimdSse41ReduceGray4x4.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41ResizeBilinear.cpp b/3rdparty/simdlib/Simd/SimdSse41ResizeBilinear.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41Resizer.cpp b/3rdparty/simdlib/Simd/SimdSse41Resizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdStore.h b/3rdparty/simdlib/Simd/SimdStore.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdStream.h b/3rdparty/simdlib/Simd/SimdStream.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdUpdate.h b/3rdparty/simdlib/Simd/SimdUpdate.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdView.hpp b/3rdparty/simdlib/Simd/SimdView.hpp old mode 100755 new mode 100644 diff --git a/CMakeLists.txt b/CMakeLists.txt index 18f9b81221..c6219b9913 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -586,17 +586,7 @@ if(SOQT_FOUND) # SoQt < 1.6.0 that depends on Qt4 was found. We need an explicit VP_OPTION(USE_QT Qt "" "Include Coin/SoQt/Qt support" "" ON IF USE_SOQT AND NOT WINRT AND NOT IOS) endif() VP_OPTION(USE_SOXT SOXT "" "Include Coin/SoXt support" "" OFF IF USE_COIN3D AND NOT WINRT AND NOT IOS) -set(THREADS_PREFER_PTHREAD_FLAG ON) -VP_OPTION(USE_THREADS Threads "" "Include std::thread support" "" ON IF NOT (WIN32 OR MINGW)) - -# We need threads. To be changed to make threads optional -if(NOT USE_THREADS) - if(Threads_FOUND) - message(WARNING "We need std::thread. We turn USE_THREADS=ON.") - unset(USE_THREADS) - set(USE_THREADS ON CACHE BOOL "Include std::thread support" FORCE) - endif() -endif() +VP_OPTION(USE_THREADS Threads "" "Include std::thread support" "" ON) VP_OPTION(USE_XML2 XML2 "" "Include libxml2 support" "" ON IF NOT WINRT) if(CMAKE_TOOLCHAIN_FILE) @@ -613,7 +603,7 @@ VP_OPTION(USE_X11 X11 "" "Include X11 support" "${X1 VP_OPTION(USE_GTK2 MyGTK2 "" "Include gtk2 support" "" OFF IF NOT WINRT AND NOT IOS) VP_OPTION(USE_JPEG "JPEG;MyJPEG" "" "Include jpeg support" "" ON IF NOT IOS) VP_OPTION(USE_PNG "PNG;MyPNG" "" "Include png support" "" ON IF NOT IOS) -# To control Pioneer mobile robots, under UNIX we need Aria, pthread, rt and dl 3rd party libraries +# To control Pioneer mobile robots, under UNIX we need Aria and std::threads, rt and dl 3rd party libraries VP_OPTION(USE_ARIA ARIA "" "Include aria support" "" ON IF NOT WINRT AND NOT IOS) #VP_OPTION(USE_RT RT "" "Include rt support" "" ON) #VP_OPTION(USE_DL DL "" "Include dl support" "" ON) @@ -624,7 +614,6 @@ VP_OPTION(USE_PCL PCL QUIET "Include Point Cloud Library suppor 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) -# Upgrade c++ standard to 14 for pcl 1.9.1.99 that enables by default c++ 14 standard if(USE_PCL) # PCL is used in modules gui, sensor and mbt. # In these modules we cannot directly use PCL_INCLUDE_DIRS and PCL_LIBRARIES using: @@ -705,7 +694,7 @@ endif() # ---------------------------------------------------------------------------- # Build-in 3rd parties. Should be after c++ standard potential modification # ---------------------------------------------------------------------------- -VP_OPTION(WITH_PTHREAD "" "" "Build pthread as built-in library" "" ON IF (NOT USE_THREADS) AND (WIN32 OR MINGW) AND (NOT WINRT)) +VP_OPTION(WITH_PTHREAD "" "" "Build pthread as built-in library" "" ON IF (WIN32 OR MINGW) AND (NOT WINRT)) # Since C99 is not supported by MSVC 2010 or prior, we disable apriltag if MSVC < 2012 VP_OPTION(WITH_APRILTAG "" "" "Build AprilTag as built-in library" "" ON IF (USE_THREADS OR WITH_PTHREAD) AND (NOT WINRT) AND (NOT MSVC_VERSION LESS 1700)) VP_OPTION(WITH_APRILTAG_BIG_FAMILY "" "" "Build AprilTag big family (41h12, 48h12, 49h12, 52h13)" "" OFF IF WITH_APRILTAG) diff --git a/apps/calibration/hand_eye_calibration_show_extrinsics.py b/apps/calibration/hand_eye_calibration_show_extrinsics.py old mode 100755 new mode 100644 diff --git a/cmake/templates/visp-config.bat.in b/cmake/templates/visp-config.bat.in old mode 100755 new mode 100644 diff --git a/cmake/templates/visp-config.in b/cmake/templates/visp-config.in old mode 100755 new mode 100644 diff --git a/cmake/templates/visp-config.install.in b/cmake/templates/visp-config.install.in old mode 100755 new mode 100644 diff --git a/cmake/templates/vpConfig.h.in b/cmake/templates/vpConfig.h.in index 45d8918a21..807d5db374 100644 --- a/cmake/templates/vpConfig.h.in +++ b/cmake/templates/vpConfig.h.in @@ -146,7 +146,7 @@ // Defined if XML2 library available. #cmakedefine VISP_HAVE_XML2 -// Defined if pthread library available. +// Defined if pthread library available (deprecated). #cmakedefine VISP_HAVE_PTHREAD // Defined if std::thread available. diff --git a/doc/image/tutorial/started/img-monkey-win.jpg b/doc/image/tutorial/started/img-monkey-win.jpg old mode 100755 new mode 100644 diff --git a/doc/image/tutorial/visual-servo/img-bebop2-coord-system.png b/doc/image/tutorial/visual-servo/img-bebop2-coord-system.png old mode 100755 new mode 100644 diff --git a/example/calibration/camera_calibration_show_extrinsics.py b/example/calibration/camera_calibration_show_extrinsics.py old mode 100755 new mode 100644 diff --git a/example/device/framegrabber/CMakeLists.txt b/example/device/framegrabber/CMakeLists.txt index 4879b1fabf..535c4e9d80 100644 --- a/example/device/framegrabber/CMakeLists.txt +++ b/example/device/framegrabber/CMakeLists.txt @@ -48,7 +48,6 @@ set(example_cpp grabDirectShow.cpp grabDirectShowMulti.cpp grabFlyCapture.cpp - grabRealSense.cpp grabRealSense2.cpp grabRealSense2_T265.cpp grabV4l2MultiCpp11Thread.cpp @@ -83,7 +82,6 @@ if(VISP_HAVE_REALSENSE OR VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") visp_set_source_file_compile_flag(getRealSense2Info.cpp ${CXX_FLAGS_MUTE_WARNINGS}) - visp_set_source_file_compile_flag(grabRealSense.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(grabRealSense2.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(grabRealSense2_T265.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(readRealSenseData.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/example/device/framegrabber/grabRealSense.cpp b/example/device/framegrabber/grabRealSense.cpp deleted file mode 100644 index 1c5a6bcc99..0000000000 --- a/example/device/framegrabber/grabRealSense.cpp +++ /dev/null @@ -1,259 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 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. - * - * Description: - * Test RealSense RGB-D sensor. - * -*****************************************************************************/ - -/*! - \example grabRealSense.cpp - This example shows how to retrieve data from a RealSense RGB-D sensor. - -*/ - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(VISP_HAVE_REALSENSE) - -// Using a thread to display the pointcloud with PCL produces a segfault on -// OSX -#if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX -#if (defined(VISP_HAVE_PTHREAD) || defined(_WIN32)) // Threading available -#define USE_THREAD -#endif -#endif - -#ifdef VISP_HAVE_PCL -#include -#include -#endif - -#ifdef VISP_HAVE_PCL -#ifdef USE_THREAD -// Shared vars -typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; -t_CaptureState s_capture_state = capture_waiting; -vpMutex s_mutex_capture; - -vpThread::Return displayPointcloudFunction(vpThread::Args args) -{ - pcl::PointCloud::Ptr pointcloud_ = *((pcl::PointCloud::Ptr *)args); - - pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer")); - pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud_); - viewer->setBackgroundColor(0, 0, 0); - viewer->initCameraParameters(); - viewer->setPosition(640 + 80, 480 + 80); - viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0); - viewer->setSize(640, 480); - - t_CaptureState capture_state_; - - do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); - - if (capture_state_ == capture_started) { - static bool update = false; - if (!update) { - viewer->addPointCloud(pointcloud_, rgb, "sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); - update = true; - } - else { - viewer->updatePointCloud(pointcloud_, rgb, "sample cloud"); - } - - viewer->spinOnce(10); - } - } while (capture_state_ != capture_stopped); - - std::cout << "End of point cloud display thread" << std::endl; - return EXIT_SUCCESS; -} -#endif -#endif -#endif - -int main() -{ -#if defined(VISP_HAVE_REALSENSE) - try { - vpRealSense rs; - rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30)); - rs.open(); - - std::cout << rs.getCameraParameters(rs::stream::color, vpCameraParameters::perspectiveProjWithoutDistortion) - << std::endl; - std::cout << rs.getCameraParameters(rs::stream::color, vpCameraParameters::perspectiveProjWithDistortion) - << std::endl; - std::cout << "Extrinsics cMd: \n" << rs.getTransformation(rs::stream::color, rs::stream::depth) << std::endl; - std::cout << "Extrinsics dMc: \n" << rs.getTransformation(rs::stream::depth, rs::stream::color) << std::endl; - std::cout << "Extrinsics cMi: \n" << rs.getTransformation(rs::stream::color, rs::stream::infrared) << std::endl; - std::cout << "Extrinsics dMi: \n" << rs.getTransformation(rs::stream::depth, rs::stream::infrared) << std::endl; - - vpImage color((unsigned int)rs.getIntrinsics(rs::stream::color).height, - (unsigned int)rs.getIntrinsics(rs::stream::color).width); - - vpImage infrared_display((unsigned int)rs.getIntrinsics(rs::stream::infrared).height, - (unsigned int)rs.getIntrinsics(rs::stream::infrared).width); - vpImage infrared_y16; - rs::device *dev = rs.getHandler(); - bool use_infrared_y16 = dev->get_stream_format(rs::stream::infrared) == rs::format::y16; - - vpImage depth_display((unsigned int)rs.getIntrinsics(rs::stream::depth).height, - (unsigned int)rs.getIntrinsics(rs::stream::depth).width); - vpImage depth(depth_display.getHeight(), depth_display.getWidth()); - -#ifdef VISP_HAVE_PCL - pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud); - -#ifdef USE_THREAD - vpThread thread_display_pointcloud(displayPointcloudFunction, (vpThread::Args)&pointcloud); -#else - pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer")); - pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud); - viewer->setBackgroundColor(0, 0, 0); - viewer->addCoordinateSystem(1.0); - viewer->initCameraParameters(); - viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0); -#endif - -#else - std::vector pointcloud; -#endif - -#if defined(VISP_HAVE_X11) - vpDisplayX dc(color, 10, 10, "Color image"); - vpDisplayX di(infrared_display, (int)color.getWidth() + 80, 10, "Infrared image"); - vpDisplayX dd(depth_display, 10, (int)color.getHeight() + 80, "Depth image"); -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI dc(color, 10, 10, "Color image"); - vpDisplayGDI di(infrared_display, color.getWidth() + 80, 10, "Infrared image"); - vpDisplayGDI dd(depth_display, 10, color.getHeight() + 80, "Depth image"); -#else - std::cout << "No image viewer is available..." << std::endl; -#endif - - while (1) { - double t = vpTime::measureTimeMs(); - - if (use_infrared_y16) { - rs.acquire(color, infrared_y16, depth, pointcloud); - vpImageConvert::convert(infrared_y16, infrared_display); - } - else { -#ifdef VISP_HAVE_PCL - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)infrared_display.bitmap); -#else - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)infrared_display.bitmap); -#endif - } - -#ifdef VISP_HAVE_PCL -#ifdef USE_THREAD - { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_started; - } -#else - static bool update = false; - if (!update) { - viewer->addPointCloud(pointcloud, rgb, "sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); - viewer->setPosition(color.getWidth() + 80, color.getHeight() + 80); - update = true; - } - else { - viewer->updatePointCloud(pointcloud, rgb, "sample cloud"); - } - - viewer->spinOnce(10); -#endif -#endif - - vpImageConvert::createDepthHistogram(depth, depth_display); - - vpDisplay::display(color); - vpDisplay::display(infrared_display); - vpDisplay::display(depth_display); - - vpDisplay::displayText(color, 15, 15, "Click to quit", vpColor::red); - if (vpDisplay::getClick(color, false) || vpDisplay::getClick(infrared_display, false) || - vpDisplay::getClick(depth_display, false)) { - break; - } - vpDisplay::flush(color); - vpDisplay::flush(infrared_display); - vpDisplay::flush(depth_display); - - std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl; - } - - std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; - -#ifdef VISP_HAVE_PCL -#ifdef USE_THREAD - { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; - } -#endif -#endif - - rs.close(); - } - catch (const vpException &e) { - std::cerr << "RealSense error " << e.what() << std::endl; - } - catch (const rs::error &e) { - std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() - << "): " << e.what() << std::endl; - } - catch (const std::exception &e) { - std::cerr << e.what() << std::endl; - } - -#elif !defined(VISP_HAVE_REALSENSE) - std::cout << "This deprecated example is only working with librealsense 1.x" << std::endl; -#endif - return EXIT_SUCCESS; -} diff --git a/example/device/framegrabber/grabRealSense2.cpp b/example/device/framegrabber/grabRealSense2.cpp index 6d2b7a4bdd..19f3f5bd15 100644 --- a/example/device/framegrabber/grabRealSense2.cpp +++ b/example/device/framegrabber/grabRealSense2.cpp @@ -44,10 +44,9 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ - && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) -#ifdef VISP_HAVE_PCL +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) #include #include @@ -180,7 +179,7 @@ int main() (unsigned int)rs.getIntrinsics(RS2_STREAM_DEPTH).width); vpImage depth(depth_display.getHeight(), depth_display.getWidth()); -#ifdef VISP_HAVE_PCL +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) std::mutex mutex; ViewerWorker viewer(true, mutex); std::thread viewer_thread(&ViewerWorker::run, &viewer); @@ -199,7 +198,7 @@ int main() while (true) { double t = vpTime::measureTimeMs(); -#ifdef VISP_HAVE_PCL +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) { std::lock_guard lock(mutex); rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, @@ -230,7 +229,7 @@ int main() std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; -#ifdef VISP_HAVE_PCL +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) { std::lock_guard lock(mutex); cancelled = true; @@ -253,7 +252,7 @@ int main() int main() { #if !defined(VISP_HAVE_REALSENSE2) - std::cout << "You do not realsense2 SDK functionality enabled..." << std::endl; + std::cout << "You do not have realsense2 SDK functionality enabled..." << std::endl; std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; diff --git a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp index 32fc56ae73..2f4333cc31 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)) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_V4L2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) && defined(VISP_HAVE_THREADS) #include #include diff --git a/example/device/framegrabber/readRealSenseData.cpp b/example/device/framegrabber/readRealSenseData.cpp index d7ad1c9336..5fe2cda11e 100644 --- a/example/device/framegrabber/readRealSenseData.cpp +++ b/example/device/framegrabber/readRealSenseData.cpp @@ -40,7 +40,7 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include #include @@ -71,27 +71,27 @@ namespace void usage(const char *name, const char *badparam) { fprintf(stdout, "\n\ - Read RealSense data.\n\ - \n\ - %s\ - OPTIONS: \n\ - -i \n\ - Input directory.\n\ - \n\ - -c \n\ - Click enable.\n\ - \n\ - -b \n\ - Pointcloud is in binary format.\n\ - \n\ - -o \n\ - Save color and depth side by side to image sequence.\n\ - \n\ - -d \n\ - Display depth in color.\n\ - \n\ - -h \n\ - Print the help.\n\n", + Read RealSense data.\n\ + \n\ + %s\ + OPTIONS: \n\ + -i \n\ + Input directory.\n\ + \n\ + -c \n\ + Click enable.\n\ + \n\ + -b \n\ + Pointcloud is in binary format.\n\ + \n\ + -o \n\ + Save color and depth side by side to image sequence.\n\ + \n\ + -d \n\ + Display depth in color.\n\ + \n\ + -h \n\ + Print the help.\n\n", name); if (badparam) diff --git a/example/device/framegrabber/saveRealSenseData.cpp b/example/device/framegrabber/saveRealSenseData.cpp index e22dbe4b08..35263c266b 100644 --- a/example/device/framegrabber/saveRealSenseData.cpp +++ b/example/device/framegrabber/saveRealSenseData.cpp @@ -39,8 +39,8 @@ #include #include -#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) +#if (defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2)) && defined(VISP_HAVE_THREADS) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PUGIXML) #include #include @@ -75,42 +75,42 @@ namespace void usage(const char *name, const char *badparam) { fprintf(stdout, "\n\ - Save RealSense data.\n\ - \n\ - %s\ - OPTIONS: \n\ - -s \n\ - Save data.\n\ - \n\ - -o \n\ - Output directory.\n\ - \n\ - -a \n\ - Use aligned streams.\n\ - \n\ - -c \n\ - Save color stream.\n\ - \n\ - -d \n\ - Save depth stream.\n\ - \n\ - -p \n\ - Save pointcloud.\n\ - \n\ - -i \n\ - Save infrared stream.\n\ - \n\ - -C \n\ - Click to save.\n\ - \n\ - -f \n\ - Set FPS.\n\ - \n\ - -b \n\ - Save point cloud in binary format.\n\ - \n\ - -h \n\ - Print the help.\n\n", + Save RealSense data.\n\ + \n\ + %s\ + OPTIONS: \n\ + -s \n\ + Save data.\n\ + \n\ + -o \n\ + Output directory.\n\ + \n\ + -a \n\ + Use aligned streams.\n\ + \n\ + -c \n\ + Save color stream.\n\ + \n\ + -d \n\ + Save depth stream.\n\ + \n\ + -p \n\ + Save pointcloud.\n\ + \n\ + -i \n\ + Save infrared stream.\n\ + \n\ + -C \n\ + Click to save.\n\ + \n\ + -f \n\ + Set FPS.\n\ + \n\ + -b \n\ + Save point cloud in binary format.\n\ + \n\ + -h \n\ + Print the help.\n\n", name); if (badparam) diff --git a/example/device/laserscanner/SickLDMRS-Process.cpp b/example/device/laserscanner/SickLDMRS-Process.cpp index dc1dac47b3..67bd4974ec 100644 --- a/example/device/laserscanner/SickLDMRS-Process.cpp +++ b/example/device/laserscanner/SickLDMRS-Process.cpp @@ -68,23 +68,20 @@ #include #include -#if (!defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__)))) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) +#if (!defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__)))) && \ + (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) && defined(VISP_HAVE_THREADS) + +#include +#include static int save = 0; static int layerToDisplay = 0xF; // 0xF = 1111 => all the layers are selected static vpLaserScan shm_laserscan[4]; double time_offset = 0; -#ifdef VISP_HAVE_PTHREAD -pthread_mutex_t shm_mutex; -#endif +std::mutex shm_mutex; std::string output_path; -void *laser_display_and_save_loop(void *); -void *laser_acq_loop(void *); -void *camera_acq_and_display_loop(void *); - -void *laser_display_and_save_loop(void *) +void laser_display_and_save_loop() { vpImage map(700, 300); map = 0; @@ -133,14 +130,11 @@ void *laser_display_and_save_loop(void *) vpDisplay::display(map); #endif -#ifdef VISP_HAVE_PTHREAD - pthread_mutex_lock(&shm_mutex); -#endif - for (int layer = 0; layer < 4; layer++) + shm_mutex.lock(); + for (int layer = 0; layer < 4; layer++) { laserscan[layer] = shm_laserscan[layer]; -#ifdef VISP_HAVE_PTHREAD - pthread_mutex_unlock(&shm_mutex); -#endif + } + shm_mutex.unlock(); // Parse the four layers for (int layer = 0; layer < 4; layer++) { @@ -158,12 +152,12 @@ void *laser_display_and_save_loop(void *) // Write the file header fdscan << "# Scan layer [1 to 4] : " << layer + 1 << std::endl - << "# Start timestamp (s) : " << laserscan[layer].getStartTimestamp() - time_offset << std::endl - << "# End timestamp (s) : " << laserscan[layer].getEndTimestamp() - time_offset << std::endl - << "# Data : \"radial distance (m)\" \"horizontal angle " - "(rad)\" \"vertical angle (rad)\" \"X (m)\" \"Y (m)\" \"Z " - "(m)\"" - << std::endl; + << "# Start timestamp (s) : " << laserscan[layer].getStartTimestamp() - time_offset << std::endl + << "# End timestamp (s) : " << laserscan[layer].getEndTimestamp() - time_offset << std::endl + << "# Data : \"radial distance (m)\" \"horizontal angle " + "(rad)\" \"vertical angle (rad)\" \"X (m)\" \"Y (m)\" \"Z " + "(m)\"" + << std::endl; } vpImagePoint E; // Beam echo @@ -194,10 +188,9 @@ void *laser_display_and_save_loop(void *) // std::endl; } delete display; - return nullptr; } -void *laser_acq_loop(void *) +void laser_acq_loop() { std::string ip = "131.254.12.119"; @@ -211,22 +204,17 @@ void *laser_acq_loop(void *) if (laser.measure(laserscan) == false) continue; -#ifdef VISP_HAVE_PTHREAD - pthread_mutex_lock(&shm_mutex); -#endif - for (int layer = 0; layer < 4; layer++) + shm_mutex.lock(); + for (int layer = 0; layer < 4; layer++) { shm_laserscan[layer] = laserscan[layer]; -#ifdef VISP_HAVE_PTHREAD - pthread_mutex_unlock(&shm_mutex); -#endif + } + shm_mutex.unlock(); std::cout << "laser acq time: " << vpTime::measureTimeMs() - t1 << std::endl; } - - return nullptr; } -void *camera_acq_and_display_loop(void *) +void camera_acq_and_display_loop() { #ifdef VISP_HAVE_DC1394 try { @@ -234,8 +222,9 @@ void *camera_acq_and_display_loop(void *) vp1394TwoGrabber g; // Create a grabber based on libdc1394-2.x third party lib // If no camera found return - if (g.getNumCameras() == 0) - return nullptr; + if (g.getNumCameras() == 0) { + return; + } // g.setVideoMode(vp1394TwoGrabber::vpVIDEO_MODE_640x480_MONO8); // g.setFramerate(vp1394TwoGrabber::vpFRAMERATE_60); @@ -255,7 +244,7 @@ void *camera_acq_and_display_loop(void *) display->init(Q, 320, 10, "Camera"); #endif - // Create a file with cameraimage time stamps + // Create a file with image time stamps std::ofstream fdimage_ts; if (save) { std::string filename = output_path + "/image_timestamp.txt"; @@ -289,10 +278,10 @@ void *camera_acq_and_display_loop(void *) if (save) { fdimage_ts.close(); } - } catch (...) { + } + catch (...) { } #endif - return nullptr; } int main(int argc, const char **argv) @@ -304,7 +293,8 @@ int main(int argc, const char **argv) try { // Create a directory with name "username" vpIoTools::makeDirectory(output_path); - } catch (...) { + } + catch (...) { std::cout << "Cannot create " << output_path << " directory" << std::endl; return EXIT_FAILURE; } @@ -323,30 +313,27 @@ int main(int argc, const char **argv) {"-h", vpParseArgv::ARGV_HELP, (char *)nullptr, (char *)nullptr, "Display one or more measured layers form a Sick LD-MRS laser " "scanner."}, - {(char *)nullptr, vpParseArgv::ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr}}; + {(char *)nullptr, vpParseArgv::ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr} }; // Read the command line options if (vpParseArgv::parse(&argc, argv, argTable, vpParseArgv::ARGV_NO_LEFTOVERS | vpParseArgv::ARGV_NO_ABBREV | - vpParseArgv::ARGV_NO_DEFAULTS)) { + vpParseArgv::ARGV_NO_DEFAULTS)) { return (EXIT_FAILURE); } + VISP_HAVE_PTHREAD + time_offset = vpTime::measureTimeSecond(); - time_offset = vpTime::measureTimeSecond(); -#ifdef VISP_HAVE_PTHREAD - pthread_t thread_camera_acq; - pthread_t thread_laser_acq; - pthread_t thread_laser_display; - pthread_create(&thread_camera_acq, nullptr, &camera_acq_and_display_loop, nullptr); - pthread_create(&thread_laser_acq, nullptr, &laser_acq_loop, nullptr); - pthread_create(&thread_laser_display, nullptr, &laser_display_and_save_loop, nullptr); - pthread_join(thread_camera_acq, 0); - pthread_join(thread_laser_acq, 0); - pthread_join(thread_laser_display, 0); -#endif + std::thread thread_camera_acq(&camera_acq_and_display_loop); + std::thread thread_laser_acq(&laser_acq_loop); + std::thread thread_laser_display(&laser_display_and_save_loop); + thread_camera_acq.join(); + thread_laser_acq.join(); + thread_laser_display.join(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -367,7 +354,7 @@ int main() int main() { std::cout << "This example is only working on unix-like platforms \n" - << "since the Sick LD-MRS driver was not ported to Windows." << std::endl; + << "since the Sick LD-MRS driver was not ported to Windows." << std::endl; return EXIT_SUCCESS; } diff --git a/example/moments/image/servoMomentImage.cpp b/example/moments/image/servoMomentImage.cpp index bd3c7045ae..1cfe5b9352 100644 --- a/example/moments/image/servoMomentImage.cpp +++ b/example/moments/image/servoMomentImage.cpp @@ -63,25 +63,12 @@ #include #include -#if !defined(_WIN32) && !defined(VISP_HAVE_PTHREAD) -// Robot simulator used in this example is not available -int main() -{ - std::cout << "Can't run this example since vpSimulatorAfma6 capability is " - "not available." - << std::endl; - std::cout << "You should install pthread third-party library." << std::endl; - return EXIT_SUCCESS; -} -// No display available -#elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ - !defined(VISP_HAVE_GTK) +#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ + !defined(VISP_HAVE_GTK) && !defined(VISP_HAVE_THREADS) int main() { std::cout << "Can't run this example since no display capability is available." << std::endl; - std::cout << "You should install one of the following third-party library: " - "X11, OpenCV, GDI, GTK." - << std::endl; + std::cout << "You should install one of the following third-party library: X11, OpenCV, GDI, GTK." << std::endl; return EXIT_SUCCESS; } #else diff --git a/example/moments/points/servoMomentPoints.cpp b/example/moments/points/servoMomentPoints.cpp index 53c0f5782c..4c3184a2ef 100644 --- a/example/moments/points/servoMomentPoints.cpp +++ b/example/moments/points/servoMomentPoints.cpp @@ -62,25 +62,12 @@ #include #include -#if !defined(_WIN32) && !defined(VISP_HAVE_PTHREAD) -// Robot simulator used in this example is not available -int main() -{ - std::cout << "Can't run this example since vpSimulatorAfma6 capability is " - "not available." - << std::endl; - std::cout << "You should install pthread third-party library." << std::endl; - return EXIT_SUCCESS; -} -// No display available -#elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ - !defined(VISP_HAVE_GTK) +#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ + !defined(VISP_HAVE_GTK) && !defined(VISP_HAVE_THREADS) int main() { std::cout << "Can't run this example since no display capability is available." << std::endl; - std::cout << "You should install one of the following third-party library: " - "X11, OpenCV, GDI, GTK." - << std::endl; + std::cout << "You should install one of the following third-party library: X11, OpenCV, GDI, GTK." << std::endl; return EXIT_SUCCESS; } #else diff --git a/example/moments/polygon/servoMomentPolygon.cpp b/example/moments/polygon/servoMomentPolygon.cpp index 4134c33caa..776c7528b2 100644 --- a/example/moments/polygon/servoMomentPolygon.cpp +++ b/example/moments/polygon/servoMomentPolygon.cpp @@ -61,25 +61,12 @@ #include #include -#if !defined(_WIN32) && !defined(VISP_HAVE_PTHREAD) -// Robot simulator used in this example is not available -int main() -{ - std::cout << "Can't run this example since vpSimulatorAfma6 capability is " - "not available." - << std::endl; - std::cout << "You should install pthread third-party library." << std::endl; - return EXIT_SUCCESS; -} -// No display available -#elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ - !defined(VISP_HAVE_GTK) +#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ + !defined(VISP_HAVE_GTK) && !defined(VISP_HAVE_THREADS) int main() { std::cout << "Can't run this example since no display capability is available." << std::endl; - std::cout << "You should install one of the following third-party library: " - "X11, OpenCV, GDI, GTK." - << std::endl; + std::cout << "You should install one of the following third-party library: X11, OpenCV, GDI, GTK." << std::endl; return EXIT_SUCCESS; } #else diff --git a/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp b/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp index 649961326d..cceca787e7 100644 --- a/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp @@ -53,9 +53,8 @@ #include #include -#if ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_GDI)) && \ - (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) +#if defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_GDI)) \ + && (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) // We need to use threading capabilities. Thus on Unix-like // platforms, the libpthread third-party library need to be diff --git a/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp b/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp index b99dc47015..64e82c5d71 100644 --- a/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp @@ -53,9 +53,8 @@ #include #include -#if ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_GDI)) && \ - (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) +#if defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_GDI)) \ + && (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) // We need to use threading capabilities. Thus on Unix-like // platforms, the libpthread third-party library need to be @@ -348,7 +347,8 @@ int main(int argc, const char **argv) vpDisplay::getClick(Iint); } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } @@ -357,7 +357,7 @@ int main(int argc, const char **argv) int main() { std::cout << "You do not have X11, or GDI (Graphical Device Interface) of OpenCV functionalities to display images..." - << std::endl; + << std::endl; std::cout << "Tip if you are on a unix-like system:" << std::endl; std::cout << "- Install X11, configure again ViSP using cmake and build again this example" << std::endl; std::cout << "Tip if you are on a windows-like system:" << std::endl; diff --git a/example/servo-pixhawk/sendMocapToPixhawk.cpp b/example/servo-pixhawk/sendMocapToPixhawk.cpp index 67cf9fdc32..e646a8599b 100644 --- a/example/servo-pixhawk/sendMocapToPixhawk.cpp +++ b/example/servo-pixhawk/sendMocapToPixhawk.cpp @@ -46,7 +46,7 @@ // Check if std:c++17 or higher #if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) && \ - (defined(VISP_HAVE_QUALISYS) || defined(VISP_HAVE_VICON)) + (defined(VISP_HAVE_QUALISYS) || defined(VISP_HAVE_VICON)) && defined(VISP_HAVE_THREADS) #include #include diff --git a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp index 8fa7735c17..50d495cc5e 100644 --- a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp +++ b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp @@ -59,7 +59,7 @@ #endif #include -#if defined(VISP_HAVE_PTU46) && defined(VISP_HAVE_DC1394) +#if defined(VISP_HAVE_PTU46) && defined(VISP_HAVE_DC1394) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/ar/src/coin-simulator/vpSimulator.cpp b/modules/ar/src/coin-simulator/vpSimulator.cpp index 16598e938f..8d154d9931 100644 --- a/modules/ar/src/coin-simulator/vpSimulator.cpp +++ b/modules/ar/src/coin-simulator/vpSimulator.cpp @@ -73,12 +73,12 @@ // Positions of all of the vertices: // -static float pyramidVertexes[5][3] = {{0.33f, 0.33f, 0.f}, +static float pyramidVertexes[5][3] = { {0.33f, 0.33f, 0.f}, {-0.33f, 0.33f, 0.f}, {-0.33f, -0.33f, 0.f}, {0.33f, -0.33f, 0.f}, - {0.f, 0.f, -1.0f}}; + {0.f, 0.f, -1.0f} }; static int32_t pyramidFaces[] = { 0, @@ -325,18 +325,18 @@ void vpSimulator::kill() vpSimulator::vpSimulator() : #if defined(VISP_HAVE_SOWIN) - mainWindow(), + mainWindow(), #elif defined(VISP_HAVE_SOQT) - mainWindow(nullptr), + mainWindow(nullptr), #elif defined(VISP_HAVE_SOXT) - mainWindow(), + mainWindow(), #endif - mainWindowInitialized(false), typeImage(vpSimulator::grayImage), image_background(nullptr), internalView(nullptr), - externalView(nullptr), mainThread(nullptr), internal_width(0), internal_height(0), external_width(0), external_height(0), - scene(nullptr), internalRoot(nullptr), externalRoot(nullptr), internalCamera(nullptr), externalCamera(nullptr), - internalCameraPosition(nullptr), extrenalCameraPosition(nullptr), internalCameraObject(nullptr), zoomFactor(0.), - cameraPositionInitialized(false), cMf(), internalCameraParameters(), externalCameraParameters(), realtime(nullptr), - offScreenRenderer(nullptr), bufferView(nullptr), get(0) + mainWindowInitialized(false), typeImage(vpSimulator::grayImage), image_background(nullptr), internalView(nullptr), + externalView(nullptr), mainThread(nullptr), internal_width(0), internal_height(0), external_width(0), external_height(0), + scene(nullptr), internalRoot(nullptr), externalRoot(nullptr), internalCamera(nullptr), externalCamera(nullptr), + internalCameraPosition(nullptr), extrenalCameraPosition(nullptr), internalCameraObject(nullptr), zoomFactor(0.), + cameraPositionInitialized(false), cMf(), internalCameraParameters(), externalCameraParameters(), realtime(nullptr), + offScreenRenderer(nullptr), bufferView(nullptr), get(0) { vpSimulator::init(); } @@ -415,7 +415,8 @@ void vpSimulator::setZoomFactor(float zoom) taille->scaleFactor.setValue(zoomFactor, zoomFactor, zoomFactor); this->scene->addChild(taille); firstTime = false; - } else { + } + else { SoScale *taille = (SoScale *)this->scene->getChild(0); taille->scaleFactor.setValue(zoomFactor, zoomFactor, zoomFactor); } @@ -750,7 +751,8 @@ void vpSimulator::load(const char *iv_filename, const vpHomogeneousMatrix &fMo) try { this->addObject(newObject, fMo); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error adding object from file <%s> ", iv_filename); throw; } @@ -765,7 +767,8 @@ void vpSimulator::addObject(SoSeparator *newObject, const vpHomogeneousMatrix &f { try { this->addObject(newObject, fMo, scene); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error adding object in scene graph "); throw; } @@ -787,7 +790,8 @@ void vpSimulator::addObject(SoSeparator *object, const vpHomogeneousMatrix &fMo, if (i == j) { if (fabs(fMo[i][j] - 1) > 1e-6) identity = false; - } else { + } + else { if (fabs(fMo[i][j]) > 1e-6) identity = false; } @@ -796,7 +800,8 @@ void vpSimulator::addObject(SoSeparator *object, const vpHomogeneousMatrix &fMo, if (identity == true) { root->addChild(object); - } else { + } + else { SbMatrix matrix; SbRotation rotation; for (unsigned int i = 0; i < 4; i++) @@ -875,7 +880,8 @@ void vpSimulator::offScreenRendering(vpSimulatorViewType view, int *width, int * if (view == vpSimulator::INTERNAL) { size = this->internalView->getViewportRegion().getWindowSize(); thisroot = this->internalView->getSceneManager()->getSceneGraph(); - } else { + } + else { size = this->externalView->getViewportRegion().getWindowSize(); thisroot = this->externalView->getSceneManager()->getSceneGraph(); } @@ -886,7 +892,8 @@ void vpSimulator::offScreenRendering(vpSimulatorViewType view, int *width, int * if (nullptr == this->offScreenRenderer) { // Init du SoOffscreenRenderer this->offScreenRenderer = new SoOffscreenRenderer(myViewPort); - } else { + } + else { // Redefini le view port this->offScreenRenderer->setViewportRegion(myViewPort); } @@ -896,20 +903,21 @@ void vpSimulator::offScreenRendering(vpSimulatorViewType view, int *width, int * vpERROR_TRACE("La scene n'a pas pu etre rendue offscreen."); delete this->offScreenRenderer; this->offScreenRenderer = nullptr; - } else { - - /* - if (view==vpSimulator::INTERNAL) - { - //Recopie du buffer contenant l'image, dans bufferView - int length = 3*size [0]*size[1]; - delete [] bufferView; - bufferView = new unsigned char [length]; - for(int i=0; ioffScreenRenderer->getBuffer()[i]; - } - }*/ + } + else { + + /* + if (view==vpSimulator::INTERNAL) + { + //Recopie du buffer contenant l'image, dans bufferView + int length = 3*size [0]*size[1]; + delete [] bufferView; + bufferView = new unsigned char [length]; + for(int i=0; ioffScreenRenderer->getBuffer()[i]; + } + }*/ } // exit(1) ; @@ -996,7 +1004,6 @@ void vpSimulator::getInternalImage(vpImage &I) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_ar.a(vpSimulator.cpp.o) has no -// symbols -void dummy_vpSimulator(){}; +// Work around to avoid warning: libvisp_ar.a(vpSimulator.cpp.o) has no symbols +void dummy_vpSimulator() { }; #endif diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 8dbaa41ec5..1184627d29 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -48,8 +48,8 @@ #include #include -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) -#include +#if defined(VISP_HAVE_THREADS) +#include #endif #include @@ -481,7 +481,7 @@ inline std::ostream &operator<<(std::ostream &s, const vpImage &I) return s; } -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_HAVE_THREADS) namespace { struct vpImageLut_Param_t @@ -499,9 +499,8 @@ struct vpImageLut_Param_t { } }; -vpThread::Return performLutThread(vpThread::Args args) +void performLutThread(vpImageLut_Param_t *imageLut_param) { - vpImageLut_Param_t *imageLut_param = static_cast(args); unsigned int start_index = imageLut_param->m_start_index; unsigned int end_index = imageLut_param->m_end_index; @@ -511,11 +510,6 @@ vpThread::Return performLutThread(vpThread::Args args) unsigned char *ptrEnd = bitmap + end_index; unsigned char *ptrCurrent = ptrStart; - // while(ptrCurrent != ptrEnd) { - // *ptrCurrent = imageLut_param->m_lut[*ptrCurrent]; - // ++ptrCurrent; - // } - if (end_index - start_index >= 8) { // Unroll loop version for (; ptrCurrent <= ptrEnd - 8;) { @@ -548,8 +542,6 @@ vpThread::Return performLutThread(vpThread::Args args) for (; ptrCurrent != ptrEnd; ++ptrCurrent) { *ptrCurrent = imageLut_param->m_lut[*ptrCurrent]; } - - return 0; } struct vpImageLutRGBa_Param_t @@ -567,9 +559,8 @@ struct vpImageLutRGBa_Param_t { } }; -vpThread::Return performLutRGBaThread(vpThread::Args args) +void performLutRGBaThread(vpImageLutRGBa_Param_t *imageLut_param) { - vpImageLutRGBa_Param_t *imageLut_param = static_cast(args); unsigned int start_index = imageLut_param->m_start_index; unsigned int end_index = imageLut_param->m_end_index; @@ -615,8 +606,6 @@ vpThread::Return performLutRGBaThread(vpThread::Args args) *ptrCurrent = imageLut_param->m_lut[*ptrCurrent].A; ptrCurrent++; } - - return 0; } } // namespace #endif @@ -2023,7 +2012,7 @@ template <> inline void vpImage::performLut(const unsigned char(& unsigned char *ptrCurrent = ptrStart; bool use_single_thread = (nbThreads == 0 || nbThreads == 1); -#if !defined(VISP_HAVE_PTHREAD) && !defined(_WIN32) +#if !defined(VISP_HAVE_THREADS) use_single_thread = true; #endif @@ -2040,10 +2029,9 @@ template <> inline void vpImage::performLut(const unsigned char(& } } else { -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_HAVE_THREADS) // Multi-threads - - std::vector threadpool; + std::vector threadpool; std::vector imageLutParams; unsigned int image_size = getSize(); @@ -2064,7 +2052,7 @@ template <> inline void vpImage::performLut(const unsigned char(& imageLutParams.push_back(imageLut_param); // Start the threads - vpThread *imageLut_thread = new vpThread((vpThread::Fn)performLutThread, (vpThread::Args)imageLut_param); + std::thread *imageLut_thread = new std::thread(&performLutThread, imageLut_param); threadpool.push_back(imageLut_thread); } @@ -2103,7 +2091,7 @@ template <> inline void vpImage::performLut(const vpRGBa(&lut)[256], uns unsigned char *ptrCurrent = ptrStart; bool use_single_thread = (nbThreads == 0 || nbThreads == 1); -#if !defined(VISP_HAVE_PTHREAD) && !defined(_WIN32) +#if !defined(VISP_HAVE_THREADS) use_single_thread = true; #endif @@ -2128,9 +2116,9 @@ template <> inline void vpImage::performLut(const vpRGBa(&lut)[256], uns } } else { -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_HAVE_THREADS) // Multi-threads - std::vector threadpool; + std::vector threadpool; std::vector imageLutParams; unsigned int image_size = getSize(); @@ -2151,7 +2139,7 @@ template <> inline void vpImage::performLut(const vpRGBa(&lut)[256], uns imageLutParams.push_back(imageLut_param); // Start the threads - vpThread *imageLut_thread = new vpThread((vpThread::Fn)performLutRGBaThread, (vpThread::Args)imageLut_param); + std::thread *imageLut_thread = new std::thread(&performLutRGBaThread, imageLut_param); threadpool.push_back(imageLut_thread); } diff --git a/modules/core/include/visp3/core/vpImageTools.h b/modules/core/include/visp3/core/vpImageTools.h index 55d3c002ea..6c8fa38269 100644 --- a/modules/core/include/visp3/core/vpImageTools.h +++ b/modules/core/include/visp3/core/vpImageTools.h @@ -43,8 +43,8 @@ #include -#ifdef VISP_HAVE_PTHREAD -#include +#ifdef VISP_HAVE_THREADS +#include #endif #include @@ -518,7 +518,7 @@ inline void vpImageTools::binarise(vpImage &I, unsigned char thre } } -#ifdef VISP_HAVE_PTHREAD +#ifdef VISP_HAVE_THREADS #ifndef DOXYGEN_SHOULD_SKIP_THIS template class vpUndistortInternalType @@ -549,22 +549,21 @@ template class vpUndistortInternalType return *this; } - static void *vpUndistort_threaded(void *arg); + static void vpUndistort_threaded(vpUndistortInternalType &undistortSharedData); }; -template void *vpUndistortInternalType::vpUndistort_threaded(void *arg) +template void vpUndistortInternalType::vpUndistort_threaded(vpUndistortInternalType &undistortSharedData) { - vpUndistortInternalType *undistortSharedData = static_cast *>(arg); - int offset = (int)undistortSharedData->threadid; - int width = (int)undistortSharedData->width; - int height = (int)undistortSharedData->height; - int nthreads = (int)undistortSharedData->nthreads; - - double u0 = undistortSharedData->cam.get_u0(); - double v0 = undistortSharedData->cam.get_v0(); - double px = undistortSharedData->cam.get_px(); - double py = undistortSharedData->cam.get_py(); - double kud = undistortSharedData->cam.get_kud(); + int offset = (int)undistortSharedData.threadid; + int width = (int)undistortSharedData.width; + int height = (int)undistortSharedData.height; + int nthreads = (int)undistortSharedData.nthreads; + + double u0 = undistortSharedData.cam.get_u0(); + double v0 = undistortSharedData.cam.get_v0(); + double px = undistortSharedData.cam.get_px(); + double py = undistortSharedData.cam.get_py(); + double kud = undistortSharedData.cam.get_kud(); double invpx = 1.0 / px; double invpy = 1.0 / py; @@ -572,8 +571,8 @@ template void *vpUndistortInternalType::vpUndistort_threaded( double kud_px2 = kud * invpx * invpx; double kud_py2 = kud * invpy * invpy; - Type *dst = undistortSharedData->dst + (height / nthreads * offset) * width; - Type *src = undistortSharedData->src; + Type *dst = undistortSharedData.dst + (height / nthreads * offset) * width; + Type *src = undistortSharedData.src; for (double v = height / nthreads * offset; v < height / nthreads * (offset + 1); v++) { double deltav = v - v0; @@ -616,12 +615,9 @@ template void *vpUndistortInternalType::vpUndistort_threaded( dst++; } } - - pthread_exit((void *)0); - return nullptr; } #endif // DOXYGEN_SHOULD_SKIP_THIS -#endif // VISP_HAVE_PTHREAD +#endif // VISP_HAVE_THREADS /*! Undistort an image @@ -650,7 +646,7 @@ template void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &cam, vpImage &undistI, unsigned int nThreads) { -#ifdef VISP_HAVE_PTHREAD +#if defined(VISP_HAVE_THREADS) // // Optimized version using pthreads // @@ -669,13 +665,9 @@ void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &c } unsigned int nthreads = nThreads; - pthread_attr_t attr; - pthread_t *callThd = new pthread_t[nthreads]; - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); + std::vector threadpool; - vpUndistortInternalType *undistortSharedData; - undistortSharedData = new vpUndistortInternalType[nthreads]; + vpUndistortInternalType *undistortSharedData = new vpUndistortInternalType[nthreads]; for (unsigned int i = 0; i < nthreads; i++) { // Each thread works on a different set of data. @@ -687,19 +679,22 @@ void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &c undistortSharedData[i].cam = cam; undistortSharedData[i].nthreads = nthreads; undistortSharedData[i].threadid = i; - pthread_create(&callThd[i], &attr, &vpUndistortInternalType::vpUndistort_threaded, &undistortSharedData[i]); + std::thread *undistort_thread = new std::thread(&vpUndistortInternalType::vpUndistort_threaded, std::ref(undistortSharedData[i])); + threadpool.push_back(undistort_thread); } - pthread_attr_destroy(&attr); /* Wait on the other threads */ for (unsigned int i = 0; i < nthreads; i++) { // vpTRACE("join thread %d", i); - pthread_join(callThd[i], nullptr); + threadpool[i]->join(); + } + + for (unsigned int i = 0; i < nthreads; i++) { + delete threadpool[i]; } - delete[] callThd; delete[] undistortSharedData; -#else // VISP_HAVE_PTHREAD +#else // VISP_HAVE_THREADS (void)nThreads; // // optimized version without pthreads @@ -773,7 +768,7 @@ void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &c dst++; } } -#endif // VISP_HAVE_PTHREAD +#endif // VISP_HAVE_THREADS #if 0 // non optimized version @@ -1137,7 +1132,7 @@ void vpImageTools::resize(const vpImage &I, vpImage &Ires, const vpI } } } -} + } #if defined(VISP_HAVE_SIMDLIB) template <> diff --git a/modules/core/include/visp3/core/vpMutex.h b/modules/core/include/visp3/core/vpMutex.h index a9aaf12e1e..f61ab41063 100644 --- a/modules/core/include/visp3/core/vpMutex.h +++ b/modules/core/include/visp3/core/vpMutex.h @@ -37,7 +37,7 @@ #include #include -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) && (defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0))) #if defined(VISP_HAVE_PTHREAD) #include @@ -53,6 +53,7 @@ \class vpMutex \ingroup group_core_threading + \deprecated Use rather std::mutex. Class that allows protection by mutex. @@ -66,7 +67,7 @@ \sa vpScopedLock */ -class vpMutex +class vp_deprecated vpMutex { public: vpMutex() : m_mutex() diff --git a/modules/core/include/visp3/core/vpThread.h b/modules/core/include/visp3/core/vpThread.h index 8420656b82..672ba84ffb 100644 --- a/modules/core/include/visp3/core/vpThread.h +++ b/modules/core/include/visp3/core/vpThread.h @@ -36,7 +36,7 @@ #include #include -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) && (defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0))) #if defined(VISP_HAVE_PTHREAD) #include @@ -53,6 +53,8 @@ \ingroup group_core_threading + \deprecated Use rather std::thread. + Class to represent individual threads of execution. This class implements native pthread functionalities if available, or native Windows threading capabilities if pthread is not available under @@ -65,7 +67,7 @@ More examples are provided in \ref tutorial-multi-threading. */ -class vpThread +class vp_deprecated vpThread { public: #if defined(VISP_HAVE_PTHREAD) diff --git a/modules/core/src/tools/convert/vpConvert.cpp b/modules/core/src/tools/convert/vpConvert.cpp index 9e38c3def8..6ba42f78c6 100644 --- a/modules/core/src/tools/convert/vpConvert.cpp +++ b/modules/core/src/tools/convert/vpConvert.cpp @@ -185,7 +185,7 @@ cv::Point3d vpConvert::vpCamPointToPoint3d(const vpPoint &point) } /*! - Unary function to convert the 3D coordinates in the object frame to a cv::Point3f. + Unary function to convert the 3D coordinates in the object frame to a cv::Point3f. \param point : Point to convert. \return A cv::Point3f with the 3D coordinates stored in vpPoint in the @@ -248,7 +248,8 @@ void vpConvert::convertFromOpenCV(const cv::Point3f &from, vpPoint &to, bool cam { if (cameraFrame) { to = point3fToVpCamPoint(from); - } else { + } + else { to = point3fToVpObjectPoint(from); } } @@ -264,7 +265,8 @@ void vpConvert::convertFromOpenCV(const cv::Point3d &from, vpPoint &to, bool cam { if (cameraFrame) { to = point3dToVpCamPoint(from); - } else { + } + else { to = point3dToVpObjectPoint(from); } } @@ -314,7 +316,8 @@ void vpConvert::convertFromOpenCV(const std::vector &from, std::vec to.resize(from.size()); if (cameraFrame) { std::transform(from.begin(), from.end(), to.begin(), point3fToVpCamPoint); - } else { + } + else { std::transform(from.begin(), from.end(), to.begin(), point3fToVpObjectPoint); } } @@ -331,7 +334,8 @@ void vpConvert::convertFromOpenCV(const std::vector &from, std::vec to.resize(from.size()); if (cameraFrame) { std::transform(from.begin(), from.end(), to.begin(), point3dToVpCamPoint); - } else { + } + else { std::transform(from.begin(), from.end(), to.begin(), point3dToVpObjectPoint); } } @@ -377,7 +381,8 @@ void vpConvert::convertToOpenCV(const vpPoint &from, cv::Point3f &to, bool camer { if (cameraFrame) { to = vpCamPointToPoint3f(from); - } else { + } + else { to = vpObjectPointToPoint3f(from); } } @@ -393,7 +398,8 @@ void vpConvert::convertToOpenCV(const vpPoint &from, cv::Point3d &to, bool camer { if (cameraFrame) { to = vpCamPointToPoint3d(from); - } else { + } + else { to = vpObjectPointToPoint3d(from); } } @@ -432,7 +438,8 @@ void vpConvert::convertToOpenCV(const std::vector &from, std::vector &from, std::vector #include -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) -#include +#if defined(VISP_HAVE_THREADS) +#include namespace { @@ -76,9 +76,8 @@ struct vpHistogram_Param_t } }; -vpThread::Return computeHistogramThread(vpThread::Args args) +void computeHistogramThread(vpHistogram_Param_t *histogram_param) { - vpHistogram_Param_t *histogram_param = static_cast(args); unsigned int start_index = histogram_param->m_start_index; unsigned int end_index = histogram_param->m_end_index; @@ -171,7 +170,6 @@ vpThread::Return computeHistogramThread(vpThread::Args args) ++ptrMaskCurrent; } } - return 0; } } // namespace #endif @@ -188,7 +186,7 @@ bool compare_vpHistogramPeak(vpHistogramPeak first, vpHistogramPeak second) } /*! - Defaut constructor for a gray level histogram. + Default constructor for a gray level histogram. */ vpHistogram::vpHistogram() : m_histogram(nullptr), m_size(256), mp_mask(nullptr), m_total(0) { init(); } @@ -314,7 +312,7 @@ void vpHistogram::calculate(const vpImage &I, unsigned int nbins, memset(m_histogram, 0, m_size * sizeof(unsigned int)); bool use_single_thread; -#if !defined(VISP_HAVE_PTHREAD) && !defined(_WIN32) +#if !defined(VISP_HAVE_THREADS) use_single_thread = true; #else use_single_thread = (nbThreads == 0 || nbThreads == 1); @@ -355,9 +353,9 @@ void vpHistogram::calculate(const vpImage &I, unsigned int nbins, } } else { -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_HAVE_THREADS) // Multi-threads - std::vector threadpool; + std::vector threadpool; std::vector histogramParams; unsigned int image_size = I.getSize(); @@ -381,7 +379,7 @@ void vpHistogram::calculate(const vpImage &I, unsigned int nbins, histogramParams.push_back(histogram_param); // Start the threads - vpThread *histogram_thread = new vpThread((vpThread::Fn)computeHistogramThread, (vpThread::Args)histogram_param); + std::thread *histogram_thread = new std::thread(&computeHistogramThread, histogram_param); threadpool.push_back(histogram_thread); } diff --git a/modules/core/src/tools/histogram/vpHistogramPeak.cpp b/modules/core/src/tools/histogram/vpHistogramPeak.cpp index 63e476ad70..6b507e8490 100644 --- a/modules/core/src/tools/histogram/vpHistogramPeak.cpp +++ b/modules/core/src/tools/histogram/vpHistogramPeak.cpp @@ -44,12 +44,12 @@ #include /*! - Defaut constructor for a gray level histogram peak. + Default constructor for a gray level histogram peak. */ vpHistogramPeak::vpHistogramPeak() : level(0), value(0) {} /*! - Defaut constructor for a gray level histogram peak. + Default constructor for a gray level histogram peak. */ vpHistogramPeak::vpHistogramPeak(unsigned char lvl, unsigned val) : level(lvl), value(val) {} diff --git a/modules/core/src/tools/xml/vpXmlParser.cpp b/modules/core/src/tools/xml/vpXmlParser.cpp index 8c203293bb..56480aee98 100644 --- a/modules/core/src/tools/xml/vpXmlParser.cpp +++ b/modules/core/src/tools/xml/vpXmlParser.cpp @@ -52,7 +52,7 @@ Initialise the main tag with default value. */ -vpXmlParser::vpXmlParser() : nodeMap(), main_tag("config") {} +vpXmlParser::vpXmlParser() : nodeMap(), main_tag("config") { } /*! Basic destructor that does nothing. @@ -79,7 +79,7 @@ vpXmlParser::~vpXmlParser() \param _twin : The parser to copy. */ -vpXmlParser::vpXmlParser(const vpXmlParser &_twin) : nodeMap(_twin.nodeMap), main_tag(_twin.main_tag) {} +vpXmlParser::vpXmlParser(const vpXmlParser &_twin) : nodeMap(_twin.nodeMap), main_tag(_twin.main_tag) { } /* utilities functions to read/write data from an xml document */ @@ -457,7 +457,8 @@ void vpXmlParser::save(const std::string &filename, bool append) doc = xmlNewDoc((xmlChar *)"1.0"); root_node = xmlNewNode(nullptr, (xmlChar *)main_tag.c_str()); xmlDocSetRootElement(doc, root_node); - } else { + } + else { if (!append) { xmlFreeDoc(doc); if (remove(filename.c_str()) != 0) @@ -482,7 +483,6 @@ void vpXmlParser::save(const std::string &filename, bool append) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpXmlParser.cpp.o) has no -// symbols -void dummy_vpXmlParser(){}; +// Work around to avoid warning: libvisp_core.a(vpXmlParser.cpp.o) has no symbols +void dummy_vpXmlParser() { }; #endif diff --git a/modules/core/test/image-with-dataset/perfColorConversion.cpp b/modules/core/test/image-with-dataset/perfColorConversion.cpp index b8b26970cc..03d24abf5b 100644 --- a/modules/core/test/image-with-dataset/perfColorConversion.cpp +++ b/modules/core/test/image-with-dataset/perfColorConversion.cpp @@ -35,7 +35,7 @@ #include -#ifdef VISP_HAVE_CATCH2 +#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/core/test/image-with-dataset/perfImageResize.cpp b/modules/core/test/image-with-dataset/perfImageResize.cpp index 06e60928bb..69cd7d90ca 100644 --- a/modules/core/test/image-with-dataset/perfImageResize.cpp +++ b/modules/core/test/image-with-dataset/perfImageResize.cpp @@ -35,7 +35,7 @@ #include -#ifdef VISP_HAVE_CATCH2 +#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/core/test/image-with-dataset/testColorConversion.cpp b/modules/core/test/image-with-dataset/testColorConversion.cpp index f3d2e61ee8..b9b1a43d67 100644 --- a/modules/core/test/image-with-dataset/testColorConversion.cpp +++ b/modules/core/test/image-with-dataset/testColorConversion.cpp @@ -149,7 +149,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -164,7 +164,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -179,7 +179,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -194,7 +194,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -209,7 +209,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -224,7 +224,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -243,12 +243,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -263,12 +263,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -283,11 +283,11 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -302,12 +302,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -322,12 +322,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -342,12 +342,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -458,7 +458,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -477,7 +477,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -496,7 +496,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -515,7 +515,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -534,7 +534,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -553,7 +553,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -576,7 +576,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -595,7 +595,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -614,7 +614,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -633,7 +633,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -652,7 +652,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -671,7 +671,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -691,7 +691,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -707,7 +707,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -723,7 +723,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -739,7 +739,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -755,7 +755,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -771,7 +771,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -830,7 +830,7 @@ TEST_CASE("OpenCV Mat <==> vpImage conversion", "[image_conversion]") vpImageConvert::convert(img, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("CV_8UC1 to unsigned char") @@ -996,7 +996,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - BGGR - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - BGGR - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1007,7 +1007,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - BGGR - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - BGGR - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1027,7 +1027,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - GBRG - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - GBRG - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1038,7 +1038,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - GBRG - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - GBRG - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1058,7 +1058,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - GRBG - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - GRBG - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1069,7 +1069,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - GRBG - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - GRBG - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1089,7 +1089,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - RGGB - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - RGGB - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1100,7 +1100,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - RGGB - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - RGGB - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1127,7 +1127,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - BGGR - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - BGGR - Bilinear - PSNR: " << PSNR <<" min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1137,7 +1137,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - BGGR - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - BGGR - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1157,7 +1157,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - GBRG - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - GBRG - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1167,7 +1167,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - GBRG - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - GBRG - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1187,7 +1187,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - GRBG - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - GRBG - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1197,7 +1197,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - GRBG - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - GRBG - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1217,7 +1217,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - RGGB - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - RGGB - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1227,7 +1227,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - RGGB - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - RGGB - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1249,6 +1249,7 @@ int main(int argc, char *argv[]) // numFailed is clamped to 255 as some unices only use the lower 8 bits. // This clamping has already been applied, so just return it here // You can also do any post run clean-up here + std::cout << (numFailed ? "Test failed" : "Test succeed") << std::endl; return numFailed; } #else diff --git a/modules/core/test/image-with-dataset/testUndistortImage.cpp b/modules/core/test/image-with-dataset/testUndistortImage.cpp index cbe07c8476..3f871a0983 100644 --- a/modules/core/test/image-with-dataset/testUndistortImage.cpp +++ b/modules/core/test/image-with-dataset/testUndistortImage.cpp @@ -30,11 +30,7 @@ * * Description: * Test for image undistortion. - * - * Authors: - * Anthony Saunier - * -*****************************************************************************/ + */ #include #include @@ -45,15 +41,14 @@ #include #include #include + /*! \example testUndistortImage.cpp \brief Undistort an image. - Read an image from the disk, undistort it and save the - undistorted image on the disk. - - */ + Read an image from the disk, undistort it and save the undistorted image on the disk. +*/ // List of allowed command line options #define GETOPTARGS "cdi:o:t:s:h" @@ -200,7 +195,7 @@ int main(int argc, const char **argv) if (!env_ipath.empty()) ipath = env_ipath; -// Set the default output path + // Set the default output path #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX opt_opath = "/tmp"; #elif defined(_WIN32) @@ -229,7 +224,8 @@ int main(int argc, const char **argv) try { // Create the dirname vpIoTools::makeDirectory(opath); - } catch (...) { + } + catch (...) { usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; @@ -244,8 +240,8 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } @@ -254,9 +250,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -279,7 +275,8 @@ int main(int argc, const char **argv) if (scale > 1) { std::cout << "Scale the image by a factor of " << scale << std::endl; vpImageTools::resize(I_, I, I_.getWidth() * scale, I_.getHeight() * scale); - } else { + } + else { I = I_; } std::cout << "Input image: " << I.getWidth() << "x" << I.getHeight() << std::endl; @@ -430,7 +427,8 @@ int main(int argc, const char **argv) vpImageIo::write(U_diff_gray, filename); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp b/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp index 7974ed449e..1c818c46ea 100644 --- a/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp +++ b/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp @@ -264,7 +264,7 @@ int main(int argc, const char **argv) int nbIterations = 100; unsigned int nbBins = 256; unsigned int sum_single_thread = 0; - unsigned int sum_single_multithread = 0; + unsigned int sum_multi_thread = 0; double t_single_thread = vpTime::measureTimeMs(); for (int iteration = 0; iteration < nbIterations; iteration++) { @@ -272,19 +272,19 @@ int main(int argc, const char **argv) } t_single_thread = vpTime::measureTimeMs() - t_single_thread; - double t_multithread = vpTime::measureTimeMs(); + double t_multi_thread = vpTime::measureTimeMs(); for (int iteration = 0; iteration < nbIterations; iteration++) { - sum_single_multithread = histogramSum(I, nbBins, nbThreads); + sum_multi_thread = histogramSum(I, nbBins, nbThreads); } - t_multithread = vpTime::measureTimeMs() - t_multithread; + t_multi_thread = vpTime::measureTimeMs() - t_multi_thread; std::cout << "sum_single_thread=" << sum_single_thread << " ; t_single_thread=" << t_single_thread << " ms ; mean=" << t_single_thread / (double)nbIterations << " ms" << std::endl; - std::cout << "sum_single_multithread=" << sum_single_multithread << " ; t_multithread=" << t_multithread - << " ms ; mean=" << t_multithread / (double)nbIterations << " ms" << std::endl; - std::cout << "Speed-up=" << t_single_thread / (double)t_multithread << "X" << std::endl; + std::cout << "sum_multi_thread (nbThreads=" << nbThreads << ")=" << sum_multi_thread << " ; t_multi_thread=" << t_multi_thread + << " ms ; mean=" << t_multi_thread / (double)nbIterations << " ms" << std::endl; + std::cout << "Speed-up=" << t_single_thread / (double)t_multi_thread << "X" << std::endl; - if (sum_single_thread != I.getSize() || sum_single_multithread != I.getSize()) { + if (sum_single_thread != I.getSize() || sum_multi_thread != I.getSize()) { std::cerr << "Problem with histogram!" << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/tools/threading/testMutex.cpp b/modules/core/test/tools/threading/testMutex.cpp deleted file mode 100644 index 61e59352e7..0000000000 --- a/modules/core/test/tools/threading/testMutex.cpp +++ /dev/null @@ -1,98 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 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. - * - * Description: - * Test threading capabilities. - * -*****************************************************************************/ - -/*! - - \example testMutex.cpp - - \brief Test mutexes and threading capabilities. - -*/ - -#include - -#include -#include - -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) - -int thread_counter = 0; -vpMutex mutex; - -vpThread::Return doSomeThing(vpThread::Args args) -{ - mutex.lock(); - unsigned int thread_id = *((unsigned int *)args); - - std::cout << "Started job " << thread_counter << " with id " << thread_id << std::endl; - - for (unsigned long i = 0; i < (0xFFFF); i++) { - }; - - std::cout << "Ended job " << thread_counter << std::endl; - - thread_counter++; - mutex.unlock(); - - return 0; -} - -int main(void) -{ - unsigned int nthread = 10; - vpThread *thread = new vpThread[nthread]; - unsigned int *thread_id = new unsigned int[nthread]; - - for (unsigned int i = 0; i < nthread; i++) { - thread_id[i] = i; - thread[i].create((vpThread::Fn)&doSomeThing, (vpThread::Args)&thread_id[i]); - } - - delete[] thread; - delete[] thread_id; - - return EXIT_SUCCESS; -} - -#else -int main() -{ -#if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX - std::cout << "You should enable pthread usage and rebuild ViSP..." << std::endl; -#else - std::cout << "Multi-threading seems not supported on this platform" << std::endl; -#endif -} -#endif diff --git a/modules/core/test/tools/threading/testThread.cpp b/modules/core/test/tools/threading/testThread.cpp deleted file mode 100644 index f048d4b20b..0000000000 --- a/modules/core/test/tools/threading/testThread.cpp +++ /dev/null @@ -1,137 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 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. - * - * Description: - * Test threading capabilities. - * -*****************************************************************************/ - -/*! - - \example testThread.cpp - - \brief Test threading capabilities. - -*/ - -#include - -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) - -//! [Code] -#include - -#include -#include -#include - -vpMutex g_mutex_cout; - -vpThread::Return myFooFunction(vpThread::Args args) -{ - (void)(args); // Avoid warning: unused parameter args - // do stuff... - return 0; -} - -vpThread::Return myBarFunction(vpThread::Args args) -{ - (void)(args); // Avoid warning: unused parameter args - // do stuff... - return 0; -} - -vpThread::Return myQuxFunction(vpThread::Args args) -{ - unsigned int args_ = *((unsigned int *)args); - g_mutex_cout.lock(); - std::cout << "qux arg: " << args_ << std::endl; - g_mutex_cout.unlock(); - // do stuff... - return 0; -} - -int main() -{ - unsigned int qux_arg = 12; - vpThread foo; - vpThread bar((vpThread::Fn)myBarFunction); - vpThread qux((vpThread::Fn)myQuxFunction, - (vpThread::Args)&qux_arg); // Pass qux_arg to myQuxFunction() function - - vpTime::wait(1000); // Sleep 1s to ensure myQuxFunction() internal printings - g_mutex_cout.lock(); - std::cout << "Joinable after construction:" << std::endl; - std::cout << "foo: " << foo.joinable() << std::endl; - std::cout << "bar: " << bar.joinable() << std::endl; - std::cout << "qux: " << qux.joinable() << std::endl; - g_mutex_cout.unlock(); - - foo.create((vpThread::Fn)myFooFunction); - - g_mutex_cout.lock(); - std::cout << "Joinable after creation:" << std::endl; - std::cout << "foo: " << foo.joinable() << std::endl; - std::cout << "bar: " << bar.joinable() << std::endl; - std::cout << "qux: " << qux.joinable() << std::endl; - g_mutex_cout.unlock(); - - if (foo.joinable()) - foo.join(); - if (bar.joinable()) - bar.join(); - if (qux.joinable()) - qux.join(); - - g_mutex_cout.lock(); - std::cout << "Joinable after joining:" << std::endl; - std::cout << "foo: " << foo.joinable() << std::endl; - std::cout << "bar: " << bar.joinable() << std::endl; - std::cout << "qux: " << qux.joinable() << std::endl; - g_mutex_cout.unlock(); - - return EXIT_SUCCESS; -} -//! [Code] - -#else - -#include - -int main() -{ -#if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX - std::cout << "You should enable pthread usage and rebuild ViSP..." << std::endl; -#else - std::cout << "Multi-threading seems not supported on this platform" << std::endl; -#endif - return EXIT_SUCCESS; -} -#endif diff --git a/modules/core/test/tools/threading/testThread2.cpp b/modules/core/test/tools/threading/testThread2.cpp deleted file mode 100644 index 10ed60cfc5..0000000000 --- a/modules/core/test/tools/threading/testThread2.cpp +++ /dev/null @@ -1,205 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 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. - * - * Description: - * Test threading capabilities (extended). - * -*****************************************************************************/ - -/*! - \example testThread2.cpp - - \brief Test threading capabilities (extended). -*/ - -#include - -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) - -#include -#include -#include - -#include -#include -#include - -namespace -{ -//! [functor-thread-example declaration] -class vpArithmFunctor -{ -public: - vpArithmFunctor(const vpColVector &v1, const vpColVector &v2, unsigned int start, unsigned int end) - : m_add(), m_mul(), m_v1(v1), m_v2(v2), m_indexStart(start), m_indexEnd(end) - { } - - vpArithmFunctor() : m_add(), m_mul(), m_v1(), m_v2(), m_indexStart(0), m_indexEnd(0) { } - - void operator()() { computeImpl(); } - - vpColVector getVectorAdd() const { return m_add; } - - vpColVector getVectorMul() const { return m_mul; } - -private: - vpColVector m_add; - vpColVector m_mul; - vpColVector m_v1; - vpColVector m_v2; - unsigned int m_indexStart; - unsigned int m_indexEnd; - - void computeImpl() - { - m_add.resize(m_indexEnd - m_indexStart); - m_mul.resize(m_indexEnd - m_indexStart); - - // to simulate a long computation - for (int iter = 0; iter < 100; iter++) { - for (unsigned int i = m_indexStart, cpt = 0; i < m_indexEnd; i++, cpt++) { - m_add[cpt] = m_v1[i] + m_v2[i]; - m_mul[cpt] = m_v1[i] * m_v2[i]; - } - } - } -}; -//! [functor-thread-example declaration] - -//! [functor-thread-example threadFunction] -vpThread::Return arithmThread(vpThread::Args args) -{ - vpArithmFunctor *f = static_cast(args); - (*f)(); - return 0; -} -//! [functor-thread-example threadFunction] - -void insert(vpColVector &v1, const vpColVector &v2) -{ - unsigned int size = v1.size(); - v1.resize(size + v2.size(), false); - - for (unsigned int i = 0, cpt = size; i < v2.size(); i++, cpt++) { - v1[cpt] = v2[i]; - } -} - -bool check(const vpColVector &v1, const vpColVector &v2, const vpColVector &res_add, const vpColVector &res_mul) -{ - double add = 0.0, mul = 0.0; - for (unsigned int i = 0; i < v1.size(); i++) { - add += v1[i] + v2[i]; - mul += v1[i] * v2[i]; - } - - double add_th = res_add.sum(); - double mul_th = res_mul.sum(); - - std::cout << "add=" << add << " ; add_th=" << add_th << std::endl; - std::cout << "mul=" << mul << " ; mul_th=" << mul_th << std::endl; - - if (!vpMath::equal(add, add_th, std::numeric_limits::epsilon())) { - std::cerr << "Problem: add=" << add << " ; add_th=" << add_th << std::endl; - return false; - } - - if (!vpMath::equal(mul, mul_th, std::numeric_limits::epsilon())) { - std::cerr << "Problem: mul=" << mul << " ; mul_th=" << mul_th << std::endl; - return false; - } - - return true; -} -} // namespace - -int main() -{ - unsigned int nb_threads = 4; - unsigned int size = 1000007; - srand((unsigned int)time(nullptr)); - - vpColVector v1(size), v2(size); - for (unsigned int i = 0; i < size; i++) { - v1[i] = rand() % 101; - v2[i] = rand() % 101; - } - - //! [functor-thread-example threadCreation] - std::vector threads(nb_threads); - std::vector functors(nb_threads); - unsigned int split = size / nb_threads; - for (unsigned int i = 0; i < nb_threads; i++) { - if (i < nb_threads - 1) { - functors[i] = vpArithmFunctor(v1, v2, i * split, (i + 1) * split); - } - else { - functors[i] = vpArithmFunctor(v1, v2, i * split, size); - } - - std::cout << "Create thread: " << i << std::endl; - threads[i].create((vpThread::Fn)arithmThread, (vpThread::Args)&functors[i]); - } - //! [functor-thread-example threadCreation] - - //! [functor-thread-example getResults] - vpColVector res_add, res_mul; - for (size_t i = 0; i < nb_threads; i++) { - std::cout << "Join thread: " << i << std::endl; - threads[i].join(); - - insert(res_add, functors[i].getVectorAdd()); - insert(res_mul, functors[i].getVectorMul()); - } - //! [functor-thread-example getResults] - - if (!check(v1, v2, res_add, res_mul)) { - return EXIT_FAILURE; - } - - std::cout << "testThread2 is ok!" << std::endl; - return EXIT_SUCCESS; -} - -#else - -#include -#include - -int main() -{ -#if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX - std::cout << "You should enable pthread usage and rebuild ViSP..." << std::endl; -#else - std::cout << "Multi-threading seems not supported on this platform" << std::endl; -#endif - return EXIT_SUCCESS; -} -#endif diff --git a/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp b/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp index f8babbc1f4..bb17b37a4a 100644 --- a/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp +++ b/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp @@ -1179,7 +1179,6 @@ void vpDetectorDNNOpenCV::setParsingMethod(const DNNResultsParsingType &typePars } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDetectorDNNOpenCV.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDetectorDNNOpenCV.cpp.o) has no symbols void dummy_vpDetectorDNN() { }; #endif diff --git a/modules/detection/src/face/vpDetectorFace.cpp b/modules/detection/src/face/vpDetectorFace.cpp index ab62cdbcf3..be790f1cb7 100644 --- a/modules/detection/src/face/vpDetectorFace.cpp +++ b/modules/detection/src/face/vpDetectorFace.cpp @@ -46,7 +46,7 @@ bool vpSortLargestFace(cv::Rect rect1, cv::Rect rect2) { return (rect1.area() > /*! Default constructor. */ -vpDetectorFace::vpDetectorFace() : m_faces(), m_face_cascade(), m_frame_gray() {} +vpDetectorFace::vpDetectorFace() : m_faces(), m_face_cascade(), m_frame_gray() { } /*! Set the name of the OpenCV cascade classifier file used for face detection. @@ -141,7 +141,6 @@ bool vpDetectorFace::detect(const cv::Mat &frame_gray) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDetectorFace.cpp.o) has no -// symbols -void dummy_vpDetectorFace(){}; +// Work around to avoid warning: libvisp_core.a(vpDetectorFace.cpp.o) has no symbols +void dummy_vpDetectorFace() { }; #endif diff --git a/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h b/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h old mode 100755 new mode 100644 diff --git a/modules/gui/include/visp3/gui/vpPclViewer.h b/modules/gui/include/visp3/gui/vpPclViewer.h old mode 100755 new mode 100644 index ace4fb1363..28bc9ec785 --- a/modules/gui/include/visp3/gui/vpPclViewer.h +++ b/modules/gui/include/visp3/gui/vpPclViewer.h @@ -37,7 +37,7 @@ #include -#if defined(VISP_HAVE_PCL) +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) // System #include #include @@ -253,7 +253,7 @@ class VISP_EXPORT vpPclViewer std::thread m_threadDisplay; /*!< The non-blocking drawing thread.*/ bool m_hasToRun; /*!< If true, the drawing thread is running. Otherwise, it is stopped.*/ std::string m_title; /*!< The title of the viewer window.*/ - bool m_hasToSavePCDs; /*!< If true, thhe point clouds will be saved at each iteration of the drawing thread.*/ + bool m_hasToSavePCDs; /*!< If true, the point clouds will be saved at each iteration of the drawing thread.*/ std::string m_outFolder; /*!< If non empty, the path to the folders where the point clouds will be saved.*/ }; #endif // #if defined(VISP_HAVE_PCL) diff --git a/modules/gui/src/display/vpDisplayGTK.cpp b/modules/gui/src/display/vpDisplayGTK.cpp index b070bb9c85..6bb25f78f5 100644 --- a/modules/gui/src/display/vpDisplayGTK.cpp +++ b/modules/gui/src/display/vpDisplayGTK.cpp @@ -1589,7 +1589,6 @@ unsigned int vpDisplayGTK::getScreenHeight() } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayGTK.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayGTK.cpp.o) has no symbols void dummy_vpDisplayGTK() { }; #endif diff --git a/modules/gui/src/display/vpDisplayOpenCV.cpp b/modules/gui/src/display/vpDisplayOpenCV.cpp index d0b73d743d..a31918ab57 100644 --- a/modules/gui/src/display/vpDisplayOpenCV.cpp +++ b/modules/gui/src/display/vpDisplayOpenCV.cpp @@ -2174,7 +2174,6 @@ void vpDisplayOpenCV::overlay(std::function overlay_function, d } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayOpenCV.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayOpenCV.cpp.o) has no symbols void dummy_vpDisplayOpenCV() { }; #endif diff --git a/modules/gui/src/display/vpDisplayX.cpp b/modules/gui/src/display/vpDisplayX.cpp index bc9ec6d092..f2c42f3d1f 100644 --- a/modules/gui/src/display/vpDisplayX.cpp +++ b/modules/gui/src/display/vpDisplayX.cpp @@ -2661,7 +2661,6 @@ bool vpDisplayX::getPointerPosition(vpImagePoint &ip) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayX.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayX.cpp.o) has no symbols void dummy_vpDisplayX() { }; #endif diff --git a/modules/gui/src/display/windows/vpD3DRenderer.cpp b/modules/gui/src/display/windows/vpD3DRenderer.cpp index e2ce40fae9..caae08fa6e 100644 --- a/modules/gui/src/display/windows/vpD3DRenderer.cpp +++ b/modules/gui/src/display/windows/vpD3DRenderer.cpp @@ -1191,8 +1191,7 @@ void vpD3DRenderer::getImage(vpImage &I) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no symbols void dummy_vpD3DRenderer() { }; #endif #endif diff --git a/modules/gui/src/display/windows/vpDisplayD3D.cpp b/modules/gui/src/display/windows/vpDisplayD3D.cpp index a00ac23d59..ef67a63a1e 100644 --- a/modules/gui/src/display/windows/vpDisplayD3D.cpp +++ b/modules/gui/src/display/windows/vpDisplayD3D.cpp @@ -189,7 +189,6 @@ vpDisplayD3D::vpDisplayD3D(vpImage &I, int winx, int winy, const } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayD3D.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayD3D.cpp.o) has no symbols void dummy_vpDisplayD3D() { }; #endif diff --git a/modules/gui/src/display/windows/vpDisplayGDI.cpp b/modules/gui/src/display/windows/vpDisplayGDI.cpp index 5140f60cbc..37581e306a 100644 --- a/modules/gui/src/display/windows/vpDisplayGDI.cpp +++ b/modules/gui/src/display/windows/vpDisplayGDI.cpp @@ -189,7 +189,6 @@ vpDisplayGDI::vpDisplayGDI(vpImage &I, int winx, int winy, const } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayGDI.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayGDI.cpp.o) has no symbols void dummy_vpDisplayGDI() { }; #endif diff --git a/modules/gui/src/display/windows/vpDisplayWin32.cpp b/modules/gui/src/display/windows/vpDisplayWin32.cpp index 410db2674f..a8d5013761 100644 --- a/modules/gui/src/display/windows/vpDisplayWin32.cpp +++ b/modules/gui/src/display/windows/vpDisplayWin32.cpp @@ -906,7 +906,6 @@ unsigned int vpDisplayWin32::getScreenHeight() return height; } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayWin32.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayWin32.cpp.o) has no symbols void dummy_vpDisplayWin32() { }; #endif diff --git a/modules/gui/src/display/windows/vpGDIRenderer.cpp b/modules/gui/src/display/windows/vpGDIRenderer.cpp index eed3809185..7a8de6d807 100644 --- a/modules/gui/src/display/windows/vpGDIRenderer.cpp +++ b/modules/gui/src/display/windows/vpGDIRenderer.cpp @@ -1029,7 +1029,6 @@ void vpGDIRenderer::getImage(vpImage &I) } #endif #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpGDIRenderer.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpGDIRenderer.cpp.o) has no symbols void dummy_vpGDIRenderer() { }; #endif diff --git a/modules/gui/src/display/windows/vpWin32API.cpp b/modules/gui/src/display/windows/vpWin32API.cpp index 105853e7f4..ca65e445bd 100644 --- a/modules/gui/src/display/windows/vpWin32API.cpp +++ b/modules/gui/src/display/windows/vpWin32API.cpp @@ -50,7 +50,7 @@ DWORD vpProcessErrors(const std::string &api_name) FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM | FORMAT_MESSAGE_IGNORE_INSERTS, nullptr, err, MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (LPTSTR)&lpMsgBuf, 0, nullptr); std::cout << "call to " << api_name << " failed with the following error code: " << err << "(" << (LPTSTR)lpMsgBuf - << ")" << std::endl; + << ")" << std::endl; return err; } @@ -136,7 +136,6 @@ HBITMAP vpCreateBitmap(int nWidth, int nHeight, UINT cPlanes, UINT cBitsPerPel, } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpWin32API.cpp.o) has no -// symbols -void dummy_vpWin32API(){}; +// Work around to avoid warning: libvisp_core.a(vpWin32API.cpp.o) has no symbols +void dummy_vpWin32API() { }; #endif diff --git a/modules/gui/src/display/windows/vpWin32Window.cpp b/modules/gui/src/display/windows/vpWin32Window.cpp index 3b2a0962b6..2dd7d3c0d4 100644 --- a/modules/gui/src/display/windows/vpWin32Window.cpp +++ b/modules/gui/src/display/windows/vpWin32Window.cpp @@ -156,13 +156,13 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) // case WM_SYSKEYUP: case WM_KEYDOWN: // case WM_KEYUP: - { - GetKeyNameText((LONG)lParam, window->lpString, - 10); // 10 is the size of lpString - // window->key = MapVirtualKey(wParam, MAPVK_VK_TO_CHAR); - vpReleaseSemaphore(window->semaKey, 1, nullptr); - break; - } + { + GetKeyNameText((LONG)lParam, window->lpString, + 10); // 10 is the size of lpString + // window->key = MapVirtualKey(wParam, MAPVK_VK_TO_CHAR); + vpReleaseSemaphore(window->semaKey, 1, nullptr); + break; + } case WM_COMMAND: @@ -298,9 +298,11 @@ void vpWin32Window::initWindow(const char *title, int posx, int posy, unsigned i if (val == -1) { std::cout << "GetMessage error:" << GetLastError() << std::endl; break; - } else if (val == 0) { + } + else if (val == 0) { break; - } else { + } + else { if (!TranslateAccelerator(msg.hwnd, nullptr, &msg)) { TranslateMessage(&msg); DispatchMessage(&msg); @@ -311,7 +313,6 @@ void vpWin32Window::initWindow(const char *title, int posx, int posy, unsigned i #endif #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpWin32Window.cpp.o) has no -// symbols -void dummy_vpWin32Window(){}; +// Work around to avoid warning: libvisp_core.a(vpWin32Window.cpp.o) has no symbols +void dummy_vpWin32Window() { }; #endif diff --git a/modules/gui/src/plot/vpPlotCurve.cpp b/modules/gui/src/plot/vpPlotCurve.cpp index c35ded35ee..ea4c221f73 100644 --- a/modules/gui/src/plot/vpPlotCurve.cpp +++ b/modules/gui/src/plot/vpPlotCurve.cpp @@ -46,9 +46,8 @@ #if defined(VISP_HAVE_DISPLAY) vpPlotCurve::vpPlotCurve() : color(vpColor::red), curveStyle(point), thickness(1), nbPoint(0), lastPoint(), pointListx(), pointListy(), - pointListz(), legend(), xmin(0), xmax(0), ymin(0), ymax(0) -{ -} + pointListz(), legend(), xmin(0), xmax(0), ymin(0), ymax(0) +{ } vpPlotCurve::~vpPlotCurve() { @@ -73,14 +72,16 @@ void vpPlotCurve::plotPoint(const vpImage &I, const vpImagePoint if (iP.get_i() <= lastPoint.get_i()) { top = iP.get_i() - 5; height = lastPoint.get_i() - top + 10; - } else { + } + else { top = lastPoint.get_i() - 5; height = iP.get_i() - top + 10; } if (iP.get_j() <= lastPoint.get_j()) { left = iP.get_j() - 5; width = lastPoint.get_j() - left + 10; - } else { + } + else { left = lastPoint.get_j() - 5; width = iP.get_j() - left + 10; } @@ -114,8 +115,7 @@ void vpPlotCurve::plotList(const vpImage &I, double xorg, double } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpPlotCurve.cpp.o) has no -// symbols -void dummy_vpPlotCurve(){}; +// Work around to avoid warning: libvisp_core.a(vpPlotCurve.cpp.o) has no symbols +void dummy_vpPlotCurve() { }; #endif #endif diff --git a/modules/gui/src/plot/vpPlotGraph.cpp b/modules/gui/src/plot/vpPlotGraph.cpp index 8ba2d3c383..d27f45d54a 100644 --- a/modules/gui/src/plot/vpPlotGraph.cpp +++ b/modules/gui/src/plot/vpPlotGraph.cpp @@ -1339,8 +1339,7 @@ vpHomogeneousMatrix vpPlotGraph::navigation(const vpImage &I, boo } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpPlotGraph.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpPlotGraph.cpp.o) has no symbols void dummy_vpPlotGraph() { }; #endif #endif diff --git a/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp b/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp old mode 100755 new mode 100644 diff --git a/modules/gui/src/pointcloud/vpPclViewer.cpp b/modules/gui/src/pointcloud/vpPclViewer.cpp old mode 100755 new mode 100644 index 93e14b888d..efeda9ee89 --- a/modules/gui/src/pointcloud/vpPclViewer.cpp +++ b/modules/gui/src/pointcloud/vpPclViewer.cpp @@ -35,7 +35,7 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS #include -#if defined(VISP_HAVE_PCL) +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) // PCL #include @@ -487,8 +487,7 @@ void vpPclViewer::threadUpdateSurfaceOriginalColor(const pclPointCloudPointXYZRG } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no symbols void dummy_vpPCLPointCLoudVisualization() { }; #endif #endif diff --git a/modules/io/include/visp3/io/vpImageQueue.h b/modules/io/include/visp3/io/vpImageQueue.h index 75381cd77a..e7869d1036 100644 --- a/modules/io/include/visp3/io/vpImageQueue.h +++ b/modules/io/include/visp3/io/vpImageQueue.h @@ -36,7 +36,7 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/io/include/visp3/io/vpImageStorageWorker.h b/modules/io/include/visp3/io/vpImageStorageWorker.h index 9fc16fab51..1eb0e79b2b 100644 --- a/modules/io/include/visp3/io/vpImageStorageWorker.h +++ b/modules/io/include/visp3/io/vpImageStorageWorker.h @@ -36,7 +36,7 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/io/src/parallel-port/vpParallelPort.cpp b/modules/io/src/parallel-port/vpParallelPort.cpp index c8c0edd62e..26d39c4533 100644 --- a/modules/io/src/parallel-port/vpParallelPort.cpp +++ b/modules/io/src/parallel-port/vpParallelPort.cpp @@ -159,7 +159,6 @@ void vpParallelPort::close() } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpParallelPort.cpp.o) has no -// symbols -void dummy_vpParallelPort(){}; +// Work around to avoid warning: libvisp_core.a(vpParallelPort.cpp.o) has no symbols +void dummy_vpParallelPort() { }; #endif diff --git a/modules/io/test/image-with-dataset/perfImageLoadSave.cpp b/modules/io/test/image-with-dataset/perfImageLoadSave.cpp index 93d5d3dfd1..815525b09f 100644 --- a/modules/io/test/image-with-dataset/perfImageLoadSave.cpp +++ b/modules/io/test/image-with-dataset/perfImageLoadSave.cpp @@ -35,7 +35,7 @@ #include -#ifdef VISP_HAVE_CATCH2 +#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/io/test/image-with-dataset/testImageLoadSave.cpp b/modules/io/test/image-with-dataset/testImageLoadSave.cpp index a58ccb560a..3d3ae6d855 100644 --- a/modules/io/test/image-with-dataset/testImageLoadSave.cpp +++ b/modules/io/test/image-with-dataset/testImageLoadSave.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_CATCH2) && (VISP_HAVE_DATASET_VERSION >= 0x030500) +#if defined(VISP_HAVE_CATCH2) && (VISP_HAVE_DATASET_VERSION >= 0x030500) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/java/generator/gen2.py b/modules/java/generator/gen2.py old mode 100755 new mode 100644 diff --git a/modules/java/generator/gen_java.py b/modules/java/generator/gen_java.py old mode 100755 new mode 100644 diff --git a/modules/java/generator/hdr_parser.py b/modules/java/generator/hdr_parser.py old mode 100755 new mode 100644 diff --git a/modules/robot/include/visp3/robot/vpPololu.h b/modules/robot/include/visp3/robot/vpPololu.h index 372fa46cf1..a4c16e6bba 100644 --- a/modules/robot/include/visp3/robot/vpPololu.h +++ b/modules/robot/include/visp3/robot/vpPololu.h @@ -36,7 +36,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpQbDevice.h b/modules/robot/include/visp3/robot/vpQbDevice.h index 8d72d6cc34..034df6731e 100644 --- a/modules/robot/include/visp3/robot/vpQbDevice.h +++ b/modules/robot/include/visp3/robot/vpQbDevice.h @@ -37,7 +37,7 @@ #define _vpQbDevice_h_ #include -#ifdef VISP_HAVE_QBDEVICE +#if defined(VISP_HAVE_QBDEVICE) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpQbSoftHand.h b/modules/robot/include/visp3/robot/vpQbSoftHand.h index d4dbd9995a..3b26d947fc 100644 --- a/modules/robot/include/visp3/robot/vpQbSoftHand.h +++ b/modules/robot/include/visp3/robot/vpQbSoftHand.h @@ -35,7 +35,7 @@ #define _vpQbSoftHand_h_ #include -#ifdef VISP_HAVE_QBDEVICE +#if defined(VISP_HAVE_QBDEVICE) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpRobotBebop2.h b/modules/robot/include/visp3/robot/vpRobotBebop2.h index 5261436a0d..3c4576607b 100644 --- a/modules/robot/include/visp3/robot/vpRobotBebop2.h +++ b/modules/robot/include/visp3/robot/vpRobotBebop2.h @@ -41,7 +41,7 @@ #include -#ifdef VISP_HAVE_ARSDK +#if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/robot/include/visp3/robot/vpRobotBiclops.h b/modules/robot/include/visp3/robot/vpRobotBiclops.h index 0c6999c7e6..d4c0ac0416 100644 --- a/modules/robot/include/visp3/robot/vpRobotBiclops.h +++ b/modules/robot/include/visp3/robot/vpRobotBiclops.h @@ -36,7 +36,7 @@ #include -#ifdef VISP_HAVE_BICLOPS +#if defined(VISP_HAVE_BICLOPS) && defined(VISP_HAVE_THREADS) /* ------------------------------------------------------------------------ */ /* --- INCLUDES ----------------------------------------------------------- */ diff --git a/modules/robot/include/visp3/robot/vpRobotFranka.h b/modules/robot/include/visp3/robot/vpRobotFranka.h index c7d23ad620..f07ea3e808 100644 --- a/modules/robot/include/visp3/robot/vpRobotFranka.h +++ b/modules/robot/include/visp3/robot/vpRobotFranka.h @@ -36,7 +36,7 @@ #include -#ifdef VISP_HAVE_FRANKA +#if defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpRobotMavsdk.h b/modules/robot/include/visp3/robot/vpRobotMavsdk.h index 5b6bba8156..376fcd2025 100644 --- a/modules/robot/include/visp3/robot/vpRobotMavsdk.h +++ b/modules/robot/include/visp3/robot/vpRobotMavsdk.h @@ -40,7 +40,8 @@ // Check if std:c++17 or higher. // Here we cannot use (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) in the declaration of the class -#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) +#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \ + && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpRobotPololuPtu.h b/modules/robot/include/visp3/robot/vpRobotPololuPtu.h index aacac886f3..30031bba61 100644 --- a/modules/robot/include/visp3/robot/vpRobotPololuPtu.h +++ b/modules/robot/include/visp3/robot/vpRobotPololuPtu.h @@ -36,7 +36,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h b/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h index 3bb77f9b16..a84db8f60c 100644 --- a/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h +++ b/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h @@ -41,20 +41,14 @@ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include // std::fabs #include // numeric_limits -#if defined(_WIN32) -// Include WinSock2.h before windows.h to ensure that winsock.h is not -// included by windows.h since winsock.h and winsock2.h are incompatible -#include -#include -#elif defined(VISP_HAVE_PTHREAD) -#include -#endif -#include +#include +#include + #include #include #include @@ -114,23 +108,18 @@ class VISP_EXPORT vpRobotWireFrameSimulator : protected vpWireFrameSimulator, pu /*! The velocity in the current frame (articular, camera or reference)*/ vpColVector velocity; -#if defined(_WIN32) - HANDLE hThread; -#elif defined(VISP_HAVE_PTHREAD) - pthread_t thread; - pthread_attr_t attr; -#endif + std::thread *m_thread; - vpMutex m_mutex_fMi; - vpMutex m_mutex_eMc; - vpMutex m_mutex_artVel; - vpMutex m_mutex_artCoord; - vpMutex m_mutex_velocity; - vpMutex m_mutex_display; - vpMutex m_mutex_robotStop; - vpMutex m_mutex_frame; - vpMutex m_mutex_setVelocityCalled; - vpMutex m_mutex_scene; + std::mutex m_mutex_fMi; + std::mutex m_mutex_eMc; + std::mutex m_mutex_artVel; + std::mutex m_mutex_artCoord; + std::mutex m_mutex_velocity; + std::mutex m_mutex_display; + std::mutex m_mutex_robotStop; + std::mutex m_mutex_frame; + std::mutex m_mutex_setVelocityCalled; + std::mutex m_mutex_scene; bool displayBusy; @@ -335,26 +324,18 @@ class VISP_EXPORT vpRobotWireFrameSimulator : protected vpWireFrameSimulator, pu /** @name Protected Member Functions Inherited from vpRobotWireFrameSimulator */ //@{ -/*! - * Function used to launch the thread which moves the robot. - */ -#if defined(_WIN32) - static DWORD WINAPI launcher(LPVOID lpParam) - { - (static_cast(lpParam))->updateArticularPosition(); - return 0; - } -#elif defined(VISP_HAVE_PTHREAD) - static void *launcher(void *arg) + /*! + * Function used to launch the thread which moves the robot. + */ + static void launcher(vpRobotWireFrameSimulator &simulator) { - (reinterpret_cast(arg))->updateArticularPosition(); - // pthread_exit((void*) 0); - return nullptr; + simulator.updateArticularPosition(); } -#endif - /*! Method lauched by the thread to compute the position of the robot in the - * articular frame. */ + /*! + * Method launched by the thread to compute the position of the robot in the + * articular frame. + */ virtual void updateArticularPosition() = 0; /*! Method used to check if the robot reached a joint limit. */ virtual int isInJointLimit() = 0; diff --git a/modules/robot/include/visp3/robot/vpSimulatorAfma6.h b/modules/robot/include/visp3/robot/vpSimulatorAfma6.h index bfbc62e863..b15ebe6bdf 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorAfma6.h +++ b/modules/robot/include/visp3/robot/vpSimulatorAfma6.h @@ -44,7 +44,7 @@ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) /*! * \class vpSimulatorAfma6 diff --git a/modules/robot/include/visp3/robot/vpSimulatorViper850.h b/modules/robot/include/visp3/robot/vpSimulatorViper850.h index fe39abee69..854f7646f9 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorViper850.h +++ b/modules/robot/include/visp3/robot/vpSimulatorViper850.h @@ -40,7 +40,7 @@ */ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp b/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp index 20792b37d3..7c022269f1 100644 --- a/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp +++ b/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp @@ -34,7 +34,7 @@ *****************************************************************************/ #include -#ifdef VISP_HAVE_QBDEVICE +#if defined(VISP_HAVE_QBDEVICE) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp b/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp index 5c8aca7159..5f5e3c3322 100644 --- a/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp +++ b/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp @@ -34,7 +34,7 @@ *****************************************************************************/ #include -#ifdef VISP_HAVE_QBDEVICE +#if defined(VISP_HAVE_QBDEVICE) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/robot/src/light/vpRingLight.cpp b/modules/robot/src/light/vpRingLight.cpp index 193e882168..27f469e6ea 100644 --- a/modules/robot/src/light/vpRingLight.cpp +++ b/modules/robot/src/light/vpRingLight.cpp @@ -214,7 +214,6 @@ void vpRingLight::off() } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRingLight.cpp.o) has no -// symbols -void dummy_vpRingLight(){}; +// Work around to avoid warning: libvisp_robot.a(vpRingLight.cpp.o) has no symbols +void dummy_vpRingLight() { }; #endif diff --git a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp index c79d06eb55..f03344475b 100644 --- a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp +++ b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp @@ -1754,7 +1754,6 @@ void vpRobotAfma4::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotAfma4.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotAfma4.cpp.o) has no symbols void dummy_vpRobotAfma4() { }; #endif diff --git a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp index 80f1a4d1f9..73709afcb9 100644 --- a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp +++ b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp @@ -187,8 +187,9 @@ vpRobotAfma6::vpRobotAfma6(bool verbose) : vpAfma6(), vpRobot() try { this->init(); this->setRobotState(vpRobot::STATE_STOP); - } catch (...) { - // vpERROR_TRACE("Error caught") ; + } + catch (...) { + // vpERROR_TRACE("Error caught") ; throw; } positioningVelocity = defaultPositioningVelocity; @@ -602,9 +603,10 @@ vpRobot::vpRobotStateType vpRobotAfma6::setRobotState(vpRobot::vpRobotStateType if (vpRobot::STATE_VELOCITY_CONTROL == getRobotState()) { std::cout << "Change the control mode from velocity to position control.\n"; Try(PrimitiveSTOP_Afma6()); - } else { - // std::cout << "Change the control mode from stop to position - // control.\n"; + } + else { + // std::cout << "Change the control mode from stop to position + // control.\n"; } this->powerOn(); break; @@ -672,20 +674,23 @@ void vpRobotAfma6::powerOn(void) Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); if (EStopStatus == ESTOP_AUTO) { break; // exit for loop - } else if (EStopStatus == ESTOP_MANUAL) { + } + else if (EStopStatus == ESTOP_MANUAL) { break; // exit for loop - } else if (EStopStatus == ESTOP_ACTIVATED) { + } + else if (EStopStatus == ESTOP_ACTIVATED) { if (firsttime) { std::cout << "Emergency stop is activated! \n" - << "Check the emergency stop button and push the yellow " - "button before continuing." - << std::endl; + << "Check the emergency stop button and push the yellow " + "button before continuing." + << std::endl; firsttime = false; } fprintf(stdout, "Remaining time %us \r", nitermax - i); fflush(stdout); CAL_Wait(1); - } else { + } + else { std::cout << "Sorry there is an error on the emergency chain." << std::endl; std::cout << "You have to call Adept for maintenance..." << std::endl; // Free allocated resources @@ -835,7 +840,8 @@ void vpRobotAfma6::get_eJe(vpMatrix &eJe) try { vpAfma6::get_eJe(q, eJe); - } catch (...) { + } + catch (...) { vpERROR_TRACE("catch exception "); throw; } @@ -879,7 +885,8 @@ void vpRobotAfma6::get_fJe(vpMatrix &fJe) try { vpAfma6::get_fJe(q, fJe); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -1149,8 +1156,9 @@ void vpRobotAfma6::setPosition(const vpRobot::vpControlFrameType frame, const vp } Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity)); Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000)); - } else { - // Cartesian position is out of range + } + else { + // Cartesian position is out of range error = -1; } @@ -1186,8 +1194,9 @@ void vpRobotAfma6::setPosition(const vpRobot::vpControlFrameType frame, const vp } Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity)); Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000)); - } else { - // Cartesian position is out of range + } + else { + // Cartesian position is out of range error = -1; } @@ -1298,7 +1307,8 @@ void vpRobotAfma6::setPosition(const vpRobot::vpControlFrameType frame, double p position[5] = pos6; setPosition(frame, position); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -1674,12 +1684,14 @@ void vpRobotAfma6::setVelocity(const vpRobot::vpControlFrameType frame, const vp if (axisInJoint[i]) std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl; } - } else { + } + else { printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt); if (TryString != nullptr) { // The statement is in TryString, but we need to check the validity printf(" Error sentence %s\n", TryString); // Print the TryString - } else { + } + else { printf("\n"); } } @@ -1823,7 +1835,8 @@ void vpRobotAfma6::getVelocity(const vpRobot::vpControlFrameType frame, vpColVec "vpRobotAfma6::getVelocity() not implemented in end-effector")); } } - } else { + } + else { first_time_getvel = false; } @@ -2239,7 +2252,8 @@ void vpRobotAfma6::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto return; } } - } else { + } + else { first_time_getdis = false; } @@ -2279,7 +2293,8 @@ bool vpRobotAfma6::checkJointLimits(vpColVector &jointsStatus) std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl; jointsStatus[i] = axisInJoint[i]; status = false; - } else { + } + else { jointsStatus[i] = 0; } } @@ -2294,7 +2309,6 @@ bool vpRobotAfma6::checkJointLimits(vpColVector &jointsStatus) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotAfma6.cpp.o) has no -// symbols -void dummy_vpRobotAfma6(){}; +// Work around to avoid warning: libvisp_robot.a(vpRobotAfma6.cpp.o) has no symbols +void dummy_vpRobotAfma6() { }; #endif diff --git a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp index 893258a983..4744a3d099 100644 --- a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp +++ b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp @@ -33,7 +33,7 @@ #include -#ifdef VISP_HAVE_BICLOPS +#if defined(VISP_HAVE_BICLOPS) && defined(VISP_HAVE_THREADS) #include // std::fabs #include @@ -854,7 +854,6 @@ void vpRobotBiclops::getDisplacement(vpRobot::vpControlFrameType frame, vpColVec } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotBiclops.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotBiclops.cpp.o) has no symbols void dummy_vpRobotBiclops() { }; #endif diff --git a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp index 5a7015e323..5885ca333c 100644 --- a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp +++ b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp @@ -35,7 +35,7 @@ #include -#ifdef VISP_HAVE_FRANKA +#if defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp index 1aafc581e8..54792a5670 100644 --- a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp +++ b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp @@ -36,7 +36,8 @@ #include // Check if std:c++17 or higher -#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) +#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \ + && defined(VISP_HAVE_THREADS) #include #include @@ -1579,7 +1580,6 @@ void vpRobotMavsdk::setVerbose(bool verbose) { m_impl->setVerbose(verbose); } bool vpRobotMavsdk::hasFlyingCapability() { return m_impl->getFlyingCapability(); } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotMavsdk.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotMavsdk.cpp.o) has no symbols void dummy_vpRobotMavsdk() { }; #endif diff --git a/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp b/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp index 6c47d0bb0e..84658c4d3f 100644 --- a/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp +++ b/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp @@ -124,7 +124,8 @@ void vpRobotPioneer::setVelocity(const vpRobot::vpControlFrameType frame, const this->setVel(vel_sat[0] * 1000.); // convert velocity in mm/s this->setRotVel(vpMath::deg(vel_sat[1])); // convert velocity in deg/s this->unlock(); - } else if (frame == vpRobot::ARTICULAR_FRAME) { + } + else if (frame == vpRobot::ARTICULAR_FRAME) { vel_max[0] = getMaxTranslationVelocity(); vel_max[1] = getMaxTranslationVelocity(); @@ -134,7 +135,8 @@ void vpRobotPioneer::setVelocity(const vpRobot::vpControlFrameType frame, const this->setVel2(vel_sat[0] * 1000., vel_sat[1] * 1000.); // convert velocity in mm/s this->unlock(); - } else { + } + else { throw vpRobotException(vpRobotException::wrongStateError, "Cannot send the robot velocity in the specified control frame"); } @@ -193,12 +195,14 @@ void vpRobotPioneer::getVelocity(const vpRobot::vpControlFrameType frame, vpColV velocity[0] = this->getLeftVel() / 1000.; velocity[1] = this->getRightVel() / 1000; this->unlock(); - } else if (frame == vpRobot::REFERENCE_FRAME) { + } + else if (frame == vpRobot::REFERENCE_FRAME) { this->lock(); velocity[0] = this->getVel() / 1000.; velocity[1] = vpMath::rad(this->getRotVel()); this->unlock(); - } else { + } + else { throw vpRobotException(vpRobotException::wrongStateError, "Cannot get the robot volocity in the specified control frame"); } @@ -232,7 +236,6 @@ vpColVector vpRobotPioneer::getVelocity(const vpRobot::vpControlFrameType frame) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotPioneer.cpp.o) has no -// symbols -void dummy_vpRobotPioneer(){}; +// Work around to avoid warning: libvisp_robot.a(vpRobotPioneer.cpp.o) has no symbols +void dummy_vpRobotPioneer() { }; #endif diff --git a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp index ad20ba4d31..43cc96719d 100644 --- a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp +++ b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp @@ -34,7 +34,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp b/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp index be3c57a42c..253dce7c61 100644 --- a/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp +++ b/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp @@ -33,8 +33,7 @@ #include - -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp b/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp index 4bbe8acef2..262dc2f5d7 100644 --- a/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp +++ b/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp @@ -770,7 +770,6 @@ void vpRobotPtu46::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotPtu46.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotPtu46.cpp.o) has no symbols void dummy_vpRobotPtu46() { }; #endif diff --git a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp index 64e5cd3b8f..daed273a17 100644 --- a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp +++ b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp @@ -874,7 +874,6 @@ vpRobot::vpRobotStateType vpRobotUniversalRobots::setRobotState(vpRobot::vpRobot } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotUniversalRobots.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotUniversalRobots.cpp.o) has no symbols void dummy_vpRobotUniversalRobots() { }; #endif diff --git a/modules/robot/src/robot-simulator/vpRobotCamera.cpp b/modules/robot/src/robot-simulator/vpRobotCamera.cpp index d9eecf8d4a..5d632ece76 100644 --- a/modules/robot/src/robot-simulator/vpRobotCamera.cpp +++ b/modules/robot/src/robot-simulator/vpRobotCamera.cpp @@ -248,7 +248,6 @@ void vpRobotCamera::setPosition(const vpHomogeneousMatrix &cMw) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotCamera.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotCamera.cpp.o) has no symbols void dummy_vpRobotCamera() { }; #endif diff --git a/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp b/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp index f45e033005..9e5d3e32f9 100644 --- a/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp +++ b/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include #include @@ -48,14 +48,10 @@ */ vpRobotWireFrameSimulator::vpRobotWireFrameSimulator() : vpWireFrameSimulator(), vpRobotSimulator(), I(), tcur(0), tprev(0), robotArms(nullptr), size_fMi(8), fMi(nullptr), - artCoord(), artVel(), velocity(), -#if defined(_WIN32) -#elif defined(VISP_HAVE_PTHREAD) - thread(), attr(), -#endif - m_mutex_fMi(), m_mutex_eMc(), m_mutex_artVel(), m_mutex_artCoord(), m_mutex_velocity(), m_mutex_display(), m_mutex_robotStop(), m_mutex_frame(), m_mutex_setVelocityCalled(), m_mutex_scene(), - displayBusy(false), - robotStop(false), jointLimit(false), jointLimitArt(false), singularityManagement(true), cameraParam(), + artCoord(), artVel(), velocity(), m_thread(), m_mutex_fMi(), m_mutex_eMc(), m_mutex_artVel(), m_mutex_artCoord(), + m_mutex_velocity(), m_mutex_display(), m_mutex_robotStop(), m_mutex_frame(), m_mutex_setVelocityCalled(), + m_mutex_scene(), displayBusy(false), robotStop(false), jointLimit(false), jointLimitArt(false), + singularityManagement(true), cameraParam(), #if defined(VISP_HAVE_DISPLAY) display(), #endif @@ -77,12 +73,8 @@ vpRobotWireFrameSimulator::vpRobotWireFrameSimulator() */ vpRobotWireFrameSimulator::vpRobotWireFrameSimulator(bool do_display) : vpWireFrameSimulator(), vpRobotSimulator(), I(), tcur(0), tprev(0), robotArms(nullptr), size_fMi(8), fMi(nullptr), - artCoord(), artVel(), velocity(), -#if defined(_WIN32) -#elif defined(VISP_HAVE_PTHREAD) - thread(), attr(), -#endif - m_mutex_fMi(), m_mutex_eMc(), m_mutex_artVel(), m_mutex_artCoord(), m_mutex_velocity(), m_mutex_display(), m_mutex_robotStop(), m_mutex_frame(), m_mutex_setVelocityCalled(), m_mutex_scene(), + artCoord(), artVel(), velocity(), m_thread(), m_mutex_fMi(), m_mutex_eMc(), m_mutex_artVel(), m_mutex_artCoord(), + m_mutex_velocity(), m_mutex_display(), m_mutex_robotStop(), m_mutex_frame(), m_mutex_setVelocityCalled(), m_mutex_scene(), displayBusy(false), robotStop(false), jointLimit(false), jointLimitArt(false), singularityManagement(true), cameraParam(), #if defined(VISP_HAVE_DISPLAY) diff --git a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp index ae1d7c870d..0e589be88c 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp @@ -34,7 +34,7 @@ *****************************************************************************/ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include // std::fabs #include // numeric_limits #include @@ -58,27 +58,14 @@ const double vpSimulatorAfma6::defaultPositioningVelocity = 25.0; */ vpSimulatorAfma6::vpSimulatorAfma6() : vpRobotWireFrameSimulator(), vpAfma6(), q_prev_getdis(), first_time_getdis(true), - positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() + positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() { init(); initDisplay(); tcur = vpTime::measureTimeMs(); -#if defined(_WIN32) - DWORD dwThreadIdArray; - hThread = CreateThread(nullptr, // default security attributes - 0, // use default stack size - launcher, // thread function name - this, // argument to thread function - 0, // use default creation flags - &dwThreadIdArray); // returns the thread identifier -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - - pthread_create(&thread, nullptr, launcher, (void *)this); -#endif + m_thread = new std::thread(&launcher, std::ref(*this)); compute_fMi(); } @@ -91,27 +78,14 @@ vpSimulatorAfma6::vpSimulatorAfma6() */ vpSimulatorAfma6::vpSimulatorAfma6(bool do_display) : vpRobotWireFrameSimulator(do_display), q_prev_getdis(), first_time_getdis(true), - positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() + positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() { init(); initDisplay(); tcur = vpTime::measureTimeMs(); -#if defined(_WIN32) - DWORD dwThreadIdArray; - hThread = CreateThread(nullptr, // default security attributes - 0, // use default stack size - launcher, // thread function name - this, // argument to thread function - 0, // use default creation flags - &dwThreadIdArray); // returns the thread identifier -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - - pthread_create(&thread, nullptr, launcher, (void *)this); -#endif + m_thread = new std::thread(&launcher, std::ref(*this)); compute_fMi(); } @@ -125,17 +99,7 @@ vpSimulatorAfma6::~vpSimulatorAfma6() robotStop = true; m_mutex_robotStop.unlock(); -#if defined(_WIN32) -#if defined(WINRT_8_1) - WaitForSingleObjectEx(hThread, INFINITE, FALSE); -#else // pure win32 - WaitForSingleObject(hThread, INFINITE); -#endif - CloseHandle(hThread); -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_destroy(&attr); - pthread_join(thread, nullptr); -#endif + m_thread->join(); if (robotArms != nullptr) { for (int i = 0; i < 6; i++) @@ -144,6 +108,7 @@ vpSimulatorAfma6::~vpSimulatorAfma6() delete[] robotArms; delete[] fMi; + delete m_thread; } /*! @@ -170,7 +135,8 @@ void vpSimulatorAfma6::init() try { arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR"); std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl; - } catch (...) { + } + catch (...) { std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl; } } @@ -383,9 +349,10 @@ void vpSimulatorAfma6::getCameraParameters(vpCameraParameters &cam, const unsign // Set default intrinsic camera parameters for 640x480 images if (image_width == 640 && image_height == 480) { std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" - << std::endl; + << std::endl; cam.initPersProjWithoutDistortion(1109.5735473989, 1112.1520168160, 320, 240); - } else { + } + else { vpTRACE("Cannot get default intrinsic camera parameters for this image " "resolution"); } @@ -395,9 +362,10 @@ void vpSimulatorAfma6::getCameraParameters(vpCameraParameters &cam, const unsign // Set default intrinsic camera parameters for 640x480 images if (image_width == 640 && image_height == 480) { std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" - << std::endl; + << std::endl; cam.initPersProjWithoutDistortion(852.6583228197, 854.8084224761, 320, 240); - } else { + } + else { vpTRACE("Cannot get default intrinsic camera parameters for this image " "resolution"); } @@ -505,12 +473,13 @@ void vpSimulatorAfma6::updateArticularPosition() if (art <= _joint_min[jointLimitArt - 1] || art >= _joint_max[jointLimitArt - 1]) { if (verbose_) { std::cout << "Joint " << jointLimitArt - 1 - << " reaches a limit: " << vpMath::deg(_joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art) - << " < " << vpMath::deg(_joint_max[jointLimitArt - 1]) << std::endl; + << " reaches a limit: " << vpMath::deg(_joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art) + << " < " << vpMath::deg(_joint_max[jointLimitArt - 1]) << std::endl; } articularVelocities = 0.0; - } else + } + else jointLimit = false; } @@ -526,10 +495,10 @@ void vpSimulatorAfma6::updateArticularPosition() if (jl != 0 && jointLimit == false) { if (jl < 0) ellapsedTime = (_joint_min[(unsigned int)(-jl - 1)] - articularCoordinates[(unsigned int)(-jl - 1)]) / - (articularVelocities[(unsigned int)(-jl - 1)]); + (articularVelocities[(unsigned int)(-jl - 1)]); else ellapsedTime = (_joint_max[(unsigned int)(jl - 1)] - articularCoordinates[(unsigned int)(jl - 1)]) / - (articularVelocities[(unsigned int)(jl - 1)]); + (articularVelocities[(unsigned int)(jl - 1)]); for (unsigned int i = 0; i < 6; i++) articularCoordinates[i] = articularCoordinates[i] + ellapsedTime * articularVelocities[i]; @@ -589,7 +558,8 @@ void vpSimulatorAfma6::updateArticularPosition() vpTime::wait(tcur, 1000 * getSamplingTime()); tcur_1 = tcur; - } else { + } + else { vpTime::wait(tcur, vpTime::getMinTimeForUsleepCall()); } @@ -759,9 +729,10 @@ vpRobot::vpRobotStateType vpSimulatorAfma6::setRobotState(vpRobot::vpRobotStateT if (vpRobot::STATE_VELOCITY_CONTROL == getRobotState()) { std::cout << "Change the control mode from velocity to position control.\n"; stopMotion(); - } else { - // std::cout << "Change the control mode from stop to position - // control.\n"; + } + else { + // std::cout << "Change the control mode from stop to position + // control.\n"; } break; } @@ -1352,7 +1323,8 @@ void vpSimulatorAfma6::setPosition(const vpRobot::vpControlFrameType frame, cons set_velocity(error); break; } - } else { + } + else { vpERROR_TRACE("Positioning error."); throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range."); } @@ -1415,7 +1387,8 @@ void vpSimulatorAfma6::setPosition(const vpRobot::vpControlFrameType frame, cons set_velocity(error); break; } - } else + } + else vpERROR_TRACE("Positioning error. Position unreachable"); } while (errsqr > 1e-8 && nbSol > 0); break; @@ -1508,7 +1481,8 @@ void vpSimulatorAfma6::setPosition(const vpRobot::vpControlFrameType frame, doub position[5] = pos6; setPosition(frame, position); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -1833,7 +1807,7 @@ int vpSimulatorAfma6::isInJointLimit() if (artNumb != 0) std::cout << "\nWarning: Velocity control stopped: axis " << fabs((float)artNumb) << " on joint limit!" - << std::endl; + << std::endl; return artNumb; } @@ -1886,7 +1860,8 @@ void vpSimulatorAfma6::getDisplacement(vpRobot::vpControlFrameType frame, vpColV return; } } - } else { + } + else { first_time_getdis = false; } @@ -2062,7 +2037,8 @@ void vpSimulatorAfma6::move(const char *filename) this->readPosFile(filename, q); this->setRobotState(vpRobot::STATE_POSITION_CONTROL); this->setPosition(vpRobot::ARTICULAR_FRAME, q); - } catch (...) { + } + catch (...) { throw; } } @@ -2106,7 +2082,8 @@ void vpSimulatorAfma6::get_eJe(vpMatrix &eJe_) { try { vpAfma6::get_eJe(get_artCoord(), eJe_); - } catch (...) { + } + catch (...) { vpERROR_TRACE("catch exception "); throw; } @@ -2127,7 +2104,8 @@ void vpSimulatorAfma6::get_fJe(vpMatrix &fJe_) try { vpColVector articularCoordinates = get_artCoord(); vpAfma6::get_fJe(articularCoordinates, fJe_); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -2178,7 +2156,8 @@ void vpSimulatorAfma6::initArms() try { scene_dir_ = vpIoTools::getenv("VISP_SCENES_DIR"); std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl; - } catch (...) { + } + catch (...) { std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl; } } @@ -2287,7 +2266,8 @@ void vpSimulatorAfma6::getExternalImage(vpImage &I_) (std::fabs(py_ext - 1) > vpMath::maximum(py_ext, 1.) * std::numeric_limits::epsilon())) { u = (double)I_.getWidth() / (2 * px_ext); v = (double)I_.getHeight() / (2 * py_ext); - } else { + } + else { u = (double)I_.getWidth() / (vpMath::minimum(I_.getWidth(), I_.getHeight())); v = (double)I_.getHeight() / (vpMath::minimum(I_.getWidth(), I_.getHeight())); } @@ -2491,5 +2471,5 @@ bool vpSimulatorAfma6::setPosition(const vpHomogeneousMatrix &cdMo_, vpImage -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include // std::fabs #include // numeric_limits @@ -58,28 +58,14 @@ const double vpSimulatorViper850::defaultPositioningVelocity = 25.0; */ vpSimulatorViper850::vpSimulatorViper850() : vpRobotWireFrameSimulator(), vpViper850(), q_prev_getdis(), first_time_getdis(true), - positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() + positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() { init(); initDisplay(); tcur = vpTime::measureTimeMs(); -#if defined(_WIN32) - - DWORD dwThreadIdArray; - hThread = CreateThread(nullptr, // default security attributes - 0, // use default stack size - launcher, // thread function name - this, // argument to thread function - 0, // use default creation flags - &dwThreadIdArray); // returns the thread identifier -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - - pthread_create(&thread, nullptr, launcher, (void *)this); -#endif + m_thread = new std::thread(&launcher, std::ref(*this)); compute_fMi(); } @@ -92,27 +78,14 @@ vpSimulatorViper850::vpSimulatorViper850() */ vpSimulatorViper850::vpSimulatorViper850(bool do_display) : vpRobotWireFrameSimulator(do_display), q_prev_getdis(), first_time_getdis(true), - positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() + positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() { init(); initDisplay(); tcur = vpTime::measureTimeMs(); -#if defined(_WIN32) - DWORD dwThreadIdArray; - hThread = CreateThread(nullptr, // default security attributes - 0, // use default stack size - launcher, // thread function name - this, // argument to thread function - 0, // use default creation flags - &dwThreadIdArray); // returns the thread identifier -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - - pthread_create(&thread, nullptr, launcher, (void *)this); -#endif + m_thread = new std::thread(&launcher, std::ref(*this)); compute_fMi(); } @@ -126,17 +99,7 @@ vpSimulatorViper850::~vpSimulatorViper850() robotStop = true; m_mutex_robotStop.unlock(); -#if defined(_WIN32) -#if defined(WINRT_8_1) - WaitForSingleObjectEx(hThread, INFINITE, FALSE); -#else // pure win32 - WaitForSingleObject(hThread, INFINITE); -#endif - CloseHandle(hThread); -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_destroy(&attr); - pthread_join(thread, nullptr); -#endif + m_thread->join(); if (robotArms != nullptr) { // free_Bound_scene (&(camera)); @@ -146,6 +109,7 @@ vpSimulatorViper850::~vpSimulatorViper850() delete[] robotArms; delete[] fMi; + delete m_thread; } /*! @@ -172,7 +136,8 @@ void vpSimulatorViper850::init() try { arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR"); std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl; - } catch (...) { + } + catch (...) { std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl; } } @@ -325,9 +290,10 @@ void vpSimulatorViper850::getCameraParameters(vpCameraParameters &cam, const uns // Set default intrinsic camera parameters for 640x480 images if (image_width == 640 && image_height == 480) { std::cout << "Get default camera parameters for camera \"" << vpViper850::CONST_MARLIN_F033C_CAMERA_NAME << "\"" - << std::endl; + << std::endl; cam.initPersProjWithoutDistortion(1232.0, 1233.0, 320, 240); - } else { + } + else { vpTRACE("Cannot get default intrinsic camera parameters for this image " "resolution"); } @@ -337,9 +303,10 @@ void vpSimulatorViper850::getCameraParameters(vpCameraParameters &cam, const uns // Set default intrinsic camera parameters for 640x480 images if (image_width == 640 && image_height == 480) { std::cout << "Get default camera parameters for camera \"" << vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME << "\"" - << std::endl; + << std::endl; cam.initPersProjWithoutDistortion(868.0, 869.0, 320, 240); - } else { + } + else { vpTRACE("Cannot get default intrinsic camera parameters for this image " "resolution"); } @@ -434,11 +401,12 @@ void vpSimulatorViper850::updateArticularPosition() if (art <= joint_min[jointLimitArt - 1] || art >= joint_max[jointLimitArt - 1]) { if (verbose_) { std::cout << "Joint " << jointLimitArt - 1 - << " reaches a limit: " << vpMath::deg(joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art) - << " < " << vpMath::deg(joint_max[jointLimitArt - 1]) << std::endl; + << " reaches a limit: " << vpMath::deg(joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art) + << " < " << vpMath::deg(joint_max[jointLimitArt - 1]) << std::endl; } articularVelocities = 0.0; - } else + } + else jointLimit = false; } @@ -454,10 +422,10 @@ void vpSimulatorViper850::updateArticularPosition() if (jl != 0 && jointLimit == false) { if (jl < 0) ellapsedTime = (joint_min[(unsigned int)(-jl - 1)] - articularCoordinates[(unsigned int)(-jl - 1)]) / - (articularVelocities[(unsigned int)(-jl - 1)]); + (articularVelocities[(unsigned int)(-jl - 1)]); else ellapsedTime = (joint_max[(unsigned int)(jl - 1)] - articularCoordinates[(unsigned int)(jl - 1)]) / - (articularVelocities[(unsigned int)(jl - 1)]); + (articularVelocities[(unsigned int)(jl - 1)]); for (unsigned int i = 0; i < 6; i++) articularCoordinates[i] = articularCoordinates[i] + ellapsedTime * articularVelocities[i]; @@ -517,7 +485,8 @@ void vpSimulatorViper850::updateArticularPosition() vpTime::wait(tcur, 1000 * getSamplingTime()); tcur_1 = tcur; - } else { + } + else { vpTime::wait(tcur, vpTime::getMinTimeForUsleepCall()); } m_mutex_robotStop.lock(); @@ -696,9 +665,10 @@ vpRobot::vpRobotStateType vpSimulatorViper850::setRobotState(vpRobot::vpRobotSta if (vpRobot::STATE_VELOCITY_CONTROL == getRobotState()) { std::cout << "Change the control mode from velocity to position control.\n"; stopMotion(); - } else { - // std::cout << "Change the control mode from stop to position - // control.\n"; + } + else { + // std::cout << "Change the control mode from stop to position + // control.\n"; } break; } @@ -1284,7 +1254,8 @@ void vpSimulatorViper850::setPosition(const vpRobot::vpControlFrameType frame, c set_velocity(error); break; } - } else { + } + else { vpERROR_TRACE("Positioning error."); throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range."); } @@ -1347,7 +1318,8 @@ void vpSimulatorViper850::setPosition(const vpRobot::vpControlFrameType frame, c set_velocity(error); break; } - } else + } + else vpERROR_TRACE("Positioning error. Position unreachable"); } while (errsqr > 1e-8 && nbSol > 0); break; @@ -1438,7 +1410,8 @@ void vpSimulatorViper850::setPosition(const vpRobot::vpControlFrameType frame, d position[5] = pos6; setPosition(frame, position); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -1809,7 +1782,7 @@ int vpSimulatorViper850::isInJointLimit() if (artNumb != 0) std::cout << "\nWarning: Velocity control stopped: axis " << fabs((float)artNumb) << " on joint limit!" - << std::endl; + << std::endl; return artNumb; } @@ -1865,7 +1838,8 @@ void vpSimulatorViper850::getDisplacement(vpRobot::vpControlFrameType frame, vpC return; } } - } else { + } + else { first_time_getdis = false; } @@ -2052,7 +2026,8 @@ void vpSimulatorViper850::move(const char *filename) this->readPosFile(filename, q); this->setRobotState(vpRobot::STATE_POSITION_CONTROL); this->setPosition(vpRobot::ARTICULAR_FRAME, q); - } catch (...) { + } + catch (...) { throw; } } @@ -2096,7 +2071,8 @@ void vpSimulatorViper850::get_eJe(vpMatrix &eJe_) { try { vpViper850::get_eJe(get_artCoord(), eJe_); - } catch (...) { + } + catch (...) { vpERROR_TRACE("catch exception "); throw; } @@ -2117,7 +2093,8 @@ void vpSimulatorViper850::get_fJe(vpMatrix &fJe_) try { vpColVector articularCoordinates = get_artCoord(); vpViper850::get_fJe(articularCoordinates, fJe_); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -2168,7 +2145,8 @@ void vpSimulatorViper850::initArms() try { scene_dir_ = vpIoTools::getenv("VISP_SCENES_DIR"); std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl; - } catch (...) { + } + catch (...) { std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl; } } @@ -2255,7 +2233,8 @@ void vpSimulatorViper850::getExternalImage(vpImage &I_) (std::fabs(py_ext - 1) > vpMath::maximum(py_ext, 1.) * std::numeric_limits::epsilon())) { u = (double)I_.getWidth() / (2 * px_ext); v = (double)I_.getHeight() / (2 * py_ext); - } else { + } + else { u = (double)I_.getWidth() / (vpMath::minimum(I_.getWidth(), I_.getHeight())); v = (double)I_.getHeight() / (vpMath::minimum(I_.getWidth(), I_.getHeight())); } @@ -2383,5 +2362,5 @@ void vpSimulatorViper850::initialiseObjectRelativeToCamera(const vpHomogeneousMa #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpSimulatorViper850.cpp.o) // has no symbols -void dummy_vpSimulatorViper850(){}; +void dummy_vpSimulatorViper850() { }; #endif diff --git a/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp b/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp index 6c330c7058..fca58e6ac2 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp @@ -48,7 +48,8 @@ #include // Check if std:c++17 or higher -#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) +#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \ + && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp b/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp index dffd649c22..26dcd0cea0 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp @@ -48,7 +48,8 @@ #include // Check if std:c++17 or higher -#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) +#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \ + && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/test/servo-pololu/testPololuPosition.cpp b/modules/robot/test/servo-pololu/testPololuPosition.cpp index 3b49043c98..deaf385e19 100644 --- a/modules/robot/test/servo-pololu/testPololuPosition.cpp +++ b/modules/robot/test/servo-pololu/testPololuPosition.cpp @@ -39,7 +39,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/test/servo-pololu/testPololuVelocity.cpp b/modules/robot/test/servo-pololu/testPololuVelocity.cpp index 7d9610b4ad..97387918e0 100644 --- a/modules/robot/test/servo-pololu/testPololuVelocity.cpp +++ b/modules/robot/test/servo-pololu/testPololuVelocity.cpp @@ -38,7 +38,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/CMakeLists.txt b/modules/sensor/CMakeLists.txt index be27453fca..8c32dc1e8c 100644 --- a/modules/sensor/CMakeLists.txt +++ b/modules/sensor/CMakeLists.txt @@ -234,8 +234,6 @@ if(CXX_FLAGS_MUTE_WARNINGS) vp_set_source_file_compile_flag(test/rgb-depth/testOccipitalStructure_Core_images.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testOccipitalStructure_Core_imu.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testOccipitalStructure_Core_pcl.cpp ${CXX_FLAGS_MUTE_WARNINGS}) - vp_set_source_file_compile_flag(test/rgb-depth/testRealSense_R200.cpp ${CXX_FLAGS_MUTE_WARNINGS}) - vp_set_source_file_compile_flag(test/rgb-depth/testRealSense_SR300.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testRealSense2_SR300.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testRealSense2_D435.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testRealSense2_D435_align.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h old mode 100755 new mode 100644 diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h index 198240c3b7..6923c6be71 100644 --- a/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h +++ b/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h @@ -46,7 +46,7 @@ #include -#ifdef VISP_HAVE_FT_IIT_SDK +#if defined(VISP_HAVE_FT_IIT_SDK) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/include/visp3/sensor/vpKinect.h b/modules/sensor/include/visp3/sensor/vpKinect.h index d66742af67..d5f73273e3 100644 --- a/modules/sensor/include/visp3/sensor/vpKinect.h +++ b/modules/sensor/include/visp3/sensor/vpKinect.h @@ -42,16 +42,16 @@ #include // Note that libfreenect needs libusb-1.0 and libpthread -#if defined(VISP_HAVE_LIBFREENECT_AND_DEPENDENCIES) +#if defined(VISP_HAVE_LIBFREENECT_AND_DEPENDENCIES) && defined(VISP_HAVE_THREADS) #include #include +#include #include #include #include #include -#include // need pthread #include /*! @@ -154,8 +154,8 @@ class VISP_EXPORT vpKinect : public Freenect::FreenectDevice void DepthCallback(void *depth, uint32_t timestamp); private: - vpMutex m_rgb_mutex; - vpMutex m_depth_mutex; + std::mutex m_rgb_mutex; + std::mutex m_depth_mutex; vpCameraParameters RGBcam, IRcam; // intrinsic parameters of the two cameras vpHomogeneousMatrix rgbMir; // Transformation from IRcam coordinate frame to diff --git a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h index e425b5a2c9..07b6c5a8e3 100644 --- a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h +++ b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/src/force-torque/vpComedi.cpp b/modules/sensor/src/force-torque/vpComedi.cpp index c4bee5e8a3..f02ed55a17 100644 --- a/modules/sensor/src/force-torque/vpComedi.cpp +++ b/modules/sensor/src/force-torque/vpComedi.cpp @@ -47,9 +47,8 @@ */ vpComedi::vpComedi() : m_device("/dev/comedi0"), m_handler(nullptr), m_subdevice(0), m_range(0), m_aref(AREF_DIFF), m_nchannel(6), - m_range_info(6), m_maxdata(6), m_chanlist(6) -{ -} + m_range_info(6), m_maxdata(6), m_chanlist(6) +{ } /*! Destructor that closes the connection to the device if it is not already @@ -173,7 +172,6 @@ std::string vpComedi::getPhyDataUnits() const } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpComedi.cpp.o) has no -// symbols -void dummy_vpComedi(){}; +// Work around to avoid warning: libvisp_sensor.a(vpComedi.cpp.o) has symbols +void dummy_vpComedi() { }; #endif diff --git a/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp b/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp index 58b4084eb2..d111f26664 100644 --- a/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp +++ b/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp @@ -43,7 +43,7 @@ #include -#ifdef VISP_HAVE_FT_IIT_SDK +#if defined(VISP_HAVE_FT_IIT_SDK) && defined(VISP_HAVE_THREADS) /*! Default constructor. diff --git a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp index 543dd82d12..d4b8009686 100644 --- a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp +++ b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp @@ -447,7 +447,7 @@ void vpV4l2Grabber::open(vpImage &I) close(); throw(vpFrameGrabberException(vpFrameGrabberException::settingError, - "No pixel format compatible with the camera was found")); + "No pixel format compatible with the camera was found")); } } } @@ -854,27 +854,27 @@ void vpV4l2Grabber::close() } if (inp != nullptr) { - delete [] inp; + delete[] inp; inp = nullptr; } if (std != nullptr) { - delete [] std; + delete[] std; std = nullptr; } if (fmt != nullptr) { - delete [] fmt; + delete[] fmt; fmt = nullptr; } if (ctl != nullptr) { - delete [] ctl; + delete[] ctl; ctl = nullptr; } if (buf_v4l2 != nullptr) { - delete [] buf_v4l2; + delete[] buf_v4l2; buf_v4l2 = nullptr; } if (buf_me != nullptr) { - delete [] buf_me; + delete[] buf_me; buf_me = nullptr; } } @@ -913,27 +913,27 @@ void vpV4l2Grabber::open() } if (inp != nullptr) { - delete [] inp; + delete[] inp; inp = nullptr; } if (std != nullptr) { - delete [] std; + delete[] std; std = nullptr; } if (fmt != nullptr) { - delete [] fmt; + delete[] fmt; fmt = nullptr; } if (ctl != nullptr) { - delete [] ctl; + delete[] ctl; ctl = nullptr; } if (buf_v4l2 != nullptr) { - delete [] buf_v4l2; + delete[] buf_v4l2; buf_v4l2 = nullptr; } if (buf_me != nullptr) { - delete [] buf_me; + delete[] buf_me; buf_me = nullptr; } @@ -1468,7 +1468,6 @@ vpV4l2Grabber &vpV4l2Grabber::operator>>(vpImage &I) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpV4l2Grabber.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_sensor.a(vpV4l2Grabber.cpp.o) has no symbols void dummy_vpV4l2Grabber() { }; #endif diff --git a/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp b/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp index 6666baaa81..67b9ca60d8 100644 --- a/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp +++ b/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp @@ -121,7 +121,7 @@ void vpKinect::stop() */ void vpKinect::VideoCallback(void *rgb, uint32_t /* timestamp */) { - vpMutex::vpScopedLock lock(m_rgb_mutex); + std::lock_guard lock(m_rgb_mutex); uint8_t *rgb_ = static_cast(rgb); for (unsigned i = 0; i < height; i++) { for (unsigned j = 0; j < width; j++) { @@ -146,7 +146,7 @@ void vpKinect::VideoCallback(void *rgb, uint32_t /* timestamp */) */ void vpKinect::DepthCallback(void *depth, uint32_t /* timestamp */) { - vpMutex::vpScopedLock lock(m_depth_mutex); + std::lock_guard lock(m_depth_mutex); uint16_t *depth_ = static_cast(depth); for (unsigned i = 0; i < height; i++) { for (unsigned j = 0; j < width; j++) { @@ -167,7 +167,7 @@ void vpKinect::DepthCallback(void *depth, uint32_t /* timestamp */) */ bool vpKinect::getDepthMap(vpImage &map) { - vpMutex::vpScopedLock lock(m_depth_mutex); + std::lock_guard lock(m_depth_mutex); if (!m_new_depth_map) return false; map = this->dmap; @@ -225,7 +225,7 @@ bool vpKinect::getDepthMap(vpImage &map, vpImage &Imap) */ bool vpKinect::getRGB(vpImage &I_RGB) { - vpMutex::vpScopedLock lock(m_rgb_mutex); + std::lock_guard lock(m_rgb_mutex); if (!m_new_rgb_frame) return false; I_RGB = this->IRGB; @@ -292,7 +292,6 @@ void vpKinect::warpRGBFrame(const vpImage &Irgb, const vpImage &I } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpKinect.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_sensor.a(vpKinect.cpp.o) has no symbols void dummy_vpKinect() { }; #endif // VISP_HAVE_LIBFREENECT diff --git a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp index e618733b24..daaeb32591 100644 --- a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp +++ b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_THREADS) #include #include #include diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp index 807e4e1c51..fd6ded07f0 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp @@ -1045,7 +1045,6 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense &rs) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpRealSense.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_sensor.a(vpRealSense.cpp.o) has symbols void dummy_vpRealSense() { }; #endif diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp index 15b9a43659..e4536ec3a3 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp @@ -1677,7 +1677,6 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpRealSense2.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_sensor.a(vpRealSense2.cpp.o) has symbols void dummy_vpRealSense2() { }; #endif diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense_impl.h b/modules/sensor/src/rgb-depth/realsense/vpRealSense_impl.h index 5dd48aba48..d76ed2834d 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense_impl.h +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense_impl.h @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_REALSENSE) +#if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_THREADS) #include #include #include diff --git a/modules/sensor/test/force-torque/testForceTorqueAti.cpp b/modules/sensor/test/force-torque/testForceTorqueAti.cpp index bb70db8786..065bde7d09 100644 --- a/modules/sensor/test/force-torque/testForceTorqueAti.cpp +++ b/modules/sensor/test/force-torque/testForceTorqueAti.cpp @@ -45,35 +45,28 @@ #include #include -#include -#include #include #include #include -#if defined(VISP_HAVE_PTHREAD) +#if defined(VISP_HAVE_THREADS) -typedef enum { BIAS_DONE, UNBIAS_DONE, TO_BIAS, TO_UNBIAS } BiasState; +#include +#include -vpMutex s_mutex_data; +typedef enum { BIAS_DONE, UNBIAS_DONE, TO_BIAS, TO_UNBIAS } BiasState; #ifndef DOXYGEN_SHOULD_SKIP_THIS -typedef struct { +typedef struct +{ vpColVector ft; double timestamp; BiasState bias_state; } t_shared_data; #endif -t_shared_data s_shared_data; - -vpMutex s_mutex_state; -bool s_state_stop = false; - -vpThread::Return scopeFunction(vpThread::Args args) +void scopeFunction(std::mutex &mutex_data, std::mutex &mutex_state, t_shared_data &s_shared_data, bool &s_state_stop) { - (void)args; // Avoid warning: unused parameter args - #ifdef VISP_HAVE_DISPLAY vpPlot scope(2, 700, 700, 100, 200, "ATI F/T sensor data"); scope.initGraph(0, 3); @@ -98,7 +91,7 @@ vpThread::Return scopeFunction(vpThread::Args args) do { #ifdef VISP_HAVE_DISPLAY { // Get new measures to plot - vpMutex::vpScopedLock lock(s_mutex_data); + std::lock_guard lock(mutex_data); shared_data.ft = s_shared_data.ft; shared_data.timestamp = s_shared_data.timestamp; shared_data.bias_state = s_shared_data.bias_state; @@ -127,7 +120,7 @@ vpThread::Return scopeFunction(vpThread::Args args) else if (shared_data.bias_state == UNBIAS_DONE) shared_data.bias_state = TO_BIAS; { // Set new bias state - vpMutex::vpScopedLock lock(s_mutex_data); + std::lock_guard lock(mutex_data); s_shared_data.bias_state = shared_data.bias_state; } } @@ -141,12 +134,11 @@ vpThread::Return scopeFunction(vpThread::Args args) #endif { // Update state to stop - vpMutex::vpScopedLock lock(s_mutex_state); + std::lock_guard lock(mutex_state); s_state_stop = true; } std::cout << "End of scope thread" << std::endl; - return 0; } int main(int argc, char **argv) @@ -177,13 +169,18 @@ int main(int argc, char **argv) ati.bias(); std::cout << "Data recording in progress..." << std::endl; + std::mutex mutex_data; + std::mutex mutex_state; + bool state_stop = false; + bool s_state_stop = false; + t_shared_data shared_data; + t_shared_data s_shared_data; + // Start scope thread - vpThread thread_scope(scopeFunction); + std::thread thread_scope(&scopeFunction, std::ref(mutex_data), std::ref(mutex_state), std::ref(s_shared_data), std::ref(s_state_stop)); std::string file("recorded-ft-sync.txt"); std::ofstream f(file.c_str()); - bool state_stop; - t_shared_data shared_data; double start_time = vpTime::measureTimeMs(); @@ -193,7 +190,7 @@ int main(int argc, char **argv) double timestamp = loop_time - start_time; { // Update shared F/T measure used by the scope to plot curves - vpMutex::vpScopedLock lock(s_mutex_data); + std::lock_guard lock(mutex_data); shared_data.bias_state = s_shared_data.bias_state; } if (shared_data.bias_state == TO_BIAS) { @@ -201,19 +198,20 @@ int main(int argc, char **argv) ati.bias(); std::cout << "Unbias sensor" << std::endl; shared_data.bias_state = BIAS_DONE; - } else if (shared_data.bias_state == TO_UNBIAS) { + } + else if (shared_data.bias_state == TO_UNBIAS) { ati.unbias(); shared_data.bias_state = UNBIAS_DONE; } { // Update shared F/T measure used by the scope to plot curves - vpMutex::vpScopedLock lock(s_mutex_data); + std::lock_guard lock(mutex_data); s_shared_data.ft = ft; s_shared_data.timestamp = timestamp; s_shared_data.bias_state = shared_data.bias_state; } { // Get state to stop - vpMutex::vpScopedLock lock(s_mutex_state); + std::lock_guard lock(mutex_state); state_stop = s_state_stop; } diff --git a/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp b/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp old mode 100755 new mode 100644 diff --git a/modules/sensor/test/mocap/testMocapQualisys.cpp b/modules/sensor/test/mocap/testMocapQualisys.cpp index ec1a79255b..4df6172314 100644 --- a/modules/sensor/test/mocap/testMocapQualisys.cpp +++ b/modules/sensor/test/mocap/testMocapQualisys.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_QUALISYS) +#if defined(VISP_HAVE_QUALISYS) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/test/mocap/testMocapVicon.cpp b/modules/sensor/test/mocap/testMocapVicon.cpp index 10c1f4c274..0c8c3a8830 100644 --- a/modules/sensor/test/mocap/testMocapVicon.cpp +++ b/modules/sensor/test/mocap/testMocapVicon.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_VICON) +#if defined(VISP_HAVE_VICON) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp index 325347c53d..cde2c5abc2 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) \ && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PCL) #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp index ea1024dbee..350d9c1013 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp @@ -42,8 +42,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ - && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #ifdef VISP_HAVE_PCL #include 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 a76074c0f6..ab7ec4d130 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp @@ -47,8 +47,8 @@ #include #include -#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)) +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) \ + && (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 94581a572e..33d272a879 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,8 +47,8 @@ #include #include -#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)) +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) #include #include diff --git a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp b/modules/sensor/test/rgb-depth/testRealSense_R200.cpp deleted file mode 100644 index f7447fa48d..0000000000 --- a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp +++ /dev/null @@ -1,592 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 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. - * - * Description: - * Test Intel RealSense acquisition. - * -*****************************************************************************/ - -/*! - \example testRealSense_R200.cpp - Test Intel RealSense R200 acquisition. -*/ - -#include - -#include -#include -#include -#include -#include - -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) -#include -#include - -#ifdef VISP_HAVE_PCL -#include -#include -#endif - -namespace -{ - -#ifdef VISP_HAVE_PCL -// Global variables -pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud()); -pcl::PointCloud::Ptr pointcloud_color(new pcl::PointCloud()); -bool cancelled = false, update_pointcloud = false; - -class ViewerWorker -{ -public: - explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { } - - void run() - { - std::string date = vpTime::getDateTime(); - pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date)); - pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud_color); - pcl::PointCloud::Ptr local_pointcloud(new pcl::PointCloud()); - pcl::PointCloud::Ptr local_pointcloud_color(new pcl::PointCloud()); - - viewer->setBackgroundColor(0, 0, 0); - viewer->initCameraParameters(); - viewer->setPosition(640 + 80, 480 + 80); - viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0); - viewer->setSize(640, 480); - - bool init = true; - bool local_update = false, local_cancelled = false; - while (!local_cancelled) { - { - std::unique_lock lock(m_mutex, std::try_to_lock); - - if (lock.owns_lock()) { - local_update = update_pointcloud; - update_pointcloud = false; - local_cancelled = cancelled; - - if (local_update) { - if (m_colorMode) { - local_pointcloud_color = pointcloud_color->makeShared(); - } - else { - local_pointcloud = pointcloud->makeShared(); - } - } - } - } - - if (local_update && !local_cancelled) { - local_update = false; - - if (init) { - if (m_colorMode) { - viewer->addPointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, - "RGB sample cloud"); - } - else { - viewer->addPointCloud(local_pointcloud, "sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); - } - init = false; - } - else { - if (m_colorMode) { - viewer->updatePointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - } - else { - viewer->updatePointCloud(local_pointcloud, "sample cloud"); - } - } - } - - viewer->spinOnce(5); - } - - std::cout << "End of point cloud display thread" << std::endl; - } - -private: - bool m_colorMode; - std::mutex &m_mutex; -}; -#endif //#ifdef VISP_HAVE_PCL - -void test_R200(vpRealSense &rs, const std::map &enables, - const std::map ¶ms, - const std::map &options, const std::string &title, - bool depth_color_visualization = false, const rs::stream &color_stream = rs::stream::color, - const rs::stream &depth_stream = rs::stream::depth, - const rs::stream &infrared2_stream = rs::stream::infrared2, bool display_pcl = false, - bool pcl_color = false) -{ - std::cout << std::endl; - - std::map::const_iterator it_enable; - std::map::const_iterator it_param; - - for (it_enable = enables.begin(), it_param = params.begin(); it_enable != enables.end(); ++it_enable) { - rs.setEnableStream(it_enable->first, it_enable->second); - - if (it_enable->second) { - it_param = params.find(it_enable->first); - - if (it_param != params.end()) { - rs.setStreamSettings(it_param->first, it_param->second); - } - } - } - - rs.open(); - - vpImage depth; - vpImage I_depth; - vpImage I_depth_color; - - vpImage I_color; - vpImage infrared, infrared2; - vpImage I_infrared, I_infrared2; - - bool direct_infrared_conversion = false; - for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) { - if (it_enable->second) { - switch (it_enable->first) { - case rs::stream::color: - I_color.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - break; - - case rs::stream::depth: - depth.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_depth.init(depth.getHeight(), depth.getWidth()); - I_depth_color.init(depth.getHeight(), depth.getWidth()); - break; - - case rs::stream::infrared: - infrared.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_infrared.init(infrared.getHeight(), infrared.getWidth()); - - it_param = params.find(it_enable->first); - if (it_param != params.end()) { - direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8; - } - break; - - case rs::stream::infrared2: - infrared2.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_infrared2.init(infrared.getHeight(), infrared.getWidth()); - - it_param = params.find(it_enable->first); - if (it_param != params.end()) { - direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8; - } - break; - - default: - break; - } - } - } - -#if defined(VISP_HAVE_X11) - vpDisplayX dc, dd, di, di2; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI dc, dd, di, di2; -#endif - - for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) { - if (it_enable->second) { - switch (it_enable->first) { - case rs::stream::color: - dc.init(I_color, 0, 0, "Color frame"); - break; - - case rs::stream::depth: - if (depth_color_visualization) { - dd.init(I_depth_color, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } - else { - dd.init(I_depth, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } - break; - - case rs::stream::infrared: - di.init(I_infrared, 0, (int)(std::max(I_color.getHeight(), I_depth.getHeight())) + 30, "Infrared frame"); - break; - - case rs::stream::infrared2: - di2.init(I_infrared2, (int)I_infrared.getWidth(), - (int)(std::max(I_color.getHeight(), I_depth.getHeight())) + 30, "Infrared2 frame"); - break; - - default: - break; - } - } - } - - std::cout << "direct_infrared_conversion=" << direct_infrared_conversion << std::endl; - -#ifdef VISP_HAVE_PCL - std::mutex mutex; - ViewerWorker viewer(pcl_color, mutex); - std::thread viewer_thread; - - if (display_pcl) { - viewer_thread = std::thread(&ViewerWorker::run, &viewer); - } -#else - display_pcl = false; -#endif - - rs::device *dev = rs.getHandler(); - - // Test stream acquisition during 10 s - std::vector time_vector; - double t_begin = vpTime::measureTimeMs(); - while (true) { - double t = vpTime::measureTimeMs(); - - for (std::map::const_iterator it = options.begin(); it != options.end(); ++it) { - dev->set_option(it->first, it->second); - } - - if (display_pcl) { -#ifdef VISP_HAVE_PCL - std::lock_guard lock(mutex); - - if (direct_infrared_conversion) { - if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, - (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, - depth_stream, rs::stream::infrared, infrared2_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, - depth_stream, rs::stream::infrared, infrared2_stream); - } - } - else { - if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, - (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, - rs::stream::infrared, infrared2_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, - rs::stream::infrared, infrared2_stream); - } - - vpImageConvert::convert(infrared, I_infrared); - vpImageConvert::convert(infrared2, I_infrared2); - } - - update_pointcloud = true; -#endif - } - else { - if (direct_infrared_conversion) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, depth_stream, - rs::stream::infrared, infrared2_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, - rs::stream::infrared, infrared2_stream); - vpImageConvert::convert(infrared, I_infrared); - vpImageConvert::convert(infrared2, I_infrared2); - } - } - - if (depth_color_visualization) { - vpImageConvert::createDepthHistogram(depth, I_depth_color); - } - else { - vpImageConvert::createDepthHistogram(depth, I_depth); - } - - vpDisplay::display(I_color); - if (depth_color_visualization) { - vpDisplay::display(I_depth_color); - } - else { - vpDisplay::display(I_depth); - } - vpDisplay::display(I_infrared); - vpDisplay::display(I_infrared2); - - vpDisplay::flush(I_color); - if (depth_color_visualization) { - vpDisplay::flush(I_depth_color); - } - else { - vpDisplay::flush(I_depth); - } - vpDisplay::flush(I_infrared); - vpDisplay::flush(I_infrared2); - - if (vpDisplay::getClick(I_color, false) || - (depth_color_visualization ? vpDisplay::getClick(I_depth_color, false) : vpDisplay::getClick(I_depth, false)) || - vpDisplay::getClick(I_infrared, false) || vpDisplay::getClick(I_infrared2, false)) { - break; - } - - time_vector.push_back(vpTime::measureTimeMs() - t); - if (vpTime::measureTimeMs() - t_begin >= 10000) { - break; - } - } - - if (display_pcl) { -#ifdef VISP_HAVE_PCL - { - std::lock_guard lock(mutex); - cancelled = true; - } - - viewer_thread.join(); -#endif - } - - std::cout << title << " - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; - - rs.close(); -} - -} // namespace - -int main(int argc, char *argv[]) -{ - try { - vpRealSense rs; - - rs.setEnableStream(rs::stream::color, false); - rs.open(); - if (rs_get_device_name((const rs_device *)rs.getHandler(), nullptr) != std::string("Intel RealSense R200")) { - std::cout << "This test file is used to test the Intel RealSense R200 only." << std::endl; - return EXIT_SUCCESS; - } - - std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl; - std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *)rs.getHandler(), nullptr) - << std::endl; - std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; - - rs.close(); - - std::map enables; - std::map params; - std::map options; - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = false; - enables[rs::stream::infrared2] = false; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 90); - - options[rs::option::r200_lr_auto_exposure_enabled] = 1; - - test_R200(rs, enables, params, options, "R200_DEPTH_Z16_640x480_90FPS + r200_lr_auto_exposure_enabled", true); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 90); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - - options[rs::option::r200_lr_auto_exposure_enabled] = 0; - options[rs::option::r200_emitter_enabled] = 0; - - test_R200(rs, enables, params, options, - "R200_DEPTH_Z16_640x480_90FPS + R200_INFRARED_Y8_640x480_90FPS " - "+ R200_INFRARED2_Y8_640x480_90FPS + " - "!r200_lr_auto_exposure_enabled + !r200_emitter_enabled", - true); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(628, 468, rs::format::z16, 90); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 90); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 90); - - options[rs::option::r200_lr_auto_exposure_enabled] = 1; - options[rs::option::r200_emitter_enabled] = 1; - - test_R200(rs, enables, params, options, - "R200_DEPTH_Z16_628x468_90FPS + " - "R200_INFRARED_Y16_640x480_90FPS + " - "R200_INFRARED2_Y16_640x480_90FPS"); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(628, 468, rs::format::z16, 90); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - - options.clear(); - - test_R200(rs, enables, params, options, - "R200_DEPTH_Z16_628x468_90FPS + R200_INFRARED_Y8_640x480_90FPS " - "+ R200_INFRARED2_Y8_640x480_90FPS"); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 90); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - - test_R200(rs, enables, params, options, - "R200_COLOR_RGBA8_640x480_30FPS + R200_DEPTH_Z16_628x468_90FPS " - "+ R200_INFRARED_Y8_640x480_90FPS + " - "R200_INFRARED2_Y8_640x480_90FPS", - true); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = false; - enables[rs::stream::infrared] = false; - enables[rs::stream::infrared2] = false; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30); - - test_R200(rs, enables, params, options, "R200_COLOR_RGBA8_1920x1080_30FPS"); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = false; - enables[rs::stream::infrared] = false; - enables[rs::stream::infrared2] = false; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60); - test_R200(rs, enables, params, options, "R200_COLOR_RGBA8_640x480_60FPS"); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - - // depth == 0 ; color == 1 ; infrared2 == 3 ; rectified_color == 6 ; - // color_aligned_to_depth == 7 ; infrared2_aligned_to_depth == 8 ; - // depth_aligned_to_color == 9 ; depth_aligned_to_rectified_color == 10 ; - // depth_aligned_to_infrared2 == 11 argv[2] <==> color stream - rs::stream color_stream = argc > 2 ? (rs::stream)atoi(argv[2]) : rs::stream::color_aligned_to_depth; - std::cout << "\ncolor_stream: " << color_stream << std::endl; - // argv[3] <==> depth stream - rs::stream depth_stream = argc > 3 ? (rs::stream)atoi(argv[3]) : rs::stream::depth_aligned_to_rectified_color; - std::cout << "depth_stream: " << depth_stream << std::endl; - // argv[4] <==> depth stream - rs::stream infrared2_stream = argc > 4 ? (rs::stream)atoi(argv[4]) : rs::stream::infrared2_aligned_to_depth; - std::cout << "infrared2_stream: " << infrared2_stream << std::endl; - - test_R200(rs, enables, params, options, - "R200_COLOR_ALIGNED_TO_DEPTH_RGBA8_640x480_60FPS + " - "R200_DEPTH_ALIGNED_TO_RECTIFIED_COLOR_Z16_640x480_60FPS + " - "R200_INFRARED_Y8_640x480_60FPS + " - "R200_INFRARED2_ALIGNED_TO_DEPTH_Y8_640x480_60FPS", - true, color_stream, depth_stream, infrared2_stream); - -#if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX, since viewer->spinOnce (10); produces a - // segfault on OSX - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - - // Cannot render two pcl::visualization::PCLVisualizer so use an arg - // option to switch between B&W and color point cloud rendering until a - // solution is found - test_R200(rs, enables, params, options, - "R200_COLOR_RGBA8_640x480_60FPS + R200_DEPTH_Z16_640x480_60FPS + " - "R200_INFRARED_Y8_640x480_60FPS + R200_INFRARED2_Y8_640x480_60FPS", - false, rs::stream::color, rs::stream::depth, rs::stream::infrared2, true, - (argc > 1 ? (bool)(atoi(argv[1]) > 0) : false)); -#endif - } - catch (const vpException &e) { - std::cerr << "RealSense error " << e.what() << std::endl; - } - catch (const rs::error &e) { - std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() - << "): " << e.what() << std::endl; - } - catch (const std::exception &e) { - std::cerr << e.what() << std::endl; - } - - return EXIT_SUCCESS; -} - -#else -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 - return EXIT_SUCCESS; -} -#endif diff --git a/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp deleted file mode 100644 index d37e15e113..0000000000 --- a/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp +++ /dev/null @@ -1,526 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 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. - * - * Description: - * Test Intel RealSense acquisition. - * -*****************************************************************************/ - -/*! - \example testRealSense_SR300.cpp - Test Intel RealSense SR300 acquisition. -*/ - -#include - -#include -#include -#include -#include -#include - -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) -#include -#include - -#ifdef VISP_HAVE_PCL -#include -#include -#endif - -namespace -{ - -#ifdef VISP_HAVE_PCL -// Global variables -pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud()); -pcl::PointCloud::Ptr pointcloud_color(new pcl::PointCloud()); -bool cancelled = false, update_pointcloud = false; - -class ViewerWorker -{ -public: - explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { } - - void run() - { - std::string date = vpTime::getDateTime(); - pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date)); - pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud_color); - pcl::PointCloud::Ptr local_pointcloud(new pcl::PointCloud()); - pcl::PointCloud::Ptr local_pointcloud_color(new pcl::PointCloud()); - - viewer->setBackgroundColor(0, 0, 0); - viewer->initCameraParameters(); - viewer->setPosition(640 + 80, 480 + 80); - viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0); - viewer->setSize(640, 480); - - bool init = true; - bool local_update = false, local_cancelled = false; - while (!local_cancelled) { - { - std::unique_lock lock(m_mutex, std::try_to_lock); - - if (lock.owns_lock()) { - local_update = update_pointcloud; - update_pointcloud = false; - local_cancelled = cancelled; - - if (local_update) { - if (m_colorMode) { - local_pointcloud_color = pointcloud_color->makeShared(); - } - else { - local_pointcloud = pointcloud->makeShared(); - } - } - } - } - - if (local_update && !local_cancelled) { - local_update = false; - - if (init) { - if (m_colorMode) { - viewer->addPointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, - "RGB sample cloud"); - } - else { - viewer->addPointCloud(local_pointcloud, "sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); - } - init = false; - } - else { - if (m_colorMode) { - viewer->updatePointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - } - else { - viewer->updatePointCloud(local_pointcloud, "sample cloud"); - } - } - } - - viewer->spinOnce(5); - } - - std::cout << "End of point cloud display thread" << std::endl; - } - -private: - bool m_colorMode; - std::mutex &m_mutex; -}; -#endif //#ifdef VISP_HAVE_PCL - -void test_SR300(vpRealSense &rs, const std::map &enables, - const std::map ¶ms, const std::string &title, - bool depth_color_visualization = false, const rs::stream &color_stream = rs::stream::color, - const rs::stream &depth_stream = rs::stream::depth, bool display_pcl = false, bool pcl_color = false) -{ - std::cout << std::endl; - - std::map::const_iterator it_enable; - std::map::const_iterator it_param; - - for (it_enable = enables.begin(), it_param = params.begin(); it_enable != enables.end(); ++it_enable) { - rs.setEnableStream(it_enable->first, it_enable->second); - - if (it_enable->second) { - it_param = params.find(it_enable->first); - - if (it_param != params.end()) { - rs.setStreamSettings(it_param->first, it_param->second); - } - } - } - - rs.open(); - - vpImage depth; - vpImage I_depth; - vpImage I_depth_color; - - vpImage I_color; - vpImage infrared; - vpImage I_infrared; - - bool direct_infrared_conversion = false; - for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) { - if (it_enable->second) { - switch (it_enable->first) { - case rs::stream::color: - I_color.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - break; - - case rs::stream::depth: - depth.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_depth.init(depth.getHeight(), depth.getWidth()); - I_depth_color.init(depth.getHeight(), depth.getWidth()); - break; - - case rs::stream::infrared: - infrared.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_infrared.init(infrared.getHeight(), infrared.getWidth()); - - it_param = params.find(it_enable->first); - if (it_param != params.end()) { - direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8; - } - break; - - default: - break; - } - } - } - -#if defined(VISP_HAVE_X11) - vpDisplayX dc, dd, di; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI dc, dd, di; -#endif - - for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) { - if (it_enable->second) { - switch (it_enable->first) { - case rs::stream::color: - dc.init(I_color, 0, 0, "Color frame"); - break; - - case rs::stream::depth: - if (depth_color_visualization) { - dd.init(I_depth_color, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } - else { - dd.init(I_depth, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } - break; - - case rs::stream::infrared: - di.init(I_infrared, 0, (int)(std::max(I_color.getHeight(), I_depth.getHeight())) + 30, "Infrared frame"); - break; - - default: - break; - } - } - } - - if (rs.getHandler()->is_stream_enabled(rs::stream::infrared)) { - std::cout << "direct_infrared_conversion=" << direct_infrared_conversion << std::endl; - } - -#ifdef VISP_HAVE_PCL - std::mutex mutex; - ViewerWorker viewer(pcl_color, mutex); - std::thread viewer_thread; - - if (display_pcl) { - viewer_thread = std::thread(&ViewerWorker::run, &viewer); - } -#else - display_pcl = false; -#endif - - // Test stream acquisition during 10 s - std::vector time_vector; - double t_begin = vpTime::measureTimeMs(); - while (true) { - double t = vpTime::measureTimeMs(); - - if (display_pcl) { -#ifdef VISP_HAVE_PCL - std::lock_guard lock(mutex); - - if (direct_infrared_conversion) { - if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, - (unsigned char *)I_infrared.bitmap, nullptr, color_stream, depth_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)I_infrared.bitmap, nullptr, color_stream, depth_stream); - } - } - else { - if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, - (unsigned char *)infrared.bitmap, nullptr, color_stream, depth_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)infrared.bitmap, nullptr, color_stream, depth_stream); - } - - vpImageConvert::convert(infrared, I_infrared); - } - - update_pointcloud = true; -#endif - } - else { - if (direct_infrared_conversion) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)I_infrared.bitmap, nullptr, color_stream, depth_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)infrared.bitmap, nullptr, color_stream, depth_stream); - vpImageConvert::convert(infrared, I_infrared); - } - } - - if (depth_color_visualization) { - vpImageConvert::createDepthHistogram(depth, I_depth_color); - } - else { - vpImageConvert::createDepthHistogram(depth, I_depth); - } - - vpDisplay::display(I_color); - if (depth_color_visualization) { - vpDisplay::display(I_depth_color); - } - else { - vpDisplay::display(I_depth); - } - vpDisplay::display(I_infrared); - - vpDisplay::flush(I_color); - if (depth_color_visualization) { - vpDisplay::flush(I_depth_color); - } - else { - vpDisplay::flush(I_depth); - } - vpDisplay::flush(I_infrared); - - if (vpDisplay::getClick(I_color, false) || - (depth_color_visualization ? vpDisplay::getClick(I_depth_color, false) : vpDisplay::getClick(I_depth, false)) || - vpDisplay::getClick(I_infrared, false)) { - break; - } - - time_vector.push_back(vpTime::measureTimeMs() - t); - if (vpTime::measureTimeMs() - t_begin >= 10000) { - break; - } - } - - if (display_pcl) { -#ifdef VISP_HAVE_PCL - { - std::lock_guard lock(mutex); - cancelled = true; - } - - viewer_thread.join(); -#endif - } - - std::cout << title << " - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; - - rs.close(); -} - -} // namespace - -int main(int argc, char *argv[]) -{ - try { - vpRealSense rs; - - rs.setEnableStream(rs::stream::color, false); - rs.open(); - if (rs_get_device_name((const rs_device *)rs.getHandler(), nullptr) != std::string("Intel RealSense SR300")) { - std::cout << "This test file is used to test the Intel RealSense SR300 only." << std::endl; - return EXIT_SUCCESS; - } - - std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl; - std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *)rs.getHandler(), nullptr) - << std::endl; - std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; - - rs.close(); - - std::map enables; - std::map params; - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = false; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 240, rs::format::z16, 110); - - test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x240_110FPS"); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = false; - enables[rs::stream::infrared] = false; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30); - - test_SR300(rs, enables, params, "SR300_COLOR_RGBA8_1920x1080_30FPS"); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = false; - enables[rs::stream::infrared] = true; - - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 200); - - test_SR300(rs, enables, params, "SR300_INFRARED_Y16_640x480_200FPS"); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = false; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - - test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x480_60FPS", true); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - - test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x480_60FPS + SR300_INFRARED_Y8_640x480_60FPS", true); - -#if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX, since viewer->spinOnce (10); produces a - // segfault on OSX - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - - // depth == 0 ; color == 1 ; rectified_color == 6 ; color_aligned_to_depth - // == 7 ; depth_aligned_to_color == 9 ; depth_aligned_to_rectified_color - // == 10 argv[1] <==> color stream - rs::stream color_stream = argc > 1 ? (rs::stream)atoi(argv[1]) : rs::stream::color; - std::cout << "\ncolor_stream: " << color_stream << std::endl; - // argv[2] <==> depth stream - rs::stream depth_stream = argc > 2 ? (rs::stream)atoi(argv[2]) : rs::stream::depth; - std::cout << "depth_stream: " << depth_stream << std::endl; - - test_SR300(rs, enables, params, - "SR300_COLOR_RGBA8_640x480_60FPS + " - "SR300_DEPTH_Z16_640x480_60FPS + " - "SR300_INFRARED_Y8_640x480_60FPS", - true, color_stream, depth_stream, true, true); -#endif - - // Color stream aligned to depth - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = false; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 30); - - test_SR300(rs, enables, params, - "SR300_COLOR_ALIGNED_TO_DEPTH_RGBA8_640x480_30FPS + " - "SR300_DEPTH_Z16_640x480_30FPS", - true, rs::stream::color_aligned_to_depth); - - // Depth stream aligned to color - test_SR300(rs, enables, params, - "SR300_COLOR_RGBA8_640x480_30FPS + " - "SR300_DEPTH_ALIGNED_TO_COLOR_Z16_640x480_30FPS", - true, rs::stream::color, rs::stream::depth_aligned_to_color); - - rs.setEnableStream(rs::stream::color, true); - rs.setEnableStream(rs::stream::depth, false); - rs.setEnableStream(rs::stream::infrared, true); - rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::bgr8, 60)); - rs.setStreamSettings(rs::stream::infrared, vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 200)); - rs.open(); - - cv::Mat color_mat(480, 640, CV_8UC3); - cv::Mat infrared_mat(480, 640, CV_8U); - - double t_begin = vpTime::measureTimeMs(); - while (true) { - rs.acquire(color_mat.data, nullptr, nullptr, infrared_mat.data); - - cv::imshow("Color mat", color_mat); - cv::imshow("Infrared mat", infrared_mat); - char c = cv::waitKey(1); - if (c == 27) { - break; - } - - if (vpTime::measureTimeMs() - t_begin >= 10000) { - break; - } - } - } - catch (const vpException &e) { - std::cerr << "RealSense error " << e.what() << std::endl; - } - catch (const rs::error &e) { - std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() - << "): " << e.what() << std::endl; - } - catch (const std::exception &e) { - std::cerr << e.what() << std::endl; - } - - return EXIT_SUCCESS; -} - -#else -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 - return EXIT_SUCCESS; -} -#endif diff --git a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h index eb63fa007e..7f1d4f9a33 100644 --- a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h +++ b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h @@ -36,7 +36,7 @@ #define _vpMegaPose_h_ #include -#if defined(VISP_HAVE_NLOHMANN_JSON) +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h index a806e2ce8e..5dc6026b89 100644 --- a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h +++ b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h @@ -37,10 +37,10 @@ #define _vpMegaPoseTracker_h_ #include -#if defined(VISP_HAVE_NLOHMANN_JSON) +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS) #include -#include +#include #include /** diff --git a/modules/tracker/dnn/src/vpMegaPose.cpp b/modules/tracker/dnn/src/vpMegaPose.cpp index e54af3f485..beb4685fdc 100644 --- a/modules/tracker/dnn/src/vpMegaPose.cpp +++ b/modules/tracker/dnn/src/vpMegaPose.cpp @@ -33,9 +33,12 @@ * *****************************************************************************/ -#include #include +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS) + +#include + #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX #include #include @@ -230,8 +233,8 @@ void decode(const std::vector &buffer, unsigned int &index, vpHomogeneo } /* -Decode multiple objects from a byte array. -These objects can have different types. They are read from the buffer in the order that they are given to the function. + Decode multiple objects from a byte array. + These objects can have different types. They are read from the buffer in the order that they are given to the function. */ template void decode(const std::vector &buffer, unsigned int &index, T &object, Rest& ...rest) @@ -276,20 +279,19 @@ void handleWrongReturnMessage(const vpMegaPose::ServerMessage code, std::vector< const std::unordered_map vpMegaPose::m_codeMap = { - {ServerMessage::ERR, "RERR"}, - {ServerMessage::OK, "OKOK"}, - {ServerMessage::GET_POSE, "GETP"}, - {ServerMessage::RET_POSE, "RETP"}, - {ServerMessage::SET_INTR, "INTR"}, - {ServerMessage::GET_VIZ, "GETV"}, - {ServerMessage::RET_VIZ, "RETV"}, - {ServerMessage::GET_SCORE, "GSCO"}, - {ServerMessage::RET_SCORE, "RSCO"}, - {ServerMessage::SET_SO3_GRID_SIZE, "SO3G"}, - {ServerMessage::GET_LIST_OBJECTS, "GLSO"}, - {ServerMessage::RET_LIST_OBJECTS, "RLSO"}, - {ServerMessage::EXIT, "EXIT"}, - + {ServerMessage::ERR, "RERR"}, + {ServerMessage::OK, "OKOK"}, + {ServerMessage::GET_POSE, "GETP"}, + {ServerMessage::RET_POSE, "RETP"}, + {ServerMessage::SET_INTR, "INTR"}, + {ServerMessage::GET_VIZ, "GETV"}, + {ServerMessage::RET_VIZ, "RETV"}, + {ServerMessage::GET_SCORE, "GSCO"}, + {ServerMessage::RET_SCORE, "RSCO"}, + {ServerMessage::SET_SO3_GRID_SIZE, "SO3G"}, + {ServerMessage::GET_LIST_OBJECTS, "GLSO"}, + {ServerMessage::RET_LIST_OBJECTS, "RLSO"}, + {ServerMessage::EXIT, "EXIT"}, }; std::string vpMegaPose::messageToString(const vpMegaPose::ServerMessage messageType) @@ -326,7 +328,7 @@ std::pair> vpMegaPose::readMessa #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX size_t readCount = read(m_serverSocket, &size, sizeof(uint32_t)); #else - size_t readCount = recv(m_serverSocket, reinterpret_cast(&size), sizeof(uint32_t), 0); + size_t readCount = recv(m_serverSocket, reinterpret_cast(&size), sizeof(uint32_t), 0); #endif if (readCount != sizeof(uint32_t)) { throw vpException(vpException::ioError, "MegaPose: Error while reading data from socket"); @@ -337,7 +339,7 @@ std::pair> vpMegaPose::readMessa #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX readCount = read(m_serverSocket, code, MEGAPOSE_CODE_SIZE); #else - readCount = recv(m_serverSocket, reinterpret_cast(code), MEGAPOSE_CODE_SIZE, 0); + readCount = recv(m_serverSocket, reinterpret_cast(code), MEGAPOSE_CODE_SIZE, 0); #endif if (readCount != MEGAPOSE_CODE_SIZE) { throw vpException(vpException::ioError, "MegaPose: Error while reading data from socket"); @@ -351,7 +353,7 @@ std::pair> vpMegaPose::readMessa #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX int actually_read = read(m_serverSocket, &data[read_total], read_size); #else - int actually_read = recv(m_serverSocket, reinterpret_cast(&data[read_total]), read_size, 0); + int actually_read = recv(m_serverSocket, reinterpret_cast(&data[read_total]), read_size, 0); #endif if (actually_read <= 0) { throw vpException(vpException::ioError, "MegaPose: Error while reading data from socket"); @@ -613,3 +615,19 @@ std::vector vpMegaPose::getObjectNames() std::vector result = jsonValue; return result; } + +#else + +// Work around to avoid libvisp_dnn_tracker library empty when threads are not used +class VISP_EXPORT dummy_vpMegaPose +{ +public: + dummy_vpMegaPose() { }; +}; + +#if !defined(VISP_BUILD_SHARED_LIBS) +// Work around to avoid warning: libvisp_dnn_tracker.a(vpMegaPose.cpp.o) has no symbols +void dummy_vpMegaPose_fct() { }; +#endif + +#endif diff --git a/modules/tracker/dnn/src/vpMegaPoseTracker.cpp b/modules/tracker/dnn/src/vpMegaPoseTracker.cpp index af443d3462..2edca7407d 100644 --- a/modules/tracker/dnn/src/vpMegaPoseTracker.cpp +++ b/modules/tracker/dnn/src/vpMegaPoseTracker.cpp @@ -33,6 +33,10 @@ * *****************************************************************************/ +#include + +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS) + #include #include @@ -72,3 +76,8 @@ void vpMegaPoseTracker::updatePose(const vpHomogeneousMatrix &cTo) m_poseEstimate.cTo = cTo; } +#elif !defined(VISP_BUILD_SHARED_LIBS) +// Work around to avoid warning: libvisp_dnn_tracker.a(vpMegaPoseTracker.cpp.o) has no symbols +void dummy_vpMegaPoseTracker(){}; + +#endif diff --git a/modules/tracker/klt/src/vpKltOpencv.cpp b/modules/tracker/klt/src/vpKltOpencv.cpp index ffd237b816..6f74012751 100644 --- a/modules/tracker/klt/src/vpKltOpencv.cpp +++ b/modules/tracker/klt/src/vpKltOpencv.cpp @@ -51,16 +51,16 @@ vpKltOpencv::vpKltOpencv() : m_gray(), m_prevGray(), m_points_id(), m_maxCount(500), m_termcrit(), m_winSize(10), m_qualityLevel(0.01), - m_minDistance(15), m_minEigThreshold(1e-4), m_harris_k(0.04), m_blockSize(3), m_useHarrisDetector(1), - m_pyrMaxLevel(3), m_next_points_id(0), m_initial_guess(false) + m_minDistance(15), m_minEigThreshold(1e-4), m_harris_k(0.04), m_blockSize(3), m_useHarrisDetector(1), + m_pyrMaxLevel(3), m_next_points_id(0), m_initial_guess(false) { m_termcrit = cv::TermCriteria(cv::TermCriteria::COUNT | cv::TermCriteria::EPS, 20, 0.03); } vpKltOpencv::vpKltOpencv(const vpKltOpencv ©) : m_gray(), m_prevGray(), m_points_id(), m_maxCount(500), m_termcrit(), m_winSize(10), m_qualityLevel(0.01), - m_minDistance(15), m_minEigThreshold(1e-4), m_harris_k(0.04), m_blockSize(3), m_useHarrisDetector(1), - m_pyrMaxLevel(3), m_next_points_id(0), m_initial_guess(false) + m_minDistance(15), m_minEigThreshold(1e-4), m_harris_k(0.04), m_blockSize(3), m_useHarrisDetector(1), + m_pyrMaxLevel(3), m_next_points_id(0), m_initial_guess(false) { *this = copy; } @@ -88,7 +88,7 @@ vpKltOpencv &vpKltOpencv::operator=(const vpKltOpencv ©) return *this; } -vpKltOpencv::~vpKltOpencv() {} +vpKltOpencv::~vpKltOpencv() { } void vpKltOpencv::initTracking(const cv::Mat &I, const cv::Mat &mask) { @@ -127,7 +127,8 @@ void vpKltOpencv::track(const cv::Mat &I) if (m_initial_guess) { flags |= cv::OPTFLOW_USE_INITIAL_FLOW; m_initial_guess = false; - } else { + } + else { std::swap(m_points[1], m_points[0]); } @@ -275,7 +276,8 @@ void vpKltOpencv::initTracking(const cv::Mat &I, const std::vector m_next_points_id = 0; for (size_t i = 0; i < m_points[1].size(); i++) m_points_id.push_back(m_next_points_id++); - } else { + } + else { long max = 0; for (size_t i = 0; i < m_points[1].size(); i++) { m_points_id.push_back(ids[i]); @@ -326,13 +328,12 @@ void vpKltOpencv::suppressFeature(const int &index) class VISP_EXPORT dummy_vpKltOpencv { public: - dummy_vpKltOpencv(){}; + dummy_vpKltOpencv() { }; }; #if !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_klt.a(vpKltOpenCV.cpp.o) has no -// symbols -void dummy_vpKltOpenCV_fct(){}; +// Work around to avoid warning: libvisp_klt.a(vpKltOpenCV.cpp.o) has no symbols +void dummy_vpKltOpenCV_fct() { }; #endif #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h old mode 100755 new mode 100644 diff --git a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp index eb5b1b9a2c..21a7475d42 100644 --- a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp +++ b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp @@ -1461,7 +1461,6 @@ void vpMbKltTracker::setUseKltTracking(const std::string &name, const bool &useK } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_mbt.a(vpMbKltTracker.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_mbt.a(vpMbKltTracker.cpp.o) has no symbols void dummy_vpMbKltTracker() { }; #endif // VISP_HAVE_OPENCV diff --git a/modules/tracker/mbt/src/vpMbTracker.cpp b/modules/tracker/mbt/src/vpMbTracker.cpp index 4f973fe94e..686c7a830e 100644 --- a/modules/tracker/mbt/src/vpMbTracker.cpp +++ b/modules/tracker/mbt/src/vpMbTracker.cpp @@ -93,7 +93,7 @@ #include #endif -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) #include #endif @@ -101,7 +101,7 @@ namespace { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::mutex g_mutex_cout; #endif /*! @@ -1838,7 +1838,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbrPoint << " points" << std::endl; @@ -1887,7 +1887,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbrLine << " lines" << std::endl; @@ -1969,7 +1969,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbrPolygonLine << " polygon lines" << std::endl; @@ -2058,7 +2058,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbrPolygonPoint << " polygon points" << std::endl; @@ -2131,7 +2131,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbCylinder << " cylinders" << std::endl; @@ -2213,7 +2213,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbCircle << " circles" << std::endl; @@ -2278,7 +2278,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "Global information for " << vpIoTools::getName(modelFile) << " :" << std::endl; @@ -2290,7 +2290,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << nbPoints << " points" << std::endl; diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp index 3e23e77981..95334199c3 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_CATCH2) +#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp index a66ea1eb23..634b7a300f 100644 --- a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp +++ b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp @@ -78,9 +78,9 @@ void vpTemplateTrackerMI::setBspline(const vpBsplineType &newbs) vpTemplateTrackerMI::vpTemplateTrackerMI(vpTemplateTrackerWarp *_warp) : vpTemplateTracker(_warp), hessianComputation(USE_HESSIEN_NORMAL), ApproxHessian(HESSIAN_NEW), lambda(0), temp(nullptr), - Prt(nullptr), dPrt(nullptr), Pt(nullptr), Pr(nullptr), d2Prt(nullptr), PrtTout(nullptr), dprtemp(nullptr), PrtD(nullptr), dPrtD(nullptr), - influBspline(0), bspline(3), Nc(8), Ncb(0), d2Ix(), d2Iy(), d2Ixy(), MI_preEstimation(0), MI_postEstimation(0), - NMI_preEstimation(0), NMI_postEstimation(0), covarianceMatrix(), computeCovariance(false) + Prt(nullptr), dPrt(nullptr), Pt(nullptr), Pr(nullptr), d2Prt(nullptr), PrtTout(nullptr), dprtemp(nullptr), PrtD(nullptr), dPrtD(nullptr), + influBspline(0), bspline(3), Nc(8), Ncb(0), d2Ix(), d2Iy(), d2Ixy(), MI_preEstimation(0), MI_postEstimation(0), + NMI_preEstimation(0), NMI_postEstimation(0), covarianceMatrix(), computeCovariance(false) { Ncb = Nc + bspline; influBspline = bspline * bspline; @@ -272,7 +272,8 @@ double vpTemplateTrackerMI::getNormalizedCost(const vpImage &I, c int Tij_ = static_cast(Tij); if (!blur) { IW = I[(int)i2][(int)j2]; - } else { + } + else { IW = BI.getValue(i2, j2); } int IW_ = static_cast(IW); @@ -438,7 +439,7 @@ void vpTemplateTrackerMI::computeHessien(vpMatrix &Hessian) for (unsigned int jt = 0; jt < nbParam; jt++) { if (ApproxHessian != HESSIAN_NONSECOND && ApproxHessian != HESSIAN_NEW) Hessian[it][jt] += - dprtemp[it] * dprtemp[jt] * Prt_Pt_ + d2Prt[r_Ncb_t_nbParam2_it_nbParam_ + jt] * dtemp; + dprtemp[it] * dprtemp[jt] * Prt_Pt_ + d2Prt[r_Ncb_t_nbParam2_it_nbParam_ + jt] * dtemp; else if (ApproxHessian == HESSIAN_NEW) Hessian[it][jt] += d2Prt[r_Ncb_t_nbParam2_it_nbParam_ + jt] * dtemp; else @@ -656,7 +657,8 @@ double vpTemplateTrackerMI::getMI(const vpImage &I, int &nc, cons delete[] tPt; return 0; - } else { + } + else { for (unsigned int r = 0; r < tNcb; r++) for (unsigned int t = 0; t < tNcb; t++) tPrt[r * tNcb + t] = tPrt[r * tNcb + t] / Nbpoint; diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index 5eaef2c574..e476fb83be 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -49,7 +49,7 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) #include #endif @@ -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_98) +#if defined(VISP_HAVE_THREADS) unsigned int nbThreads = 1; bool executeParallelVersion = useParallelRansac; #else @@ -363,7 +363,7 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo #endif if (executeParallelVersion) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) if (nbParallelRansacThreads <= 0) { // Get number of CPU threads nbThreads = std::thread::hardware_concurrency(); @@ -381,7 +381,7 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo bool foundSolution = false; if (executeParallelVersion) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::vector threadpool; std::vector ransacWorkers; diff --git a/platforms/android/build_sdk.py b/platforms/android/build_sdk.py old mode 100755 new mode 100644 diff --git a/script/make-coverage-report.sh b/script/make-coverage-report.sh old mode 100755 new mode 100644 diff --git a/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp b/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp index 4e682c121e..46c45a5922 100644 --- a/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp +++ b/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp @@ -2,39 +2,29 @@ #include #include -#include -#include #include #include #include #include #include -#if defined(HAVE_OPENCV_OBJDETECT) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEOIO) && (defined(VISP_HAVE_PTHREAD) || defined(_WIN32)) +#if defined(HAVE_OPENCV_OBJDETECT) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) \ + && defined(HAVE_OPENCV_VIDEOIO) && defined(VISP_HAVE_THREADS) + +#include +#include #include // Shared vars typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; -t_CaptureState s_capture_state = capture_waiting; -bool s_face_available = false; -#if defined(VISP_HAVE_V4L2) -vpImage s_frame; -#elif defined(VISP_HAVE_OPENCV) -cv::Mat s_frame; -#endif -vpMutex s_mutex_capture; -vpMutex s_mutex_face; -vpRect s_face_bbox; -vpThread::Return captureFunction(vpThread::Args args) -{ #if defined(VISP_HAVE_V4L2) - vpV4l2Grabber cap = *(static_cast(args)); +void captureFunction(vpV4l2Grabber &cap, std::mutex &mutex_capture, vpImage &frame, t_CaptureState &capture_state) #elif defined(HAVE_OPENCV_VIDEOIO) - cv::VideoCapture cap = *((cv::VideoCapture *)args); +void captureFunction(cv::VideoCapture &cap, std::mutex &mutex_capture, cv::Mat &frame, t_CaptureState &capture_state) #endif - +{ // If the image is larger than 640 by 480, we subsample #if defined(VISP_HAVE_V4L2) vpImage frame_; @@ -50,26 +40,28 @@ vpThread::Return captureFunction(vpThread::Args args) // Update shared data { - vpMutex::vpScopedLock lock(s_mutex_capture); - if (s_capture_state == capture_stopped) + std::lock_guard lock(mutex_capture); + if (capture_state == capture_stopped) stop_capture_ = true; else - s_capture_state = capture_started; - s_frame = frame_; + capture_state = capture_started; + frame = frame_; } } { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } std::cout << "End of capture thread" << std::endl; - return 0; } -vpThread::Return displayFunction(vpThread::Args args) +#if defined(VISP_HAVE_V4L2) +void displayFunction(std::mutex &mutex_capture, std::mutex &mutex_face, vpImage &frame, t_CaptureState &capture_state, vpRect &face_bbox, bool &face_available) +#elif defined(HAVE_OPENCV_VIDEOIO) +void displayFunction(std::mutex &mutex_capture, std::mutex &mutex_face, cv::Mat &frame, t_CaptureState &capture_state, vpRect &face_bbox, bool &face_available) +#endif { - (void)args; // Avoid warning: unused parameter args vpImage I_; t_CaptureState capture_state_; @@ -83,20 +75,20 @@ vpThread::Return displayFunction(vpThread::Args args) #endif do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); + mutex_capture.lock(); + capture_state_ = capture_state; + mutex_capture.unlock(); // Check if a frame is available if (capture_state_ == capture_started) { // Get the frame and convert it to a ViSP image used by the display // class { - vpMutex::vpScopedLock lock(s_mutex_capture); + std::lock_guard lock(mutex_capture); #if defined(VISP_HAVE_V4L2) - I_ = s_frame; + I_ = frame; #elif defined(VISP_HAVE_OPENCV) - vpImageConvert::convert(s_frame, I_); + vpImageConvert::convert(frame, I_); #endif } @@ -117,9 +109,10 @@ vpThread::Return displayFunction(vpThread::Args args) // Check if a face was detected { - vpMutex::vpScopedLock lock(s_mutex_face); - face_available_ = s_face_available; - face_bbox_ = s_face_bbox; + + std::lock_guard lock(mutex_face); + face_available_ = face_available; + face_bbox_ = face_bbox; } if (face_available_) { // Access to the face bounding box to display it @@ -130,8 +123,8 @@ vpThread::Return displayFunction(vpThread::Args args) // Trigger end of acquisition with a mouse click vpDisplay::displayText(I_, 10, 10, "Click to exit...", vpColor::red); if (vpDisplay::getClick(I_, false)) { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } // Update the display @@ -147,16 +140,17 @@ vpThread::Return displayFunction(vpThread::Args args) #endif std::cout << "End of display thread" << std::endl; - return 0; } //! [face-detection-threaded detectionFunction] -vpThread::Return detectionFunction(vpThread::Args args) +#if defined(VISP_HAVE_V4L2) +void detectionFunction(std::mutex &mutex_capture, std::mutex &mutex_face, vpImage &frame, t_CaptureState &capture_state, vpRect &face_bbox, std::string &face_cascade_name, bool &face_available) +#elif defined(HAVE_OPENCV_VIDEOIO) +void detectionFunction(std::mutex &mutex_capture, std::mutex &mutex_face, cv::Mat &frame, t_CaptureState &capture_state, vpRect &face_bbox, std::string &face_cascade_name, bool &face_available) +#endif { - std::string opt_face_cascade_name = *((std::string *)args); - vpDetectorFace face_detector_; - face_detector_.setCascadeClassifierFile(opt_face_cascade_name); + face_detector_.setCascadeClassifierFile(face_cascade_name); t_CaptureState capture_state_; #if defined(VISP_HAVE_V4L2) @@ -165,24 +159,24 @@ vpThread::Return detectionFunction(vpThread::Args args) cv::Mat frame_; #endif do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); + mutex_capture.lock(); + capture_state_ = capture_state; + mutex_capture.unlock(); // Check if a frame is available if (capture_state_ == capture_started) { // Backup the frame { - vpMutex::vpScopedLock lock(s_mutex_capture); - frame_ = s_frame; + std::lock_guard lock(mutex_capture); + frame_ = frame; } // Detect faces bool face_found_ = face_detector_.detect(frame_); if (face_found_) { - vpMutex::vpScopedLock lock(s_mutex_face); - s_face_available = true; - s_face_bbox = face_detector_.getBBox(0); // Get largest face bounding box + std::lock_guard lock(mutex_face); + face_available = true; + face_bbox = face_detector_.getBBox(0); // Get largest face bounding box } } else { @@ -190,13 +184,11 @@ vpThread::Return detectionFunction(vpThread::Args args) } } while (capture_state_ != capture_stopped); std::cout << "End of face detection thread" << std::endl; - - return 0; } //! [face-detection-threaded detectionFunction] //! [face-detection-threaded mainFunction] -int main(int argc, const char *argv []) +int main(int argc, const char *argv[]) { std::string opt_face_cascade_name = "./haarcascade_frontalface_alt.xml"; unsigned int opt_device = 0; @@ -221,12 +213,14 @@ int main(int argc, const char *argv []) // Instantiate the capture #if defined(VISP_HAVE_V4L2) + vpImage frame; vpV4l2Grabber cap; std::ostringstream device; device << "/dev/video" << opt_device; cap.setDevice(device.str()); cap.setScale(opt_scale); #elif defined(HAVE_OPENCV_VIDEOIO) + cv::Mat frame; cv::VideoCapture cap; cap.open(opt_device); #if (VISP_HAVE_OPENCV_VERSION >= 0x030000) @@ -242,10 +236,18 @@ int main(int argc, const char *argv []) #endif #endif + std::mutex mutex_capture; + std::mutex mutex_face; + vpRect face_bbox; + t_CaptureState capture_state = capture_waiting; + bool face_available = false; + // Start the threads - vpThread thread_capture((vpThread::Fn)captureFunction, (vpThread::Args)&cap); - vpThread thread_display((vpThread::Fn)displayFunction); - vpThread thread_detection((vpThread::Fn)detectionFunction, (vpThread::Args)&opt_face_cascade_name); + std::thread thread_capture(&captureFunction, std::ref(cap), std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); + std::thread thread_display(&displayFunction, std::ref(mutex_capture), std::ref(mutex_face), std::ref(frame), + std::ref(capture_state), std::ref(face_bbox), std::ref(face_available)); + std::thread thread_detection(&detectionFunction, std::ref(mutex_capture), std::ref(mutex_face), std::ref(frame), + std::ref(capture_state), std::ref(face_bbox), std::ref(opt_face_cascade_name), std::ref(face_available)); // Wait until thread ends up thread_capture.join(); diff --git a/tutorial/grabber/tutorial-grabber-1394.cpp b/tutorial/grabber/tutorial-grabber-1394.cpp index 8593aeca02..d495fccb1e 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) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_DC1394) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp index 244e93e047..dc08bb5b45 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) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PYLON) && defined(VISP_HAVE_THREADS) try { unsigned int opt_device = 0; std::string opt_type("GigE"); diff --git a/tutorial/grabber/tutorial-grabber-bebop2.cpp b/tutorial/grabber/tutorial-grabber-bebop2.cpp index e7c14dbb53..ab2c985e3a 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) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_FFMPEG) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-flycapture.cpp b/tutorial/grabber/tutorial-grabber-flycapture.cpp index d3251c0480..feb532ddc6 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) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_FLYCAPTURE) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-ids-ueye.cpp b/tutorial/grabber/tutorial-grabber-ids-ueye.cpp index 635fa29fa2..fe6886eec0 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) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UEYE) && defined(VISP_HAVE_THREADS) try { unsigned int opt_device = 0; std::string opt_seqname; @@ -217,7 +217,7 @@ int main(int argc, const char *argv[]) std::cout << "Active camera is Model " << g.getActiveCameraModel() << " with S/N: " << g.getActiveCameraSerialNumber() << std::endl; -//! [Open connection] + //! [Open connection] g.open(I); //! [Open connection] diff --git a/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp b/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp index b42cc9f944..78bb337b40 100644 --- a/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp +++ b/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp @@ -3,38 +3,34 @@ #include #include -#include -#include #include #include #include -#if defined(HAVE_OPENCV_VIDEOIO) && (defined(VISP_HAVE_PTHREAD) || defined(_WIN32)) +#if defined(HAVE_OPENCV_VIDEOIO) && defined(VISP_HAVE_THREADS) + +#include +#include #include #include -// Shared vars +// Possible capture states typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; -t_CaptureState s_capture_state = capture_waiting; -cv::Mat s_frame; -vpMutex s_mutex_capture; //! [capture-multi-threaded declaration] //! [capture-multi-threaded captureFunction] -vpThread::Return captureFunction(vpThread::Args args) +void captureFunction(cv::VideoCapture &cap, std::mutex &mutex_capture, cv::Mat &frame, t_CaptureState &capture_state) { - cv::VideoCapture cap = *((cv::VideoCapture *)args); - if (!cap.isOpened()) { // check if we succeeded std::cout << "Unable to start capture" << std::endl; - return 0; + return; } cv::Mat frame_; int i = 0; while ((i++ < 100) && !cap.read(frame_)) { - }; // warm up camera by skiping unread frames + }; // warm up camera by skipping unread frames bool stop_capture_ = false; @@ -45,29 +41,27 @@ vpThread::Return captureFunction(vpThread::Args args) // Update shared data { - vpMutex::vpScopedLock lock(s_mutex_capture); - if (s_capture_state == capture_stopped) + std::lock_guard lock(mutex_capture); + if (capture_state == capture_stopped) stop_capture_ = true; else - s_capture_state = capture_started; - s_frame = frame_; + capture_state = capture_started; + frame = frame_; } } { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } std::cout << "End of capture thread" << std::endl; - return 0; } //! [capture-multi-threaded captureFunction] //! [capture-multi-threaded displayFunction] -vpThread::Return displayFunction(vpThread::Args args) +void displayFunction(std::mutex &mutex_capture, cv::Mat &frame, t_CaptureState &capture_state) { - (void)args; // Avoid warning: unused parameter args vpImage I_; t_CaptureState capture_state_; @@ -79,17 +73,17 @@ vpThread::Return displayFunction(vpThread::Args args) #endif do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); + mutex_capture.lock(); + capture_state_ = capture_state; + mutex_capture.unlock(); // Check if a frame is available if (capture_state_ == capture_started) { // Get the frame and convert it to a ViSP image used by the display // class { - vpMutex::vpScopedLock lock(s_mutex_capture); - vpImageConvert::convert(s_frame, I_); + std::lock_guard lock(mutex_capture); + vpImageConvert::convert(frame, I_); } // Check if we need to initialize the display with the first frame @@ -110,8 +104,8 @@ vpThread::Return displayFunction(vpThread::Args args) // Trigger end of acquisition with a mouse click vpDisplay::displayText(I_, 10, 10, "Click to exit...", vpColor::red); if (vpDisplay::getClick(I_, false)) { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } // Update the display @@ -127,12 +121,11 @@ vpThread::Return displayFunction(vpThread::Args args) #endif std::cout << "End of display thread" << std::endl; - return 0; } //! [capture-multi-threaded displayFunction] //! [capture-multi-threaded mainFunction] -int main(int argc, const char *argv []) +int main(int argc, const char *argv[]) { int opt_device = 0; @@ -150,9 +143,13 @@ int main(int argc, const char *argv []) cv::VideoCapture cap; cap.open(opt_device); + cv::Mat frame; + t_CaptureState capture_state = capture_waiting; + // Create a mutex for capture + std::mutex mutex_capture; // Start the threads - vpThread thread_capture((vpThread::Fn)captureFunction, (vpThread::Args)&cap); - vpThread thread_display((vpThread::Fn)displayFunction); + std::thread thread_capture(&captureFunction, std::ref(cap), std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); + std::thread thread_display(&displayFunction, std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); // Wait until thread ends up thread_capture.join(); diff --git a/tutorial/grabber/tutorial-grabber-opencv.cpp b/tutorial/grabber/tutorial-grabber-opencv.cpp index 0a0d14133a..c41aab74b1 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) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(HAVE_OPENCV_VIDEOIO) && defined(HAVE_OPENCV_HIGHGUI) && defined(VISP_HAVE_THREADS) try { cv::VideoCapture cap(opt_device); // open the default camera if (!cap.isOpened()) { // check if we succeeded diff --git a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp index 6b0b06c2e3..2fab7ac820 100644 --- a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp @@ -56,8 +56,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) \ - && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname_left = "left-%04d.png", opt_seqname_right = "right-%04d.png"; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-realsense.cpp b/tutorial/grabber/tutorial-grabber-realsense.cpp index 424c1f23bf..f038a51c09 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) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-structure-core.cpp b/tutorial/grabber/tutorial-grabber-structure-core.cpp index 25799e790f..f3e9417d62 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) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname_visible = "visible-%04d.png", opt_seqname_depth = "depth-%04d.png"; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp b/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp index 5a0c538a0a..89ce052f69 100644 --- a/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp +++ b/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp @@ -1,27 +1,23 @@ //! \example tutorial-grabber-v4l2-threaded.cpp //! [capture-multi-threaded declaration] #include - #include -#include -#include #include #include #include -#if defined(VISP_HAVE_V4L2) && defined(VISP_HAVE_PTHREAD) +#if defined(VISP_HAVE_V4L2) && defined(VISP_HAVE_THREADS) + +#include +#include // Shared vars typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; -t_CaptureState s_capture_state = capture_waiting; -vpImage s_frame; -vpMutex s_mutex_capture; //! [capture-multi-threaded declaration] //! [capture-multi-threaded captureFunction] -vpThread::Return captureFunction(vpThread::Args args) +void captureFunction(vpV4l2Grabber &cap, std::mutex &mutex_capture, vpImage &frame, t_CaptureState &capture_state) { - vpV4l2Grabber cap = *(static_cast(args)); vpImage frame_; bool stop_capture_ = false; @@ -34,28 +30,26 @@ vpThread::Return captureFunction(vpThread::Args args) // Update shared data { - vpMutex::vpScopedLock lock(s_mutex_capture); - if (s_capture_state == capture_stopped) + std::lock_guard lock(mutex_capture); + if (capture_state == capture_stopped) stop_capture_ = true; else - s_capture_state = capture_started; - s_frame = frame_; + capture_state = capture_started; + frame = frame_; } } { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } std::cout << "End of capture thread" << std::endl; - return 0; } //! [capture-multi-threaded captureFunction] //! [capture-multi-threaded displayFunction] -vpThread::Return displayFunction(vpThread::Args args) +void displayFunction(std::mutex &mutex_capture, vpImage &frame, t_CaptureState &capture_state) { - (void)args; // Avoid warning: unused parameter args vpImage I_; t_CaptureState capture_state_; @@ -65,16 +59,16 @@ vpThread::Return displayFunction(vpThread::Args args) #endif do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); + mutex_capture.lock(); + capture_state_ = capture_state; + mutex_capture.unlock(); // Check if a frame is available if (capture_state_ == capture_started) { // Create a copy of the captured frame { - vpMutex::vpScopedLock lock(s_mutex_capture); - I_ = s_frame; + std::lock_guard lock(mutex_capture); + I_ = frame; } // Check if we need to initialize the display with the first frame @@ -92,13 +86,14 @@ vpThread::Return displayFunction(vpThread::Args args) // Trigger end of acquisition with a mouse click vpDisplay::displayText(I_, 10, 10, "Click to exit...", vpColor::red); if (vpDisplay::getClick(I_, false)) { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } // Update the display vpDisplay::flush(I_); - } else { + } + else { vpTime::wait(2); // Sleep 2ms } } while (capture_state_ != capture_stopped); @@ -108,7 +103,6 @@ vpThread::Return displayFunction(vpThread::Args args) #endif std::cout << "End of display thread" << std::endl; - return 0; } //! [capture-multi-threaded displayFunction] @@ -127,8 +121,8 @@ int main(int argc, const char *argv[]) opt_scale = (unsigned int)atoi(argv[i + 1]); else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "--h") { std::cout << "Usage: " << argv[0] - << " [--camera_device ] [--scale ]" - << " [--help] [-h]" << std::endl; + << " [--camera_device ] [--scale ]" + << " [--help] [-h]" << std::endl; return EXIT_SUCCESS; } } @@ -140,9 +134,13 @@ int main(int argc, const char *argv[]) g.setDevice(device.str()); g.setScale(opt_scale); + vpImage frame; + std::mutex mutex_capture; + t_CaptureState capture_state = capture_waiting; + // Start the threads - vpThread thread_capture((vpThread::Fn)captureFunction, (vpThread::Args)&g); - vpThread thread_display((vpThread::Fn)displayFunction); + std::thread thread_capture(&captureFunction, std::ref(g), std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); + std::thread thread_display(&displayFunction, std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); // Wait until thread ends up thread_capture.join(); diff --git a/tutorial/grabber/tutorial-grabber-v4l2.cpp b/tutorial/grabber/tutorial-grabber-v4l2.cpp index 36fba4330e..a65213fd7a 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) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_V4L2) && defined(VISP_HAVE_THREADS) try { int opt_device = 0; unsigned int opt_scale = 1; // Default value is 2 in the constructor. Turn diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.h b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.h old mode 100755 new mode 100644 diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.mm b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.mm old mode 100755 new mode 100644 diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.h b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.h old mode 100755 new mode 100644 diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.mm b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.mm old mode 100755 new mode 100644 diff --git a/tutorial/robot/mbot/raspberry/daemon/visual-servo b/tutorial/robot/mbot/raspberry/daemon/visual-servo old mode 100755 new mode 100644 diff --git a/tutorial/tracking/dnn/tutorial-megapose-live-single-object-tracking.cpp b/tutorial/tracking/dnn/tutorial-megapose-live-single-object-tracking.cpp index 14ba48ae7f..3aa239b2c9 100644 --- a/tutorial/tracking/dnn/tutorial-megapose-live-single-object-tracking.cpp +++ b/tutorial/tracking/dnn/tutorial-megapose-live-single-object-tracking.cpp @@ -6,7 +6,8 @@ // Check if std:c++17 or higher #if ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) && \ defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_VIDEOIO) && \ - defined(HAVE_OPENCV_DNN) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(HAVE_OPENCV_HIGHGUI)) + defined(HAVE_OPENCV_DNN) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(HAVE_OPENCV_HIGHGUI)) && \ + defined(VISP_HAVE_THREADS) #include 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 old mode 100755 new mode 100644 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 old mode 100755 new mode 100644 diff --git a/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-afma6.cpp b/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-afma6.cpp index 143b585f04..603fe9dcfc 100644 --- a/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-afma6.cpp +++ b/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-afma6.cpp @@ -30,7 +30,7 @@ void display_trajectory(const vpImage &I, std::vector &p int main() { -#if defined(VISP_HAVE_PTHREAD) +#if defined(VISP_HAVE_THREADS) try { vpHomogeneousMatrix cdMo(0, 0, 0.75, 0, 0, 0); vpHomogeneousMatrix cMo(-0.15, 0.1, 1., vpMath::rad(-10), vpMath::rad(10), vpMath::rad(50)); diff --git a/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-viper.cpp b/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-viper.cpp index 68b20c377b..00bbc20c4e 100644 --- a/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-viper.cpp +++ b/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-viper.cpp @@ -30,7 +30,7 @@ void display_trajectory(const vpImage &I, std::vector &p int main() { -#if defined(VISP_HAVE_PTHREAD) +#if defined(VISP_HAVE_THREADS) try { vpHomogeneousMatrix cdMo(0, 0, 0.75, 0, 0, 0); vpHomogeneousMatrix cMo(0.15, -0.1, 1., vpMath::rad(10), vpMath::rad(-10), vpMath::rad(50));