diff --git a/.github/workflows/ubuntu-dep-src.yml b/.github/workflows/ubuntu-dep-src.yml index 4f85386dcf..381b3d4041 100644 --- a/.github/workflows/ubuntu-dep-src.yml +++ b/.github/workflows/ubuntu-dep-src.yml @@ -74,7 +74,7 @@ jobs: pwd echo "GIT_CLONE_PROTECTION_ACTIVE=false" >> $GITHUB_ENV export GIT_CLONE_PROTECTION_ACTIVE=false - git clone --recursive --depth 1 https://github.com/Kitware/VTK.git ${HOME}/VTK + git clone --recursive --depth 1 --branch v9.3.0 https://github.com/Kitware/VTK.git ${HOME}/VTK cd ${HOME}/VTK mkdir build && cd build && mkdir install cmake .. -DVTK_ANDROID_BUILD=OFF -DVTK_BUILD_DOCUMENTATION=OFF -DVTK_BUILD_EXAMPLES=OFF -DVTK_BUILD_EXAMPLES=OFF -DCMAKE_BUILD_TYPE=Release \ diff --git a/.vscode/settings.json b/.vscode/settings.json index 26ebfdc369..e4c76f7c07 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -195,4 +195,5 @@ "editor.rulers": [ {"column": 120, "color": "#ffcc00"} ], + "C_Cpp.default.compilerPath": "/usr/bin/g++", } diff --git a/CMakeLists.txt b/CMakeLists.txt index 34ac969235..5ad2569a7e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -541,6 +541,9 @@ VP_OPTION(ENABLE_MOMENTS_COMBINE_MATRICES "" "" "Use linear combination of matr VP_OPTION(ENABLE_TEST_WITHOUT_DISPLAY "" "" "Don't use display feature when testing" "" ON) VP_OPTION(ENABLE_FULL_DOC "" "" "Build doc with internal classes that are by default not part of the doc" "" OFF) +# Allow introduction of "visp" namespace. By default disabled to keep compat with previous versions +VP_OPTION(ENABLE_VISP_NAMESPACE "" "" "Enable visp namespace" "" OFF) + if(ENABLE_SOLUTION_FOLDERS) set_property(GLOBAL PROPERTY USE_FOLDERS ON) set_property(GLOBAL PROPERTY PREDEFINED_TARGETS_FOLDER "CMakeTargets") @@ -777,17 +780,18 @@ endif() # ---------------------------------------------------------------------------- # Build-in 3rd parties. Should be after c++ standard potential modification # ---------------------------------------------------------------------------- -VP_OPTION(WITH_PTHREAD "" "" "Build pthread as built-in library" "" ON IF (WIN32 OR MINGW) AND (NOT WINRT)) +VP_OPTION(WITH_PTHREAD "" "" "Use 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 USE_PTHREAD 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) -VP_OPTION(WITH_ATIDAQ "" "" "Build atidaq-c as built-in library" "" ON IF USE_COMEDI AND NOT WINRT) -VP_OPTION(WITH_CLIPPER "" "" "Build clipper as built-in library" "" ON IF USE_OPENCV) -VP_OPTION(WITH_LAPACK "" "" "Build lapack as built-in library" "" ON IF NOT USE_LAPACK) -VP_OPTION(WITH_QBDEVICE "" "" "Build qbdevice-api as built-in library" "" ON IF (NOT WINRT) AND (NOT IOS)) -VP_OPTION(WITH_TAKKTILE2 "" "" "Build Right Hand takktile2 driver as built-in library" "" ON IF (NOT WIN32) AND (NOT WINRT) AND (NOT IOS) AND (NOT ANDROID)) +VP_OPTION(WITH_APRILTAG "" "" "Use AprilTag as built-in library" "" ON IF (USE_THREADS OR USE_PTHREAD OR WITH_PTHREAD) AND (NOT WINRT) AND (NOT MSVC_VERSION LESS 1700)) +VP_OPTION(WITH_APRILTAG_BIG_FAMILY "" "" "Use AprilTag big family (41h12, 48h12, 49h12, 52h13)" "" OFF IF WITH_APRILTAG) +VP_OPTION(WITH_MINIZ "" "" "Use npz related I/O as built-in functions" "" ON) +VP_OPTION(WITH_ATIDAQ "" "" "Use atidaq-c as built-in library" "" ON IF USE_COMEDI AND NOT WINRT) +VP_OPTION(WITH_CLIPPER "" "" "Use clipper as built-in library" "" ON IF USE_OPENCV) +VP_OPTION(WITH_LAPACK "" "" "Use lapack as built-in library" "" ON IF NOT USE_LAPACK) +VP_OPTION(WITH_QBDEVICE "" "" "Use qbdevice-api as built-in library" "" ON IF (NOT WINRT) AND (NOT IOS)) +VP_OPTION(WITH_TAKKTILE2 "" "" "Use Right Hand takktile2 driver as built-in library" "" ON IF (NOT WIN32) AND (NOT WINRT) AND (NOT IOS) AND (NOT ANDROID)) VP_OPTION(WITH_CATCH2 "" "" "Use catch2 built-in library" "" ON) -VP_OPTION(WITH_POLOLU "" "" "Build rapa pololu as built-in library" "" ON IF (NOT WINRT) AND (NOT IOS) AND (NOT ANDROID)) +VP_OPTION(WITH_POLOLU "" "" "Use rapa pololu as built-in library" "" ON IF (NOT WINRT) AND (NOT IOS) AND (NOT ANDROID)) VP_OPTION(WITH_PUGIXML "" "" "Use pugixml built-in third-party" "" ON) VP_OPTION(WITH_SIMDLIB "" "" "Use simdlib built-in third-party" "" ON) VP_OPTION(WITH_STBIMAGE "" "" "Use std_image built-in third-party" "" ON) @@ -1146,6 +1150,7 @@ VP_SET(VISP_HAVE_SIMDLIB TRUE IF (BUILD_MODULE_visp_core AND WITH_SIMDLIB)) VP_SET(VISP_HAVE_STBIMAGE TRUE IF (BUILD_MODULE_visp_core AND WITH_STBIMAGE)) VP_SET(VISP_HAVE_TINYEXR TRUE IF (BUILD_MODULE_visp_core AND WITH_TINYEXR)) VP_SET(VISP_HAVE_PUGIXML TRUE IF (BUILD_MODULE_visp_core AND WITH_PUGIXML)) +VP_SET(VISP_HAVE_MINIZ TRUE IF (BUILD_MODULE_visp_core AND WITH_MINIZ)) VP_SET(VISP_HAVE_QUALISYS TRUE IF (BUILD_MODULE_visp_sensor AND USE_QUALISYS)) VP_SET(VISP_HAVE_VICON TRUE IF (BUILD_MODULE_visp_sensor AND USE_VICON)) @@ -1603,6 +1608,7 @@ status(" To be built:" VISP_MODULES_BUILD THEN ${VISP_MOD status(" Disabled:" VISP_MODULES_DISABLED_USER THEN ${VISP_MODULES_DISABLED_USER_ST} ELSE "-") status(" Disabled by dependency:" VISP_MODULES_DISABLED_AUTO THEN ${VISP_MODULES_DISABLED_AUTO_ST} ELSE "-") status(" Unavailable:" VISP_MODULES_DISABLED_FORCE THEN ${VISP_MODULES_DISABLED_FORCE_ST} ELSE "-") +status(" Enable visp namespace:" ENABLE_VISP_NAMESPACE THEN "yes" ELSE "no") # ========================== Android details ========================== if(ANDROID) @@ -1739,6 +1745,7 @@ status(" Use OpenCV:" USE_OPENCV THEN "yes (ver ${OpenCV_VE status(" Use stb_image (built-in):" WITH_STBIMAGE THEN "yes (ver ${STBIMAGE_VERSION})" ELSE "no") status(" Use TinyEXR (built-in):" WITH_TINYEXR THEN "yes (ver ${TINYEXR_VERSION})" ELSE "no") status(" Use simdlib (built-in):" WITH_SIMDLIB THEN "yes" ELSE "no") +status(" Use npz I/O (built-in):" WITH_MINIZ THEN "yes" ELSE "no") status("") status(" Real robots: ") status(" Use Afma4:" USE_AFMA4 THEN "yes" ELSE "no") diff --git a/apps/calibration/CMakeLists.txt b/apps/calibration/CMakeLists.txt index 5b1ed25bf2..f3dce0c0b1 100644 --- a/apps/calibration/CMakeLists.txt +++ b/apps/calibration/CMakeLists.txt @@ -37,6 +37,7 @@ if(VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-function") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-parameter") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") visp_set_source_file_compile_flag(visp-acquire-franka-calib-data.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(visp-acquire-universal-robots-calib-data.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/apps/calibration/visp-acquire-franka-calib-data.cpp b/apps/calibration/visp-acquire-franka-calib-data.cpp index 2de13c8a44..3ae185fe30 100644 --- a/apps/calibration/visp-acquire-franka-calib-data.cpp +++ b/apps/calibration/visp-acquire-franka-calib-data.cpp @@ -35,6 +35,7 @@ #include #include +#include #include #include #include @@ -66,6 +67,9 @@ void usage(const char **argv, int error, const std::string &robot_ip) int main(int argc, const char **argv) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace VISP_NAMESPACE_NAME; +#endif try { std::string opt_robot_ip = "192.168.1.1"; diff --git a/apps/calibration/visp-acquire-universal-robots-calib-data.cpp b/apps/calibration/visp-acquire-universal-robots-calib-data.cpp index aea3d41630..151e8ebc9d 100644 --- a/apps/calibration/visp-acquire-universal-robots-calib-data.cpp +++ b/apps/calibration/visp-acquire-universal-robots-calib-data.cpp @@ -35,6 +35,7 @@ #include #include +#include #include #include #include @@ -66,6 +67,9 @@ void usage(const char **argv, int error, const std::string &robot_ip) int main(int argc, const char **argv) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace VISP_NAMESPACE_NAME; +#endif try { std::string opt_robot_ip = "192.168.0.100"; diff --git a/apps/calibration/visp-compute-chessboard-poses.cpp b/apps/calibration/visp-compute-chessboard-poses.cpp index b0b56b2af3..a13cd6776a 100644 --- a/apps/calibration/visp-compute-chessboard-poses.cpp +++ b/apps/calibration/visp-compute-chessboard-poses.cpp @@ -57,6 +57,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void calcChessboardCorners(int width, int height, double squareSize, std::vector &corners) @@ -224,7 +228,7 @@ int main(int argc, const char **argv) #elif defined(VISP_HAVE_GTK) display = new vpDisplayGTK(I); #endif - } + } #endif std::vector corners_pts; @@ -335,7 +339,7 @@ int main(int argc, const char **argv) } } #endif - } +} catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } diff --git a/apps/calibration/visp-compute-hand-eye-calibration.cpp b/apps/calibration/visp-compute-hand-eye-calibration.cpp index 9e89402dab..9e8d480a0f 100644 --- a/apps/calibration/visp-compute-hand-eye-calibration.cpp +++ b/apps/calibration/visp-compute-hand-eye-calibration.cpp @@ -34,6 +34,7 @@ //! \example visp-compute-hand-eye-calibration.cpp #include +#include #include #include @@ -74,6 +75,10 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace VISP_NAMESPACE_NAME; +#endif + std::string opt_data_path = "./"; std::string opt_fPe_files = "pose_fPe_%d.yaml"; std::string opt_cPo_files = "pose_cPo_%d.yaml"; diff --git a/cmake/FindVirtuose.cmake b/cmake/FindVirtuose.cmake index 9f611f5d1b..67055c90cc 100644 --- a/cmake/FindVirtuose.cmake +++ b/cmake/FindVirtuose.cmake @@ -82,7 +82,7 @@ elseif(MSVC) set(VIRTUOSE_MSVC_RUNTIME VC2017) elseif(MSVC_VERSION MATCHES "^192[0-9]$") set(VIRTUOSE_MSVC_RUNTIME VC2019) - elseif(MSVC_VERSION MATCHES "^193[0-9]$") + elseif(MSVC_VERSION MATCHES "^19[34][0-9]$") set(VIRTUOSE_MSVC_RUNTIME VC2022) endif() diff --git a/cmake/VISPDetectPlatform.cmake b/cmake/VISPDetectPlatform.cmake index e4f7466bdb..a7cddc7c9b 100644 --- a/cmake/VISPDetectPlatform.cmake +++ b/cmake/VISPDetectPlatform.cmake @@ -153,7 +153,7 @@ elseif(MSVC) set(VISP_RUNTIME vc15) elseif(MSVC_VERSION MATCHES "^192[0-9]$") set(VISP_RUNTIME vc16) - elseif(MSVC_VERSION MATCHES "^193[0-9]$") + elseif(MSVC_VERSION MATCHES "^19[34][0-9]$") set(VISP_RUNTIME vc17) else() message(WARNING "ViSP does not recognize MSVC_VERSION \"${MSVC_VERSION}\". Cannot set VISP_RUNTIME") diff --git a/cmake/templates/VISPConfig.cmake.in b/cmake/templates/VISPConfig.cmake.in index b51ca8afa2..e84df6cabf 100644 --- a/cmake/templates/VISPConfig.cmake.in +++ b/cmake/templates/VISPConfig.cmake.in @@ -189,6 +189,7 @@ set(VISP_BIN_INSTALL_PATH "@VISP_BIN_INSTALL_PATH@") #---------------------------------------------------------------------- # Remember VISP third party libs configuration #---------------------------------------------------------------------- +set(ENABLE_VISP_NAMESPACE "@ENABLE_VISP_NAMESPACE@") set(VISP_HAVE_AFMA4 "@VISP_HAVE_AFMA4@") set(VISP_HAVE_AFMA6 "@VISP_HAVE_AFMA6@") set(VISP_HAVE_APRILTAG "@VISP_HAVE_APRILTAG@") @@ -228,6 +229,7 @@ set(VISP_HAVE_LIBFREENECT_AND_DEPENDENCIES "@VISP_HAVE_LIBFREENECT_AND_DEPENDENC set(VISP_HAVE_LIBFREENECT_OLD "@VISP_HAVE_LIBFREENECT_OLD@") set(VISP_HAVE_LIBUSB_1 "@VISP_HAVE_LIBUSB_1@") set(VISP_HAVE_MAVSDK "@VISP_HAVE_MAVSDK@") +set(VISP_HAVE_MINIZ "@VISP_HAVE_MINIZ@") set(VISP_HAVE_MKL "@VISP_HAVE_MKL@") set(VISP_HAVE_NETLIB "@VISP_HAVE_NETLIB@") set(VISP_HAVE_NULLPTR "@VISP_HAVE_NULLPTR@") diff --git a/cmake/templates/VISPConfig.root-WIN32.cmake.in b/cmake/templates/VISPConfig.root-WIN32.cmake.in index b9ec2a42ea..7c4eb6b671 100644 --- a/cmake/templates/VISPConfig.root-WIN32.cmake.in +++ b/cmake/templates/VISPConfig.root-WIN32.cmake.in @@ -154,7 +154,7 @@ elseif(MSVC) set(VISP_RUNTIME vc14) # selecting previous compatible runtime version endif() endif() - elseif(MSVC_VERSION MATCHES "^193[0-9]$") + elseif(MSVC_VERSION MATCHES "^19[34][0-9]$") set(VISP_RUNTIME vc17) check_one_config(has_VS2022) if(NOT has_VS2022) diff --git a/cmake/templates/vpConfig.h.in b/cmake/templates/vpConfig.h.in index 2b0cae7cbe..7e50a6141e 100644 --- a/cmake/templates/vpConfig.h.in +++ b/cmake/templates/vpConfig.h.in @@ -112,6 +112,24 @@ VISP_VERSION_MINOR, \ VISP_VERSION_PATCH) +// Defined if the user wants to protect the classes in a dedicated visp namespace +#cmakedefine ENABLE_VISP_NAMESPACE +#define VISP_NAMESPACE_NAME visp +#ifdef ENABLE_VISP_NAMESPACE +#define VISP_NAMESPACE_ADDRESSING visp:: +#define BEGIN_VISP_NAMESPACE namespace visp { +#define END_VISP_NAMESPACE } +// Create an empty namespace to ensure that "using VISP_NAMESPACE_NAME;" does not raise an error +namespace VISP_NAMESPACE_NAME {} + +// Create an alias for compatibility with older versions of ViSP +namespace vp = VISP_NAMESPACE_NAME; +#else +#define VISP_NAMESPACE_ADDRESSING +#define BEGIN_VISP_NAMESPACE +#define END_VISP_NAMESPACE +#endif + // Enable debug and trace printings #cmakedefine VP_TRACE #cmakedefine VP_DEBUG @@ -143,6 +161,9 @@ // Always define pugixml for compatibility. #cmakedefine VISP_HAVE_PUGIXML +// Defined if basisu_miniz is used internally +#cmakedefine VISP_HAVE_MINIZ + // Defined if XML2 library available. #cmakedefine VISP_HAVE_XML2 diff --git a/demo/wireframe-simulator/servoSimu4Points.cpp b/demo/wireframe-simulator/servoSimu4Points.cpp index e7b1745ee1..2df71e1d98 100644 --- a/demo/wireframe-simulator/servoSimu4Points.cpp +++ b/demo/wireframe-simulator/servoSimu4Points.cpp @@ -66,6 +66,10 @@ #if defined(VISP_HAVE_DISPLAY) && (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) +#if defined(ENABLE_VISP_NAMESPACE) +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/demo/wireframe-simulator/servoSimuCylinder.cpp b/demo/wireframe-simulator/servoSimuCylinder.cpp index 870777a0ed..58c2880d9c 100644 --- a/demo/wireframe-simulator/servoSimuCylinder.cpp +++ b/demo/wireframe-simulator/servoSimuCylinder.cpp @@ -66,6 +66,10 @@ #if defined(VISP_HAVE_DISPLAY) && (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) +#if defined(ENABLE_VISP_NAMESPACE) +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/demo/wireframe-simulator/servoSimuSphere.cpp b/demo/wireframe-simulator/servoSimuSphere.cpp index 0cd28e7d8d..67c29bcc0c 100644 --- a/demo/wireframe-simulator/servoSimuSphere.cpp +++ b/demo/wireframe-simulator/servoSimuSphere.cpp @@ -44,6 +44,7 @@ #include #include +#include #include #include #include @@ -69,6 +70,10 @@ #if defined(VISP_HAVE_DISPLAY) && (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) +#if defined(ENABLE_VISP_NAMESPACE) +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/doc/config-doxygen.in b/doc/config-doxygen.in index b7e001c481..23d5cbff80 100644 --- a/doc/config-doxygen.in +++ b/doc/config-doxygen.in @@ -2390,6 +2390,7 @@ PREDEFINED = @DOXYGEN_SHOULD_SKIP_THIS@ \ VISP_HAVE_LIBFREENECT_AND_DEPENDENCIES \ VISP_HAVE_LIBUSB_1 \ VISP_HAVE_MAVSDK \ + VISP_HAVE_MINIZ \ VISP_HAVE_NLOHMANN_JSON \ VISP_HAVE_NULLPTR \ VISP_HAVE_OCCIPITAL_STRUCTURE \ diff --git a/example/CMakeLists.txt b/example/CMakeLists.txt index 80b6f569d9..6477806fe5 100644 --- a/example/CMakeLists.txt +++ b/example/CMakeLists.txt @@ -98,6 +98,6 @@ visp_add_subdirectory(servo-universal-robots REQUIRED_DEPS visp_core visp_robo visp_add_subdirectory(servo-viper650 REQUIRED_DEPS visp_core visp_blob visp_vs visp_robot visp_sensor visp_vision visp_gui) visp_add_subdirectory(servo-viper850 REQUIRED_DEPS visp_core visp_blob visp_vs visp_robot visp_sensor visp_vision visp_gui) visp_add_subdirectory(tools REQUIRED_DEPS visp_core visp_robot visp_io visp_gui) -visp_add_subdirectory(tracking REQUIRED_DEPS visp_core visp_io visp_gui) +visp_add_subdirectory(tracking REQUIRED_DEPS visp_core visp_core visp_blob visp_io visp_gui visp_mbt visp_me visp_tt visp_tt_mi) visp_add_subdirectory(video REQUIRED_DEPS visp_core visp_io visp_gui) visp_add_subdirectory(wireframe-simulator REQUIRED_DEPS visp_core visp_robot visp_io visp_gui) diff --git a/example/calibration/calibrate-camera.cpp b/example/calibration/calibrate-camera.cpp index 560f65a4f1..dc6059fa6f 100644 --- a/example/calibration/calibrate-camera.cpp +++ b/example/calibration/calibrate-camera.cpp @@ -101,6 +101,10 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace VISP_NAMESPACE_NAME; +#endif + try { if (argc == 1) { usage(argv, 0); @@ -679,5 +683,5 @@ int main() std::cout << "pugixml built-in 3rdparty is requested to run the calibration." << std::endl; #endif return EXIT_SUCCESS; -} + } #endif diff --git a/example/calibration/calibrate-hand-eye.cpp b/example/calibration/calibrate-hand-eye.cpp index 86dc0ec52b..eca9831650 100644 --- a/example/calibration/calibrate-hand-eye.cpp +++ b/example/calibration/calibrate-hand-eye.cpp @@ -45,6 +45,7 @@ #include #include +#include #include #include #include @@ -54,6 +55,9 @@ int main() { #if (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) +#if defined(ENABLE_VISP_NAMESPACE) + using namespace VISP_NAMESPACE_NAME; +#endif try { // We want to calibrate the hand-eye extrinsic camera parameters from 6 // couple of poses: cMo and wMe @@ -167,4 +171,4 @@ int main() std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/calibration/calibration-helper.hpp b/example/calibration/calibration-helper.hpp index daf4a41d92..4c09ce25ad 100644 --- a/example/calibration/calibration-helper.hpp +++ b/example/calibration/calibration-helper.hpp @@ -67,14 +67,14 @@ class Settings bool read(const std::string &filename) // Read the parameters { // reading configuration file - if (!vpIoTools::loadConfigFile(filename)) + if (!VISP_NAMESPACE_ADDRESSING vpIoTools::loadConfigFile(filename)) return false; - vpIoTools::readConfigVar("BoardSize_Width:", boardSize.width); - vpIoTools::readConfigVar("BoardSize_Height:", boardSize.height); - vpIoTools::readConfigVar("Square_Size:", squareSize); - vpIoTools::readConfigVar("Calibrate_Pattern:", patternToUse); - vpIoTools::readConfigVar("Input:", input); - vpIoTools::readConfigVar("Tempo:", tempo); + VISP_NAMESPACE_ADDRESSING vpIoTools::readConfigVar("BoardSize_Width:", boardSize.width); + VISP_NAMESPACE_ADDRESSING vpIoTools::readConfigVar("BoardSize_Height:", boardSize.height); + VISP_NAMESPACE_ADDRESSING vpIoTools::readConfigVar("Square_Size:", squareSize); + VISP_NAMESPACE_ADDRESSING vpIoTools::readConfigVar("Calibrate_Pattern:", patternToUse); + VISP_NAMESPACE_ADDRESSING vpIoTools::readConfigVar("Input:", input); + VISP_NAMESPACE_ADDRESSING vpIoTools::readConfigVar("Tempo:", tempo); std::cout << "grid width : " << boardSize.width << std::endl; std::cout << "grid height: " << boardSize.height << std::endl; @@ -128,20 +128,20 @@ class Settings std::string patternToUse; }; -struct CalibInfo { - CalibInfo(const vpImage &img, const std::vector &points, - const std::vector &imPts, const std::string &frame_name) +struct CalibInfo +{ + CalibInfo(const VISP_NAMESPACE_ADDRESSING vpImage &img, const std::vector &points, + const std::vector &imPts, const std::string &frame_name) : m_img(img), m_points(points), m_imPts(imPts), m_frame_name(frame_name) - { - } + { } - vpImage m_img; - std::vector m_points; - std::vector m_imPts; + VISP_NAMESPACE_ADDRESSING vpImage m_img; + std::vector m_points; + std::vector m_imPts; std::string m_frame_name; }; -void drawCalibrationOccupancy(vpImage &I, const std::vector &calib_info, +void drawCalibrationOccupancy(VISP_NAMESPACE_ADDRESSING vpImage &I, const std::vector &calib_info, unsigned int patternW) { I = 0; @@ -149,16 +149,16 @@ void drawCalibrationOccupancy(vpImage &I, const std::vector corners; + std::vector corners; corners.push_back(calib.m_imPts.front()); corners.push_back(*(calib.m_imPts.begin() + patternW - 1)); corners.push_back(calib.m_imPts.back()); corners.push_back(*(calib.m_imPts.end() - patternW)); - vpPolygon poly(corners); + VISP_NAMESPACE_ADDRESSING vpPolygon poly(corners); for (unsigned int i = 0; i < I.getHeight(); i++) { for (unsigned int j = 0; j < I.getWidth(); j++) { - if (poly.isInside(vpImagePoint(i, j))) { + if (poly.isInside(VISP_NAMESPACE_ADDRESSING vpImagePoint(i, j))) { I[i][j] += pixel_value; } } @@ -166,17 +166,17 @@ void drawCalibrationOccupancy(vpImage &I, const std::vector undistort(const vpCameraParameters &cam_dist, const std::vector &imPts) +std::vector undistort(const VISP_NAMESPACE_ADDRESSING vpCameraParameters &cam_dist, const std::vector &imPts) { - std::vector imPts_undist; + std::vector imPts_undist; - vpCameraParameters cam(cam_dist.get_px(), cam_dist.get_py(), cam_dist.get_u0(), cam_dist.get_v0()); + VISP_NAMESPACE_ADDRESSING vpCameraParameters cam(cam_dist.get_px(), cam_dist.get_py(), cam_dist.get_u0(), cam_dist.get_v0()); for (size_t i = 0; i < imPts.size(); i++) { double x = 0, y = 0; - vpPixelMeterConversion::convertPoint(cam_dist, imPts[i], x, y); + VISP_NAMESPACE_ADDRESSING vpPixelMeterConversion::convertPoint(cam_dist, imPts[i], x, y); - vpImagePoint imPt; - vpMeterPixelConversion::convertPoint(cam, x, y, imPt); + VISP_NAMESPACE_ADDRESSING vpImagePoint imPt; + VISP_NAMESPACE_ADDRESSING vpMeterPixelConversion::convertPoint(cam, x, y, imPt); imPts_undist.push_back(imPt); } @@ -190,11 +190,11 @@ bool extractCalibrationPoints(const Settings &s, const cv::Mat &cvI, std::vector { case Settings::CHESSBOARD: found = - findChessboardCorners(cvI, s.boardSize, pointBuf, + findChessboardCorners(cvI, s.boardSize, pointBuf, #if (VISP_HAVE_OPENCV_VERSION >= 0x030000) - cv::CALIB_CB_ADAPTIVE_THRESH | cv::CALIB_CB_FAST_CHECK | cv::CALIB_CB_NORMALIZE_IMAGE); + cv::CALIB_CB_ADAPTIVE_THRESH | cv::CALIB_CB_FAST_CHECK | cv::CALIB_CB_NORMALIZE_IMAGE); #else - CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_FAST_CHECK | CV_CALIB_CB_NORMALIZE_IMAGE); + CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_FAST_CHECK | CV_CALIB_CB_NORMALIZE_IMAGE); #endif break; case Settings::CIRCLES_GRID: @@ -207,7 +207,7 @@ bool extractCalibrationPoints(const Settings &s, const cv::Mat &cvI, std::vector if (found) // If done with success, { - std::vector data; + std::vector data; if (s.calibrationPattern == Settings::CHESSBOARD) { // improve the found corners' coordinate accuracy for chessboard @@ -215,7 +215,7 @@ bool extractCalibrationPoints(const Settings &s, const cv::Mat &cvI, std::vector #if (VISP_HAVE_OPENCV_VERSION >= 0x030000) cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::COUNT, 30, 0.1)); #else - cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1)); + cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1)); #endif } } diff --git a/example/coin-simulator/simulateCircle2DCamVelocity.cpp b/example/coin-simulator/simulateCircle2DCamVelocity.cpp index 093fdb7af2..17b843c02e 100644 --- a/example/coin-simulator/simulateCircle2DCamVelocity.cpp +++ b/example/coin-simulator/simulateCircle2DCamVelocity.cpp @@ -66,6 +66,10 @@ #define GETOPTARGS "cdi:h" #define SAVE 0 +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp b/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp index 683ae4c92d..d1f3111b9e 100644 --- a/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp +++ b/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp @@ -66,6 +66,10 @@ #define GETOPTARGS "di:h" #define SAVE 0 +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/coin-simulator/simulateFourPoints2DPolarCamVelocity.cpp b/example/coin-simulator/simulateFourPoints2DPolarCamVelocity.cpp index e6b98431cc..633d4b29b0 100644 --- a/example/coin-simulator/simulateFourPoints2DPolarCamVelocity.cpp +++ b/example/coin-simulator/simulateFourPoints2DPolarCamVelocity.cpp @@ -64,6 +64,10 @@ #define GETOPTARGS "di:h" #define SAVE 0 +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/device/display/displayD3D.cpp b/example/device/display/displayD3D.cpp index 6d892470a2..a931f20aed 100644 --- a/example/device/display/displayD3D.cpp +++ b/example/device/display/displayD3D.cpp @@ -66,6 +66,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/device/display/displayGDI.cpp b/example/device/display/displayGDI.cpp index 92728dec92..68139cfc17 100644 --- a/example/device/display/displayGDI.cpp +++ b/example/device/display/displayGDI.cpp @@ -67,6 +67,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/device/display/displayGTK.cpp b/example/device/display/displayGTK.cpp index 5ed0623fe8..8d9ffd1719 100644 --- a/example/device/display/displayGTK.cpp +++ b/example/device/display/displayGTK.cpp @@ -70,6 +70,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/device/display/displayOpenCV.cpp b/example/device/display/displayOpenCV.cpp index 9a3a9aa54a..ec965e745c 100644 --- a/example/device/display/displayOpenCV.cpp +++ b/example/device/display/displayOpenCV.cpp @@ -68,6 +68,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:o:p:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -459,5 +463,5 @@ int main() std::cout << "Tip:" << std::endl; std::cout << "- Install OpenCV, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/device/display/displaySequence.cpp b/example/device/display/displaySequence.cpp index b8647b5b0d..01abe9a6df 100644 --- a/example/device/display/displaySequence.cpp +++ b/example/device/display/displaySequence.cpp @@ -72,6 +72,10 @@ // List of allowed command line options #define GETOPTARGS "di:p:hf:l:s:w" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -402,5 +406,5 @@ int main() std::cout << "Tip if you are on a windows-like system:" << std::endl; std::cout << "- Install GDI, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/device/display/displayX.cpp b/example/device/display/displayX.cpp index 47a52eae04..339e1c239d 100644 --- a/example/device/display/displayX.cpp +++ b/example/device/display/displayX.cpp @@ -66,6 +66,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:o:p:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -447,5 +451,5 @@ int main() 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; return EXIT_SUCCESS; -} + } #endif diff --git a/example/device/display/displayXMulti.cpp b/example/device/display/displayXMulti.cpp index 4666e71377..876200fe11 100644 --- a/example/device/display/displayXMulti.cpp +++ b/example/device/display/displayXMulti.cpp @@ -69,6 +69,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -411,5 +415,5 @@ int main() 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; return EXIT_SUCCESS; -} + } #endif diff --git a/example/device/framegrabber/CMakeLists.txt b/example/device/framegrabber/CMakeLists.txt index 535c4e9d80..3d85fbe193 100644 --- a/example/device/framegrabber/CMakeLists.txt +++ b/example/device/framegrabber/CMakeLists.txt @@ -80,6 +80,7 @@ if(VISP_HAVE_REALSENSE OR VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-function") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-parameter") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") visp_set_source_file_compile_flag(getRealSense2Info.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(grabRealSense2.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/example/device/framegrabber/getRealSense2Info.cpp b/example/device/framegrabber/getRealSense2Info.cpp index bd8c2f5dd2..a816f5ea2f 100644 --- a/example/device/framegrabber/getRealSense2Info.cpp +++ b/example/device/framegrabber/getRealSense2Info.cpp @@ -40,12 +40,16 @@ */ #include +#include #include #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { vpRealSense2 rs; rs.open(); diff --git a/example/device/framegrabber/grab1394CMU.cpp b/example/device/framegrabber/grab1394CMU.cpp index dd48c36ea9..f5276129d6 100644 --- a/example/device/framegrabber/grab1394CMU.cpp +++ b/example/device/framegrabber/grab1394CMU.cpp @@ -57,6 +57,11 @@ // List of allowed command line options #define GETOPTARGS "dhn:o:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + + void usage(const char *name, const char *badparam, unsigned &nframes, std::string &opath); bool getOptions(int argc, const char **argv, bool &display, unsigned int &nframes, bool &save, std::string &opath); diff --git a/example/device/framegrabber/grab1394Two.cpp b/example/device/framegrabber/grab1394Two.cpp index 77018c3c1e..aeb3bafd0b 100644 --- a/example/device/framegrabber/grab1394Two.cpp +++ b/example/device/framegrabber/grab1394Two.cpp @@ -70,6 +70,10 @@ #define GETOPTARGS "b:c:df:g:hH:L:mn:io:p:rsT:v:W:" #define DUAL_ACQ +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -685,6 +689,6 @@ int main() std::cout << "Tip if you are on a unix-like system:" << std::endl; std::cout << "- Install libdc1394-2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/device/framegrabber/grabDirectShow.cpp b/example/device/framegrabber/grabDirectShow.cpp index 3e53fc53c7..6f57613dd6 100644 --- a/example/device/framegrabber/grabDirectShow.cpp +++ b/example/device/framegrabber/grabDirectShow.cpp @@ -58,6 +58,10 @@ // List of allowed command line options #define GETOPTARGS "dhn:o:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -94,7 +98,7 @@ OPTIONS: Default\n\ -h \n\ Print the help.\n\ \n", - nframes, opath.c_str()); +nframes, opath.c_str()); if (badparam) { fprintf(stderr, "ERROR: \n"); fprintf(stderr, "\nBad parameter [%s]\n", badparam); @@ -254,7 +258,8 @@ int main(int argc, const char **argv) // Release the framegrabber delete grabber; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -264,7 +269,7 @@ int main(int argc, const char **argv) int main() { std::cout << "You do not have GDI (Graphical Device Interface), or GTK functionalities to display images..." - << std::endl; + << std::endl; std::cout << "Tip if you are on a windows-like system:" << std::endl; std::cout << "- Install GDI, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; diff --git a/example/device/framegrabber/grabDirectShowMulti.cpp b/example/device/framegrabber/grabDirectShowMulti.cpp index 26c707b847..4d03b16dbd 100644 --- a/example/device/framegrabber/grabDirectShowMulti.cpp +++ b/example/device/framegrabber/grabDirectShowMulti.cpp @@ -64,6 +64,10 @@ #define GRAB_COLOR +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -136,7 +140,7 @@ OPTIONS Default\n\ -h \n\ Print the help.\n\ \n", - camera, nframes, opath.c_str()); +camera, nframes, opath.c_str()); exit(0); } @@ -297,7 +301,8 @@ int main(int argc, const char **argv) g[i].open(); } - } else { + } + else { ncameras = 1; // acquisition from only one camera delete[] g; g = new vpDirectShowGrabber[1]; @@ -355,19 +360,19 @@ int main(int argc, const char **argv) unsigned int width, height; g[i].getFormat(width, height, framerate); std::cout << "----------------------------------------------------------" << std::endl - << "---- MediaType and framerate currently used by device " << std::endl - << "---- (or camera) " << c << std::endl - << "---- Current MediaType : " << g[i].getMediaType() << std::endl - << "---- Current format : " << width << " x " << height << " at " << framerate << " fps" - << std::endl - << "----------------------------------------------------------" << std::endl; + << "---- MediaType and framerate currently used by device " << std::endl + << "---- (or camera) " << c << std::endl + << "---- Current MediaType : " << g[i].getMediaType() << std::endl + << "---- Current format : " << width << " x " << height << " at " << framerate << " fps" + << std::endl + << "----------------------------------------------------------" << std::endl; } if (verbose_settings) { std::cout << "----------------------------------------------------------" << std::endl - << "---- MediaTypes supported by device (or camera) " << c << std::endl - << "---- One of the MediaType below can be set using " << std::endl - << "---- option -t ." << std::endl - << "----------------------------------------------------------" << std::endl; + << "---- MediaTypes supported by device (or camera) " << c << std::endl + << "---- One of the MediaType below can be set using " << std::endl + << "---- option -t ." << std::endl + << "----------------------------------------------------------" << std::endl; g[i].getStreamCapabilities(); } } @@ -390,7 +395,7 @@ int main(int argc, const char **argv) c = camera; std::cout << "Image size for camera " << c << " : width: " << I[i].getWidth() << " height: " << I[i].getHeight() - << std::endl; + << std::endl; if (display) { // Initialise the display @@ -444,7 +449,8 @@ int main(int argc, const char **argv) delete[] d; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -453,7 +459,7 @@ int main(int argc, const char **argv) int main() { std::cout << "You do not have GDI (Graphical Device Interface), or GTK functionalities to display images..." - << std::endl; + << std::endl; std::cout << "Tip if you are on a windows-like system:" << std::endl; std::cout << "- Install GDI, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; diff --git a/example/device/framegrabber/grabDisk.cpp b/example/device/framegrabber/grabDisk.cpp index c3c3424fef..a095af2c46 100644 --- a/example/device/framegrabber/grabDisk.cpp +++ b/example/device/framegrabber/grabDisk.cpp @@ -33,6 +33,16 @@ * *****************************************************************************/ +/*! + \file grabDisk.cpp + + \brief Example of image sequence reading from the disk using vpDiskGrabber + class. + + The sequence is made of separate images. Each image corresponds to a PGM + file. +*/ + #include #include #include @@ -47,19 +57,13 @@ #include #include -/*! - \file grabDisk.cpp - - \brief Example of image sequence reading from the disk using vpDiskGrabber - class. - - The sequence is made of separate images. Each image corresponds to a PGM - file. -*/ - // List of allowed command line options #define GETOPTARGS "b:de:f:hi:l:s:z:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /* Print the program options. @@ -357,5 +361,5 @@ int main() std::cout << "Tip if you are on a windows-like system:" << std::endl; std::cout << "- Install GDI, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/device/framegrabber/grabFlyCapture.cpp b/example/device/framegrabber/grabFlyCapture.cpp index ff218e7735..d4299cc2ca 100644 --- a/example/device/framegrabber/grabFlyCapture.cpp +++ b/example/device/framegrabber/grabFlyCapture.cpp @@ -57,6 +57,10 @@ #define GETOPTARGS "cdhi:n:o:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -95,7 +99,7 @@ OPTIONS: Default\n\ -h \n\ Print the help.\n\ \n", - icamera, opath.c_str()); +icamera, opath.c_str()); if (badparam) { fprintf(stderr, "ERROR: \n"); @@ -220,7 +224,8 @@ int main(int argc, const char **argv) if (opt_click && opt_display) { if (vpDisplay::getClick(I, false) == true) break; - } else { + } + else { static unsigned int cpt = 0; if (cpt++ == 10) break; @@ -232,7 +237,8 @@ int main(int argc, const char **argv) // The camera connection will be closed automatically in vpFlyCapture // destructor return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } diff --git a/example/device/framegrabber/grabRealSense2.cpp b/example/device/framegrabber/grabRealSense2.cpp index b1d7c3bebd..5b2d75be6a 100644 --- a/example/device/framegrabber/grabRealSense2.cpp +++ b/example/device/framegrabber/grabRealSense2.cpp @@ -54,6 +54,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpRealSense2 rs; diff --git a/example/device/framegrabber/grabRealSense2_T265.cpp b/example/device/framegrabber/grabRealSense2_T265.cpp index 26ac71efdf..5f3d554cd1 100644 --- a/example/device/framegrabber/grabRealSense2_T265.cpp +++ b/example/device/framegrabber/grabRealSense2_T265.cpp @@ -55,6 +55,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpHomogeneousMatrix cMw, cMw_0; vpHomogeneousMatrix cextMw(0, 0, 2, 0, 0, 0); // External camera view for pose visualization vpColVector odo_vel, odo_acc, imu_acc, imu_vel; diff --git a/example/device/framegrabber/grabV4l2.cpp b/example/device/framegrabber/grabV4l2.cpp index 9590a57a42..a3d66dea5f 100644 --- a/example/device/framegrabber/grabV4l2.cpp +++ b/example/device/framegrabber/grabV4l2.cpp @@ -34,9 +34,6 @@ * *****************************************************************************/ -#include -#include -#include /*! \file grabV4l2.cpp @@ -44,6 +41,10 @@ */ +#include +#include +#include + #ifdef VISP_HAVE_V4L2 #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) @@ -60,7 +61,12 @@ // List of allowed command line options #define GETOPTARGS "df:i:hn:o:p:s:t:v:x" -typedef enum { +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + +typedef enum +{ grey_image = 0, // for ViSP unsigned char grey images color_image // for ViSP vpRGBa color images } vpImage_type; @@ -292,8 +298,9 @@ int main(int argc, const char **argv) // Acquire an image g.acquire(Ig); std::cout << "Grey image size: width : " << Ig.getWidth() << " height: " << Ig.getHeight() << std::endl; - } else { - // Open the framegrabber with the specified settings on color images + } + else { + // Open the framegrabber with the specified settings on color images g.open(Ic); // Acquire an image g.acquire(Ic); @@ -318,7 +325,8 @@ int main(int argc, const char **argv) display.init(Ig, 100, 100, "V4L2 grey images framegrabbing"); vpDisplay::display(Ig); vpDisplay::flush(Ig); - } else { + } + else { display.init(Ic, 100, 100, "V4L2 color images framegrabbing"); vpDisplay::display(Ic); vpDisplay::flush(Ic); @@ -338,7 +346,8 @@ int main(int argc, const char **argv) // Flush the display vpDisplay::flush(Ig); } - } else { + } + else { g.acquire(Ic); if (opt_display) { // Display the image @@ -355,7 +364,8 @@ int main(int argc, const char **argv) std::cout << "Write: " << filename << std::endl; if (opt_image_type == grey_image) { vpImageIo::write(Ig, filename); - } else { + } + else { vpImageIo::write(Ic, filename); } } @@ -366,7 +376,8 @@ int main(int argc, const char **argv) g.close(); 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/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp index 2f4333cc31..b342de21bc 100644 --- a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp +++ b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp @@ -66,6 +66,10 @@ #define GETOPTARGS "d:oh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { diff --git a/example/device/framegrabber/readRealSenseData.cpp b/example/device/framegrabber/readRealSenseData.cpp index 079cb7270d..a248e6bc13 100644 --- a/example/device/framegrabber/readRealSenseData.cpp +++ b/example/device/framegrabber/readRealSenseData.cpp @@ -68,7 +68,15 @@ #endif #endif +#ifdef VISP_HAVE_MINIZ #define GETOPTARGS "ci:e:jbzodh" +#else +#define GETOPTARGS "ci:e:jbodh" +#endif + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif namespace { @@ -86,7 +94,9 @@ void usage(const char *name, const char *badparam) << " [-c]" << " [-j]" << " [-b]" +#ifdef VISP_HAVE_MINIZ << " [-z]" +#endif << " [-o]" << " [-d]" << " [--help,-h]" @@ -107,9 +117,11 @@ void usage(const char *name, const char *badparam) << " -b" << std::endl << " Depth and Pointcloud streams are saved in binary format." << std::endl << std::endl +#ifdef VISP_HAVE_MINIZ << " -z" << std::endl << " Pointcloud stream is saved in NPZ format." << std::endl << std::endl +#endif << " -o" << std::endl << " Save color images in PNG format (lossless) in a new folder." << std::endl << std::endl @@ -149,9 +161,11 @@ bool getOptions(int argc, const char *argv[], std::string &input_directory, std: case 'b': force_binary_format = true; break; +#ifdef VISP_HAVE_MINIZ case 'z': read_npz = true; break; +#endif case 'o': save_video = true; break; @@ -238,6 +252,7 @@ bool readData(int cpt, const std::string &input_directory, const std::string &pa } } } +#ifdef VISP_HAVE_MINIZ else { visp::cnpy::npz_t npz_data = visp::cnpy::npz_load(filename_depth); @@ -255,6 +270,11 @@ bool readData(int cpt, const std::string &input_directory, const std::string &pa const bool copyData = true; I_depth_raw = vpImage(depth_data_ptr, height, width, copyData); } +#else + else { + throw(vpIoException(vpIoException::ioError, "Cannot open non-binary depth file when npz I/O functions are disabled.")); + } +#endif } // Read pointcloud @@ -291,6 +311,7 @@ bool readData(int cpt, const std::string &input_directory, const std::string &pa } } } +#ifdef VISP_HAVE_MINIZ else if (read_npz) { visp::cnpy::npz_t npz_data = visp::cnpy::npz_load(filename_pointcloud); @@ -320,6 +341,7 @@ bool readData(int cpt, const std::string &input_directory, const std::string &pa } } } +#endif else { #if defined(VISP_HAVE_PCL_IO) if (pcl::io::loadPCDFile(filename_pointcloud, *point_cloud) == -1) { diff --git a/example/device/framegrabber/saveRealSenseData.cpp b/example/device/framegrabber/saveRealSenseData.cpp index 580cfdbd3b..6bc764d7e7 100644 --- a/example/device/framegrabber/saveRealSenseData.cpp +++ b/example/device/framegrabber/saveRealSenseData.cpp @@ -60,6 +60,7 @@ #endif #include +#include #include #include #include @@ -74,7 +75,15 @@ #define USE_REALSENSE2 #endif +#ifdef VISP_HAVE_MINIZ #define GETOPTARGS "se:o:acdpzijCf:bvh" +#else +#define GETOPTARGS "se:o:acdpijCf:bvh" +#endif + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif namespace { @@ -89,7 +98,9 @@ void usage(const char *name, const char *badparam, int fps) << " [-d]" << " [-p]" << " [-b]" +#ifdef VISP_HAVE_MINIZ << " [-z]" +#endif << " [-i]" << " [-j]" << " [-C]" @@ -123,9 +134,11 @@ void usage(const char *name, const char *badparam, int fps) << " -b" << std::endl << " Force depth and pointcloud to be saved in (little-endian) binary format." << std::endl << std::endl +#ifdef VISP_HAVE_MINIZ << " -z" << std::endl << " Pointcloud is saved in NPZ format." << std::endl << std::endl +#endif << " -i" << std::endl << " Add infrared stream to saved data when -s option is enabled." << std::endl << std::endl @@ -208,9 +221,11 @@ bool getOptions(int argc, const char *argv[], bool &save, std::string &pattern, case 'v': depth_hist_visu = true; break; +#ifdef VISP_HAVE_MINIZ case 'z': save_pcl_npz_format = true; break; +#endif case 'b': save_force_binary_format = true; break; @@ -465,6 +480,7 @@ class vpStorageWorker } } } +#ifdef VISP_HAVE_MINIZ else { ss << m_directory << "/depth_image_" << m_save_pattern << ".npz"; snprintf(buffer, FILENAME_MAX, ss.str().c_str(), m_cpt); @@ -492,6 +508,11 @@ class vpStorageWorker std::vector I_depth_raw_vec(ptr_depthImg->bitmap, ptr_depthImg->bitmap + ptr_depthImg->getSize()); visp::cnpy::npz_save(filename_depth, "data", I_depth_raw_vec.data(), { height, width }, "a"); } +#else + else { + throw(vpIoException(vpIoException::ioError, "Cannot manage non-binary files when npz I/O functions are disabled.")); + } +#endif } if (m_save_pointcloud && ptr_pointCloud) { @@ -553,7 +574,8 @@ class vpStorageWorker } } else if (m_save_pcl_npz_format) { - // Write Npz headers +#ifdef VISP_HAVE_MINIZ +// Write Npz headers std::vector vec_filename(filename_point_cloud.begin(), filename_point_cloud.end()); // Null-terminated character is handled at reading // For null-terminated character handling, see: @@ -592,6 +614,9 @@ class vpStorageWorker #endif // Write data visp::cnpy::npz_save(filename_point_cloud, "data", vec_pcl.data(), { height, width, channels }, "a"); +#else + throw(vpIoException(vpIoException::fatalError, "Cannot save in npz format when npz I/O functions are disabled.")); +#endif } else { #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_IO) && defined(VISP_HAVE_PCL_COMMON) @@ -680,7 +705,9 @@ int main(int argc, const char *argv[]) std::cout << "save_jpeg: " << save_jpeg << std::endl; std::cout << "stream_fps: " << stream_fps << std::endl; std::cout << "depth_hist_visu: " << depth_hist_visu << std::endl; +#ifdef VISP_HAVE_MINIZ std::cout << "save_pcl_npz_format: " << save_pcl_npz_format << std::endl; +#endif std::cout << "save_force_binary_format: " << save_force_binary_format << std::endl; std::cout << "click_to_save: " << click_to_save << std::endl; @@ -908,10 +935,10 @@ int main(int argc, const char *argv[]) #else if (save_pointcloud) { ptr_pointCloud = std::make_unique>(pointCloud); - } + } save_queue.push(ptr_colorImg, ptr_depthImg, ptr_pointCloud, ptr_infraredImg); #endif - } + } double delta_time = vpTime::measureTimeMs() - start; vec_delta_time.push_back(delta_time); @@ -955,10 +982,10 @@ int main(int argc, const char *argv[]) #else if (save_pointcloud) { ptr_pointCloud = std::make_unique>(pointCloud); - } + } save_queue.push(ptr_colorImg, ptr_depthImg, ptr_pointCloud, ptr_infraredImg); #endif - } + } break; case vpMouseButton::button2: @@ -968,9 +995,9 @@ int main(int argc, const char *argv[]) quit = true; save_queue.cancel(); break; - } } } +} } double mean_vec_delta_time = vpMath::getMean(vec_delta_time); diff --git a/example/device/kinect/kinectAcquisition.cpp b/example/device/kinect/kinectAcquisition.cpp index adbfa8ecb1..547cb8df29 100644 --- a/example/device/kinect/kinectAcquisition.cpp +++ b/example/device/kinect/kinectAcquisition.cpp @@ -57,6 +57,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { // Init Kinect #ifdef VISP_HAVE_LIBFREENECT_OLD diff --git a/example/device/laserscanner/SickLDMRS-Acq.cpp b/example/device/laserscanner/SickLDMRS-Acq.cpp index 15c204441e..4fb008d411 100644 --- a/example/device/laserscanner/SickLDMRS-Acq.cpp +++ b/example/device/laserscanner/SickLDMRS-Acq.cpp @@ -43,6 +43,7 @@ platforms since the Sick LD-MRS driver was not ported to Windows. */ +#include #include #include #include @@ -51,6 +52,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpSickLDMRS laser; std::string ip = "131.254.12.119"; @@ -83,5 +88,5 @@ int main() << "since the Sick LD-MRS driver was not ported to Windows." << std::endl; return EXIT_SUCCESS; -} + } #endif // #ifdef UNIX diff --git a/example/device/laserscanner/SickLDMRS-Process.cpp b/example/device/laserscanner/SickLDMRS-Process.cpp index 63cddab2c6..5e29a39a5f 100644 --- a/example/device/laserscanner/SickLDMRS-Process.cpp +++ b/example/device/laserscanner/SickLDMRS-Process.cpp @@ -54,6 +54,7 @@ select the layers to proceed. */ +#include #include #include #include @@ -74,6 +75,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + static int save = 0; static int layerToDisplay = 0xF; // 0xF = 1111 => all the layers are selected static vpLaserScan shm_laserscan[4]; @@ -355,6 +360,6 @@ 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; return EXIT_SUCCESS; -} + } #endif // #ifdef UNIX diff --git a/example/device/light/ringLight.cpp b/example/device/light/ringLight.cpp index a0c908af88..068d0b2317 100644 --- a/example/device/light/ringLight.cpp +++ b/example/device/light/ringLight.cpp @@ -56,6 +56,10 @@ // List of allowed command line options #define GETOPTARGS "d:hn:ot:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/direct-visual-servoing/photometricVisualServoing.cpp b/example/direct-visual-servoing/photometricVisualServoing.cpp index 84f634f970..ff189bed98 100644 --- a/example/direct-visual-servoing/photometricVisualServoing.cpp +++ b/example/direct-visual-servoing/photometricVisualServoing.cpp @@ -36,6 +36,7 @@ Implemented from \cite Collewet08c. */ +#include #include #include #include @@ -66,6 +67,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:n:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, int niter); bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_allowed, bool &display, int &niter); @@ -435,4 +440,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp b/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp index 1b400271e3..023bf73a84 100644 --- a/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp +++ b/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp @@ -36,6 +36,7 @@ Implemented from \cite Collewet08c. */ +#include #include #include @@ -67,6 +68,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:n:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, int niter); bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_allowed, bool &display, int &niter); @@ -486,4 +491,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/homography/homographyHLM2DObject.cpp b/example/homography/homographyHLM2DObject.cpp index ef357b8043..6ef655d552 100644 --- a/example/homography/homographyHLM2DObject.cpp +++ b/example/homography/homographyHLM2DObject.cpp @@ -49,6 +49,7 @@ */ +#include #include #include #include @@ -66,6 +67,10 @@ #define L 0.1 #define nbpt 5 +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -273,4 +278,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/homography/homographyHLM3DObject.cpp b/example/homography/homographyHLM3DObject.cpp index ffafeab16a..25cb7c3e22 100644 --- a/example/homography/homographyHLM3DObject.cpp +++ b/example/homography/homographyHLM3DObject.cpp @@ -49,6 +49,7 @@ */ +#include #include #include #include @@ -67,6 +68,10 @@ #define L 0.1 #define nbpt 11 +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -245,4 +250,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/homography/homographyHartleyDLT2DObject.cpp b/example/homography/homographyHartleyDLT2DObject.cpp index cce2a041ba..9c73dd56a4 100644 --- a/example/homography/homographyHartleyDLT2DObject.cpp +++ b/example/homography/homographyHartleyDLT2DObject.cpp @@ -47,6 +47,7 @@ */ +#include #include #include #include @@ -65,6 +66,10 @@ #define L 0.1 #define nbpt 5 +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -241,4 +246,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/homography/homographyRansac2DObject.cpp b/example/homography/homographyRansac2DObject.cpp index 184f1dcf00..3232a140ff 100644 --- a/example/homography/homographyRansac2DObject.cpp +++ b/example/homography/homographyRansac2DObject.cpp @@ -49,6 +49,7 @@ */ +#include #include #include #include @@ -66,6 +67,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -237,4 +242,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/image/imageDiskRW.cpp b/example/image/imageDiskRW.cpp index a26addbfc6..05a1881f28 100644 --- a/example/image/imageDiskRW.cpp +++ b/example/image/imageDiskRW.cpp @@ -53,6 +53,7 @@ #include #include +#include #include #include #include @@ -61,6 +62,10 @@ // List of allowed command line options #define GETOPTARGS "i:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/kalman/ukf-linear-example.cpp b/example/kalman/ukf-linear-example.cpp index 7ff71e57b9..48c3bd1e99 100644 --- a/example/kalman/ukf-linear-example.cpp +++ b/example/kalman/ukf-linear-example.cpp @@ -67,6 +67,11 @@ #endif #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /** * \brief The process function, that updates the prior. * diff --git a/example/kalman/ukf-nonlinear-complex-example.cpp b/example/kalman/ukf-nonlinear-complex-example.cpp index 5fa5550bf1..81a3bc25b8 100644 --- a/example/kalman/ukf-nonlinear-complex-example.cpp +++ b/example/kalman/ukf-nonlinear-complex-example.cpp @@ -83,6 +83,11 @@ #endif #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { /** diff --git a/example/kalman/ukf-nonlinear-example.cpp b/example/kalman/ukf-nonlinear-example.cpp index eb4f88e5e1..f362f4a8e5 100644 --- a/example/kalman/ukf-nonlinear-example.cpp +++ b/example/kalman/ukf-nonlinear-example.cpp @@ -90,6 +90,11 @@ #endif #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { /** diff --git a/example/manual/geometric-features/manGeometricFeatures.cpp b/example/manual/geometric-features/manGeometricFeatures.cpp index 2e9636524e..319f6f9998 100644 --- a/example/manual/geometric-features/manGeometricFeatures.cpp +++ b/example/manual/geometric-features/manGeometricFeatures.cpp @@ -45,6 +45,7 @@ */ +#include #include #include // For 2D image @@ -71,6 +72,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { std::cout << "ViSP geometric features display example" << std::endl; unsigned int height = 288; diff --git a/example/manual/hello-world/Autotools/HelloWorld.cpp b/example/manual/hello-world/Autotools/HelloWorld.cpp index 5d9e3607b1..8b95c87829 100644 --- a/example/manual/hello-world/Autotools/HelloWorld.cpp +++ b/example/manual/hello-world/Autotools/HelloWorld.cpp @@ -1,11 +1,16 @@ #include +#include #include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::cout << "ViSP Hello World example" << std::endl; vpImage I(288, 384); diff --git a/example/manual/hello-world/CMake/HelloWorld.cpp b/example/manual/hello-world/CMake/HelloWorld.cpp index 257a76c4c2..5c09fbb119 100644 --- a/example/manual/hello-world/CMake/HelloWorld.cpp +++ b/example/manual/hello-world/CMake/HelloWorld.cpp @@ -35,12 +35,17 @@ #include #include +#include #include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpThetaUVector tu; diff --git a/example/manual/hello-world/Makefile/HelloWorld.cpp b/example/manual/hello-world/Makefile/HelloWorld.cpp index 5d9e3607b1..8b95c87829 100644 --- a/example/manual/hello-world/Makefile/HelloWorld.cpp +++ b/example/manual/hello-world/Makefile/HelloWorld.cpp @@ -1,11 +1,16 @@ #include +#include #include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::cout << "ViSP Hello World example" << std::endl; vpImage I(288, 384); diff --git a/example/manual/image-manipulation/manDisplay.cpp b/example/manual/image-manipulation/manDisplay.cpp index e9da06e56e..4463644eb1 100644 --- a/example/manual/image-manipulation/manDisplay.cpp +++ b/example/manual/image-manipulation/manDisplay.cpp @@ -41,6 +41,7 @@ */ #include +#include #include #include #include @@ -48,6 +49,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { // Create a grey level image vpImage I; diff --git a/example/manual/image-manipulation/manGrab1394.cpp b/example/manual/image-manipulation/manGrab1394.cpp index 0841d2c0a3..0b6cc89192 100644 --- a/example/manual/image-manipulation/manGrab1394.cpp +++ b/example/manual/image-manipulation/manGrab1394.cpp @@ -47,12 +47,18 @@ #include #include +#include #include #include int main() { #ifdef VISP_HAVE_DC1394 + +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { unsigned int ncameras; // Number of cameras on the bus vp1394TwoGrabber g; diff --git a/example/manual/image-manipulation/manGrabDirectShow.cpp b/example/manual/image-manipulation/manGrabDirectShow.cpp index 2a2b01c57e..7de60b9c73 100644 --- a/example/manual/image-manipulation/manGrabDirectShow.cpp +++ b/example/manual/image-manipulation/manGrabDirectShow.cpp @@ -52,6 +52,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; // Grey level image diff --git a/example/manual/image-manipulation/manGrabDisk.cpp b/example/manual/image-manipulation/manGrabDisk.cpp index 0103ff9dcb..6152c0e336 100644 --- a/example/manual/image-manipulation/manGrabDisk.cpp +++ b/example/manual/image-manipulation/manGrabDisk.cpp @@ -52,6 +52,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; // Grey level image diff --git a/example/manual/image-manipulation/manGrabV4l2.cpp b/example/manual/image-manipulation/manGrabV4l2.cpp index 05f26cbea0..32013f7167 100644 --- a/example/manual/image-manipulation/manGrabV4l2.cpp +++ b/example/manual/image-manipulation/manGrabV4l2.cpp @@ -45,11 +45,16 @@ */ +#include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; // Grey level image diff --git a/example/manual/moments/manServoMomentsSimple.cpp b/example/manual/moments/manServoMomentsSimple.cpp index 0ba5b221a9..429789a58b 100644 --- a/example/manual/moments/manServoMomentsSimple.cpp +++ b/example/manual/moments/manServoMomentsSimple.cpp @@ -39,6 +39,7 @@ robot */ +#include #include //the basic tracker #include //some console output @@ -51,9 +52,13 @@ #include #include //init the feature database using the information about moment dependencies #include //visual servoing task + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + // this function converts the plane defined by the cMo to 1/Z=Ax+By+C plane // form - void cMoToABC(vpHomogeneousMatrix &cMo, double &A, double &B, double &C); void cMoToABC(vpHomogeneousMatrix &cMo, double &A, double &B, double &C) diff --git a/example/manual/ogre/HelloWorldOgre.cpp b/example/manual/ogre/HelloWorldOgre.cpp index 96eba8cf33..36083fcf96 100644 --- a/example/manual/ogre/HelloWorldOgre.cpp +++ b/example/manual/ogre/HelloWorldOgre.cpp @@ -43,6 +43,7 @@ #include #include +#include #include #include #include @@ -54,6 +55,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { #if defined(VISP_HAVE_OGRE) #if defined(VISP_HAVE_V4L2) || defined(VISP_HAVE_DC1394) || defined(HAVE_OPENCV_VIDEOIO) @@ -80,7 +85,7 @@ int main() if (!grabber.isOpened()) { // check if we succeeded std::cout << "Failed to open the camera" << std::endl; return EXIT_FAILURE; - } + } cv::Mat frame; grabber >> frame; // get a new frame from camera vpImageConvert::convert(frame, I); @@ -154,7 +159,7 @@ int main() std::cout << "You need Ogre3D to run this example" << std::endl; #endif return EXIT_SUCCESS; - } +} catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; diff --git a/example/manual/ogre/HelloWorldOgreAdvanced.cpp b/example/manual/ogre/HelloWorldOgreAdvanced.cpp index 2ca3f16904..7aa04c37c7 100644 --- a/example/manual/ogre/HelloWorldOgreAdvanced.cpp +++ b/example/manual/ogre/HelloWorldOgreAdvanced.cpp @@ -43,6 +43,7 @@ #include #include +#include #include #include #include @@ -52,6 +53,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #if defined(VISP_HAVE_OGRE) #ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/example/manual/simulation/manServo4PointsDisplay.cpp b/example/manual/simulation/manServo4PointsDisplay.cpp index 58c5d7db00..995a155b77 100644 --- a/example/manual/simulation/manServo4PointsDisplay.cpp +++ b/example/manual/simulation/manServo4PointsDisplay.cpp @@ -69,6 +69,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { ////////////////////////////////////////// // sets the initial camera location @@ -223,5 +227,5 @@ int main() std::cout << "Tip if you are on a windows-like system:" << std::endl; std::cout << "- Install GDI, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/manual/simulation/manSimu4Dots.cpp b/example/manual/simulation/manSimu4Dots.cpp index b2547edbfb..1a755d8e2f 100644 --- a/example/manual/simulation/manSimu4Dots.cpp +++ b/example/manual/simulation/manSimu4Dots.cpp @@ -77,6 +77,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + static void *mainLoop(void *_simu) { // pointer copy of the vpSimulator instance diff --git a/example/manual/simulation/manSimu4Points.cpp b/example/manual/simulation/manSimu4Points.cpp index 99502c3c62..3a14f3d45e 100644 --- a/example/manual/simulation/manSimu4Points.cpp +++ b/example/manual/simulation/manSimu4Points.cpp @@ -64,6 +64,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + static void *mainLoop(void *_simu) { // pointer copy of the vpSimulator instance diff --git a/example/math/BSpline.cpp b/example/math/BSpline.cpp index b3507584fb..e6f9ce696a 100644 --- a/example/math/BSpline.cpp +++ b/example/math/BSpline.cpp @@ -44,6 +44,7 @@ Describe a curve thanks to a BSpline. */ +#include #include #include @@ -71,6 +72,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -284,11 +289,11 @@ int main(int argc, const char **argv) } if (N != nullptr) - delete [] N; + delete[] N; if (N2 != nullptr) { for (unsigned int j = 0; j <= 2; j++) - delete [] N2[j]; - delete [] N2; + delete[] N2[j]; + delete[] N2; } return EXIT_SUCCESS; @@ -310,5 +315,5 @@ int main() std::cout << "Tip if you are on a windows-like system:" << std::endl; std::cout << "- Install GDI, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/math/exponentialMap.cpp b/example/math/exponentialMap.cpp index 119a0b6b87..4304e25ee2 100644 --- a/example/math/exponentialMap.cpp +++ b/example/math/exponentialMap.cpp @@ -40,6 +40,7 @@ */ #include +#include #include #include #include @@ -49,6 +50,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { vpTranslationVector t; t[0] = 0.1; // t_x in m/s diff --git a/example/math/qp_plot.h b/example/math/qp_plot.h index 300acff88c..ecfe55f871 100644 --- a/example/math/qp_plot.h +++ b/example/math/qp_plot.h @@ -43,18 +43,18 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS -vpMatrix randM(int n, int m) +VISP_NAMESPACE_ADDRESSING vpMatrix randM(int n, int m) { - vpMatrix M(n, m); + VISP_NAMESPACE_ADDRESSING vpMatrix M(n, m); for (int i = 0; i < n; ++i) for (int j = 0; j < m; ++j) M[i][j] = (2. * rand()) / RAND_MAX - 1; return M; } -vpColVector randV(int n) +VISP_NAMESPACE_ADDRESSING vpColVector randV(int n) { - vpColVector M(n); + VISP_NAMESPACE_ADDRESSING vpColVector M(n); for (int i = 0; i < n; ++i) M[i] = (2. * rand()) / RAND_MAX - 1; return M; @@ -67,12 +67,12 @@ class QPlot virtual ~QPlot() { delete P; } QPlot(int graphNum, int total, std::vector legend) { - P = new vpPlot(graphNum, 700, 700, 100, 200, "Resolution time"); + P = new VISP_NAMESPACE_ADDRESSING vpPlot(graphNum, 700, 700, 100, 200, "Resolution time"); for (int i = 0; i < graphNum; ++i) { P->initGraph(i, 2); - P->setColor(i, 0, vpColor::red); - P->setColor(i, 1, vpColor::blue); + P->setColor(i, 0, VISP_NAMESPACE_ADDRESSING vpColor::red); + P->setColor(i, 1, VISP_NAMESPACE_ADDRESSING vpColor::blue); P->setGraphThickness(i, 2); P->initRange(i, 0, total, 0, 0.1); P->setUnitY(i, "ms"); @@ -82,10 +82,10 @@ class QPlot } } - void plot(int g, int c, int i, double t) { P->plot(g, c, i, vpTime::measureTimeMs() - t); } + void plot(int g, int c, int i, double t) { P->plot(g, c, i, VISP_NAMESPACE_ADDRESSING vpTime::measureTimeMs() - t); } void wait() { P->I.display->getClick(); } - vpPlot *P; + VISP_NAMESPACE_ADDRESSING vpPlot *P; private: // Copy constructor not allowed. diff --git a/example/math/quadprog.cpp b/example/math/quadprog.cpp index 6d89a741a2..617d08f31e 100644 --- a/example/math/quadprog.cpp +++ b/example/math/quadprog.cpp @@ -56,6 +56,10 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + const int n = 20; // x dim const int m = 10; // equality m < n const int p = 30; // inequality diff --git a/example/math/quadprog_eq.cpp b/example/math/quadprog_eq.cpp index 72d9ef40b1..85c3a00717 100644 --- a/example/math/quadprog_eq.cpp +++ b/example/math/quadprog_eq.cpp @@ -55,6 +55,10 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + const int n = 20; // x dim const int m = 10; // equality m < n const int p = 30; // inequality diff --git a/example/math/random.cpp b/example/math/random.cpp index 331b9c314f..13fafefc3b 100644 --- a/example/math/random.cpp +++ b/example/math/random.cpp @@ -1,8 +1,13 @@ #include +#include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpUniRand rng; for (int i = 0; i < 10; i++) { std::cout << rng.uniform(0, 6) << std::endl; // produces int values @@ -10,22 +15,19 @@ int main() } std::vector v; - for(unsigned int i = 0; i < 10; i++) - { + for (unsigned int i = 0; i < 10; i++) { v.push_back(i); } std::vector shuffled_v = vpUniRand::shuffleVector(v); std::cout << "Original vector = [\t"; - for(unsigned int i = 0; i < 10; i++) - { + for (unsigned int i = 0; i < 10; i++) { std::cout << v[i] << "\t"; } std::cout << "]" << std::endl; std::cout << "Shuffled vector = [\t"; - for(unsigned int i = 0; i < 10; i++) - { + for (unsigned int i = 0; i < 10; i++) { std::cout << shuffled_v[i] << "\t"; } std::cout << "]" << std::endl; diff --git a/example/moments/image/servoMomentImage.cpp b/example/moments/image/servoMomentImage.cpp index e1c345b0a5..250a738333 100644 --- a/example/moments/image/servoMomentImage.cpp +++ b/example/moments/image/servoMomentImage.cpp @@ -42,6 +42,7 @@ #include #include +#include #include #include #include @@ -78,6 +79,10 @@ int main() } #else +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS class servoMoment { diff --git a/example/moments/points/servoMomentPoints.cpp b/example/moments/points/servoMomentPoints.cpp index 9caf01c575..15d9d658b1 100644 --- a/example/moments/points/servoMomentPoints.cpp +++ b/example/moments/points/servoMomentPoints.cpp @@ -77,6 +77,10 @@ int main() } #else +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS class servoMoment { diff --git a/example/moments/polygon/servoMomentPolygon.cpp b/example/moments/polygon/servoMomentPolygon.cpp index 6a55afb8fd..ad2dae20a8 100644 --- a/example/moments/polygon/servoMomentPolygon.cpp +++ b/example/moments/polygon/servoMomentPolygon.cpp @@ -76,6 +76,10 @@ int main() } #else +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS class servoMoment { diff --git a/example/ogre-simulator/AROgre.cpp b/example/ogre-simulator/AROgre.cpp index 9e6699830b..3bb85a4c08 100644 --- a/example/ogre-simulator/AROgre.cpp +++ b/example/ogre-simulator/AROgre.cpp @@ -75,6 +75,10 @@ // List of allowed command line options #define GETOPTARGS "ci:p:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -730,5 +734,5 @@ int main() std::cout << "- Install Ogre3D, configure again ViSP using cmake and build again this example" << std::endl; #endif return EXIT_SUCCESS; -} + } #endif diff --git a/example/ogre-simulator/AROgreBasic.cpp b/example/ogre-simulator/AROgreBasic.cpp index fd6869b368..774156e558 100644 --- a/example/ogre-simulator/AROgreBasic.cpp +++ b/example/ogre-simulator/AROgreBasic.cpp @@ -75,6 +75,10 @@ // List of allowed command line options #define GETOPTARGS "ci:p:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/parse-argv/parse-argv1.cpp b/example/parse-argv/parse-argv1.cpp index 0764f3fa9b..b0b6117b69 100644 --- a/example/parse-argv/parse-argv1.cpp +++ b/example/parse-argv/parse-argv1.cpp @@ -50,11 +50,16 @@ #include #include #include +#include #include #include // List of allowed command line options #define GETOPTARGS "d:f:i:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, int i_val, float f_val, double d_val); bool getOptions(int argc, const char **argv, int &i_val, float &f_val, double &d_val); @@ -77,7 +82,7 @@ Parsing command line arguments example.\n\ SYNOPSIS\n\ %s [-i ] [-f ] [-d [-h]\n\ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -173,7 +178,8 @@ int main(int argc, const char **argv) cout << "Call " << argv[0] << " -h to see how to change these parameters." << endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/example/parse-argv/parse-argv2.cpp b/example/parse-argv/parse-argv2.cpp index bf8534c8a0..f23df14e1b 100644 --- a/example/parse-argv/parse-argv2.cpp +++ b/example/parse-argv/parse-argv2.cpp @@ -50,11 +50,16 @@ #include #include +#include #include #include int main(int argc, const char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { using ::std::cout; using ::std::endl; @@ -74,7 +79,7 @@ int main(int argc, const char **argv) {"-double", vpParseArgv::ARGV_DOUBLE, (char *)nullptr, (char *)&double_val, "A double value."}, {"-string", vpParseArgv::ARGV_STRING, (char *)nullptr, (char *)&string_val, "A chain value."}, {"-h", vpParseArgv::ARGV_HELP, (char *)nullptr, (char *)nullptr, "Print the help."}, - {(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_DEFAULTS)) { @@ -95,7 +100,8 @@ int main(int argc, const char **argv) cout << "Call " << argv[0] << " -h to see how to change these parameters." << endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } diff --git a/example/pose-estimation/poseVirtualVS.cpp b/example/pose-estimation/poseVirtualVS.cpp index d7cc269439..f3f70bc000 100644 --- a/example/pose-estimation/poseVirtualVS.cpp +++ b/example/pose-estimation/poseVirtualVS.cpp @@ -83,6 +83,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:p:hf:l:s:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -251,8 +255,8 @@ int main(int argc, const char **argv) std::cout << " poseVirtualVS.cpp" << std::endl << std::endl; std::cout << " Example of dots tracking in an image sequence and pose " - "computation" - << std::endl; + "computation" + << std::endl; std::cout << "-------------------------------------------------------" << std::endl; std::cout << std::endl; @@ -280,8 +284,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; } } // Test if an input path is set @@ -289,11 +293,11 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); 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 - << " Use -p option if you want to " << std::endl - << " use personal images" << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << " Use -p option if you want to " << std::endl + << " use personal images" << std::endl + << std::endl; return EXIT_FAILURE; } @@ -316,7 +320,8 @@ int main(int argc, const char **argv) s.setf(std::ios::right, std::ios::adjustfield); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; @@ -333,7 +338,8 @@ int main(int argc, const char **argv) if (opt_display) { d[i].setGraphics(true); - } else { + } + else { d[i].setGraphics(false); } } @@ -341,13 +347,15 @@ int main(int argc, const char **argv) // Read image named filename and put the bitmap into in I. try { vpImageIo::read(I, filename); - } catch (...) { + } + catch (...) { if (opt_ppath.empty()) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot read " << filename << std::endl; std::cerr << " Check your -i " << ipath << " option, " << std::endl - << " or VISP_INPUT_IMAGE_PATH environment variable" << std::endl; - } else { + << " or VISP_INPUT_IMAGE_PATH environment variable" << std::endl; + } + else { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot read " << filename << std::endl; std::cerr << " or your -p " << opt_ppath << " option " << std::endl << std::endl; @@ -406,7 +414,8 @@ int main(int argc, const char **argv) d[i].track(I, cog[i]); vpDisplay::flush(I); } - } else { + } + else { cog[0].set_u(194); cog[0].set_v(88); d[0].initTracking(I, cog[0]); @@ -533,7 +542,8 @@ int main(int argc, const char **argv) s.str(""); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } @@ -590,7 +600,8 @@ int main(int argc, const char **argv) iter += opt_step; } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } @@ -605,7 +616,7 @@ int main() int main() { std::cout << "You do not have X11, or GTK, or GDI (Graphical Device Interface) 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/reflex-takktile/takktile2-control.cpp b/example/reflex-takktile/takktile2-control.cpp index c264f5c481..92d9611d49 100644 --- a/example/reflex-takktile/takktile2-control.cpp +++ b/example/reflex-takktile/takktile2-control.cpp @@ -43,10 +43,15 @@ #include #include +#include #include int main(int argc, char *argv[]) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::string opt_network_interface = "eth0"; std::string opt_finger_file_name = "yaml/finger_calibrate.yaml"; std::string opt_tactile_file_name = "yaml/tactile_calibrate.yaml"; @@ -63,12 +68,12 @@ int main(int argc, char *argv[]) opt_motor_file_name = atoi(argv[i + 1]); else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] - << " [--network ] " - " [--finger ]" - " [--tactile ]" - " [--motor ]" - " [--help] [-h]\n" - << std::endl; + << " [--network ] " + " [--finger ]" + " [--tactile ]" + " [--motor ]" + " [--help] [-h]\n" + << std::endl; std::cout << "Options:" << std::endl; std::cout << " --network " << std::endl; std::cout << "\tNetwork interface name. Default: " << opt_network_interface << std::endl << std::endl; @@ -106,7 +111,7 @@ int main(int argc, char *argv[]) std::cout << "Moving fingers..." << std::endl; std::vector finger_positions = { - {0.0, 0.0, 0.0, 0.0}, {0.5, 0.5, 0.5, 0.0}, {1.0, 1.0, 1.0, 0.0}, {0.5, 0.5, 0.5, 0.0}, {0.0, 0.0, 0.0, 0.0}}; + {0.0, 0.0, 0.0, 0.0}, {0.5, 0.5, 0.5, 0.0}, {1.0, 1.0, 1.0, 0.0}, {0.5, 0.5, 0.5, 0.0}, {0.0, 0.0, 0.0, 0.0} }; for (size_t i = 0; i < finger_positions.size(); i++) { reflex.setPosition(finger_positions[i]); @@ -122,7 +127,7 @@ int main(int argc, char *argv[]) std::cout << "Moving preshape joint..." << std::endl; std::vector preshape_positions = { - {0.0, 0.0, 0.0, 0.0}, {0.0, 0.0, 0.0, 0.5}, {0.0, 0.0, 0.0, 1.5}, {0.0, 0.0, 0.0, 0.5}, {0.0, 0.0, 0.0, 0.0}}; + {0.0, 0.0, 0.0, 0.0}, {0.0, 0.0, 0.0, 0.5}, {0.0, 0.0, 0.0, 1.5}, {0.0, 0.0, 0.0, 0.5}, {0.0, 0.0, 0.0, 0.0} }; for (size_t i = 0; i < preshape_positions.size(); i++) { reflex.setPosition(preshape_positions[i]); @@ -136,7 +141,7 @@ int main(int argc, char *argv[]) // Demonstration of changing velocity std::cout << "Changing to faster speed..." << std::endl; - vpColVector faster_velocities = {7.0, 7.0, 7.0, 7.0}; + vpColVector faster_velocities = { 7.0, 7.0, 7.0, 7.0 }; reflex.setPositioningVelocity(faster_velocities); for (size_t i = 0; i < finger_positions.size(); i++) { @@ -145,7 +150,7 @@ int main(int argc, char *argv[]) } std::cout << "Changing to slower speed..." << std::endl; - vpColVector slower_velocities = {0.5, 0.5, 0.5, 0.5}; + vpColVector slower_velocities = { 0.5, 0.5, 0.5, 0.5 }; reflex.setPositioningVelocity(slower_velocities); for (size_t i = 0; i < finger_positions.size(); i++) { @@ -160,7 +165,7 @@ int main(int argc, char *argv[]) // Demonstration of blended control std::cout << "Starting blended control..." << std::endl; - vpColVector mixed_speeds = {0.5, 1.0, 1.5, 0.0}; + vpColVector mixed_speeds = { 0.5, 1.0, 1.5, 0.0 }; reflex.setPositioningVelocity(mixed_speeds); for (int i = 0; i < 5; i++) { @@ -177,8 +182,8 @@ int main(int argc, char *argv[]) // Demonstration of tactile feedback and setting sensor thresholds std::cout << "Starting tactile feedback..." << std::endl - << "All fingers will stop moving when any one makes contact" << std::endl; - vpColVector move_speeds = {1.25, 1.25, 1.25, 0}; + << "All fingers will stop moving when any one makes contact" << std::endl; + vpColVector move_speeds = { 1.25, 1.25, 1.25, 0 }; reflex.setTactileThreshold(15); @@ -191,8 +196,8 @@ int main(int argc, char *argv[]) /****************************************************/ std::cout << "Now each finger will only stop moving once it makes contact" << std::endl; - std::vector thresholds = {10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 20, 20, 20, 20, 20, 20, 20, - 20, 20, 20, 20, 20, 20, 20, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30}; + std::vector thresholds = { 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 20, 20, 20, 20, 20, 20, 20, + 20, 20, 20, 20, 20, 20, 20, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30 }; reflex.setTactileThreshold(thresholds); diff --git a/example/reflex-takktile/takktile2-read-data.cpp b/example/reflex-takktile/takktile2-read-data.cpp index 8893304cfc..8a04cb7aa8 100644 --- a/example/reflex-takktile/takktile2-read-data.cpp +++ b/example/reflex-takktile/takktile2-read-data.cpp @@ -43,10 +43,15 @@ #include #include +#include #include -int main(int argc, char *argv []) +int main(int argc, char *argv[]) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::string opt_network_interface = "eth0"; std::string opt_finger_file_name = "yaml/finger_calibrate.yaml"; std::string opt_tactile_file_name = "yaml/tactile_calibrate.yaml"; diff --git a/example/robot-simulator/afma6/CMakeLists.txt b/example/robot-simulator/afma6/CMakeLists.txt index b6c7c9ed11..a9394ecf8d 100644 --- a/example/robot-simulator/afma6/CMakeLists.txt +++ b/example/robot-simulator/afma6/CMakeLists.txt @@ -50,6 +50,8 @@ foreach(cpp ${example_cpp}) endif() # Add test - get_filename_component(target ${cpp} NAME_WE) - add_test(${target} ${target} -c ${OPTION_TO_DESACTIVE_DISPLAY}) + # Workaround for github action issue when using std::mutex by removing the test + # See https://github.com/actions/runner-images/issues/10020 + # get_filename_component(target ${cpp} NAME_WE) + # add_test(${target} ${target} -c ${OPTION_TO_DESACTIVE_DISPLAY}) endforeach() diff --git a/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp b/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp index cceca787e7..da6db8c56a 100644 --- a/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp @@ -82,6 +82,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); diff --git a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp index ba1b3875ba..0ff5f12aa5 100644 --- a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp @@ -54,6 +54,7 @@ #include #include +#include #include #include #include @@ -66,6 +67,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -302,4 +307,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocityWithoutVpServo.cpp b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocityWithoutVpServo.cpp index b855f56441..0a2a7c832e 100644 --- a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocityWithoutVpServo.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocityWithoutVpServo.cpp @@ -78,6 +78,7 @@ #include #include +#include #include #include #include @@ -90,6 +91,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); diff --git a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp index 0f54aefe77..28f350cc43 100644 --- a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp @@ -55,6 +55,7 @@ #include #include +#include #include #include #include @@ -67,6 +68,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -298,4 +303,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocityWithoutVpServo.cpp b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocityWithoutVpServo.cpp index 37cb1dfb9c..aa6d867348 100644 --- a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocityWithoutVpServo.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocityWithoutVpServo.cpp @@ -71,6 +71,7 @@ #include #include +#include #include #include #include @@ -82,6 +83,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); diff --git a/example/robot-simulator/camera/servoSimuCircle2DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuCircle2DCamVelocity.cpp index 2ab28359fc..f2f6b1f04f 100644 --- a/example/robot-simulator/camera/servoSimuCircle2DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuCircle2DCamVelocity.cpp @@ -54,6 +54,7 @@ #include #include +#include #include #include #include @@ -65,6 +66,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -240,4 +245,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuCircle2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuCircle2DCamVelocityDisplay.cpp index e8679dc4ee..ea79faf6da 100644 --- a/example/robot-simulator/camera/servoSimuCircle2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuCircle2DCamVelocityDisplay.cpp @@ -71,6 +71,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); diff --git a/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplay.cpp index 303387dd4a..95f3746640 100644 --- a/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplay.cpp @@ -71,6 +71,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); diff --git a/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp b/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp index 7599c18c77..c263b4ee1c 100644 --- a/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp +++ b/example/robot-simulator/camera/servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp @@ -53,6 +53,7 @@ #include #include +#include #include #include #include @@ -73,6 +74,10 @@ // List of allowed command line options #define GETOPTARGS "cdho" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -422,13 +427,14 @@ int main(int argc, const char **argv) if (opt_display && opt_click_allowed) { std::stringstream ss; ss << std::string("New projection operator: ") + - (opt_new_proj_operator ? std::string("yes (use option -o to use old one)") : std::string("no")); + (opt_new_proj_operator ? std::string("yes (use option -o to use old one)") : std::string("no")); vpDisplay::displayText(Iint, 20, 20, "Secondary task enabled: yes", vpColor::white); vpDisplay::displayText(Iint, 40, 20, ss.str(), vpColor::white); } iter_sec++; - } else { + } + else { if (opt_display && opt_click_allowed) { vpDisplay::displayText(Iint, 20, 20, "Secondary task: no", vpColor::white); } @@ -462,7 +468,8 @@ int main(int argc, const char **argv) // Display task information task.print(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } @@ -472,4 +479,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp index ef9b263aa9..c02062c1a5 100644 --- a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp @@ -62,6 +62,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -271,4 +275,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp index 219d880f03..c544164ae6 100644 --- a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp @@ -78,6 +78,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); diff --git a/example/robot-simulator/camera/servoSimuFourPoints2DPolarCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuFourPoints2DPolarCamVelocityDisplay.cpp index 7612b05139..e2eaceb36d 100644 --- a/example/robot-simulator/camera/servoSimuFourPoints2DPolarCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuFourPoints2DPolarCamVelocityDisplay.cpp @@ -80,6 +80,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -191,7 +195,8 @@ int main(int argc, const char **argv) try { // Create the dirname vpIoTools::makeDirectory(logdirname); - } catch (...) { + } + catch (...) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << logdirname << std::endl; return EXIT_FAILURE; @@ -468,7 +473,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; } @@ -477,11 +483,11 @@ int main(int argc, const char **argv) int main() { std::cout << "You do not have X11, or GTK, or GDI (Graphical Device Interface) 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; std::cout << "- Install GDI, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/robot-simulator/camera/servoSimuLine2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuLine2DCamVelocityDisplay.cpp index 7b5df1375c..05c8cb7921 100644 --- a/example/robot-simulator/camera/servoSimuLine2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuLine2DCamVelocityDisplay.cpp @@ -69,6 +69,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -190,7 +194,8 @@ int main(int argc, const char **argv) // display variable. vpDisplay::display(I); vpDisplay::flush(I); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error while displaying the image"); return EXIT_FAILURE; } @@ -308,7 +313,8 @@ int main(int argc, const char **argv) // Display task information task.print(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } @@ -324,7 +330,7 @@ int main() int main() { std::cout << "You do not have X11, or GTK, or GDI (Graphical Device Interface) 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/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp index c08dbc4585..ea5743dbcf 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp @@ -44,6 +44,7 @@ #include #include +#include #include #include #include @@ -55,6 +56,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -218,4 +223,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp index d6c81008fa..c91d12493d 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp @@ -52,6 +52,7 @@ #include #include +#include #include #include #include @@ -63,6 +64,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -250,4 +255,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp index b8cc4108a7..dd6f6f0aa4 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp @@ -50,6 +50,7 @@ #include #include +#include #include #include #include @@ -61,6 +62,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -246,4 +251,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp index ba6cbbab63..a40dcae8d8 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp @@ -46,6 +46,7 @@ #include #include +#include #include #include #include @@ -60,6 +61,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -262,4 +267,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp index b7f2d5b898..bb010efd48 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp @@ -45,6 +45,7 @@ #include #include +#include #include #include #include @@ -59,6 +60,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -351,4 +356,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp index 9756d6d924..121ae424df 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp @@ -45,6 +45,7 @@ #include #include +#include #include #include #include @@ -59,6 +60,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -329,4 +334,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp index d83137b22a..b5b6a2876f 100644 --- a/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp @@ -46,6 +46,7 @@ #include #include +#include #include #include #include @@ -57,6 +58,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -228,4 +233,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuSphere2DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuSphere2DCamVelocity.cpp index d0fda0cc78..d63a988b2c 100644 --- a/example/robot-simulator/camera/servoSimuSphere2DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuSphere2DCamVelocity.cpp @@ -45,6 +45,7 @@ #include #include +#include #include #include #include @@ -57,6 +58,10 @@ // List of allowed command line options #define GETOPTARGS "h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); @@ -220,7 +225,8 @@ int main(int argc, const char **argv) // Display task information task.print(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } @@ -230,4 +236,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplay.cpp index c0d1dffc75..5f27292174 100644 --- a/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplay.cpp @@ -45,6 +45,7 @@ #include #include +#include #include #include #include @@ -62,6 +63,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -279,7 +284,8 @@ int main(int argc, const char **argv) // Display task information task.print(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } @@ -289,4 +295,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp b/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp index 99b0da9da4..b6700ad69a 100644 --- a/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp +++ b/example/robot-simulator/camera/servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp @@ -46,6 +46,7 @@ #include #include +#include #include #include #include @@ -65,6 +66,10 @@ // List of allowed command line options #define GETOPTARGS "cdho" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -342,11 +347,12 @@ int main(int argc, const char **argv) if (opt_display && opt_click_allowed) { std::stringstream ss; ss << std::string("New projection operator: ") + - (opt_new_proj_operator ? std::string("yes (use option -o to use old one)") : std::string("no")); + (opt_new_proj_operator ? std::string("yes (use option -o to use old one)") : std::string("no")); vpDisplay::displayText(I, 20, 20, "Secondary task enabled: yes", vpColor::white); vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::white); } - } else { + } + else { if (opt_display && opt_click_allowed) { vpDisplay::displayText(I, 20, 20, "Secondary task enabled: no", vpColor::white); } @@ -378,7 +384,8 @@ int main(int argc, const char **argv) // Display task information task.print(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } @@ -388,4 +395,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/camera/servoSimuSquareLine2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuSquareLine2DCamVelocityDisplay.cpp index 06defae5d3..ec13d35c09 100644 --- a/example/robot-simulator/camera/servoSimuSquareLine2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuSquareLine2DCamVelocityDisplay.cpp @@ -70,6 +70,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -191,7 +195,8 @@ int main(int argc, const char **argv) // display variable. vpDisplay::display(I); vpDisplay::flush(I); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error while displaying the image"); return EXIT_FAILURE; } @@ -319,7 +324,8 @@ int main(int argc, const char **argv) // Display task information task.print(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } @@ -335,8 +341,8 @@ int main() int main() { std::cout << "You do not have X11, or GTK, or GDI (Graphical Device Interface) or OpenCV functionalities to display " - "images..." - << std::endl; + "images..." + << 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/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp b/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp index 2d4553acc4..f0df9b5be6 100644 --- a/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp @@ -48,6 +48,7 @@ #include #include +#include #include #include #include @@ -58,6 +59,11 @@ // List of allowed command line options #define GETOPTARGS "h" + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv); /*! @@ -220,4 +226,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/robot-simulator/viper850/CMakeLists.txt b/example/robot-simulator/viper850/CMakeLists.txt index cf47e1a539..12b88ad0ca 100644 --- a/example/robot-simulator/viper850/CMakeLists.txt +++ b/example/robot-simulator/viper850/CMakeLists.txt @@ -50,6 +50,8 @@ foreach(cpp ${example_cpp}) endif() # Add test - get_filename_component(target ${cpp} NAME_WE) - add_test(${target} ${target} -c ${OPTION_TO_DESACTIVE_DISPLAY}) + # Workaround for github action issue when using std::mutex by removing the test + # See https://github.com/actions/runner-images/issues/10020 + # get_filename_component(target ${cpp} NAME_WE) + # add_test(${target} ${target} -c ${OPTION_TO_DESACTIVE_DISPLAY}) endforeach() diff --git a/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp b/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp index 64e82c5d71..29136037b8 100644 --- a/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp @@ -82,6 +82,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); diff --git a/example/servo-afma4/moveAfma4.cpp b/example/servo-afma4/moveAfma4.cpp index 5594c45864..1dc5ad25a6 100644 --- a/example/servo-afma4/moveAfma4.cpp +++ b/example/servo-afma4/moveAfma4.cpp @@ -63,6 +63,10 @@ // List of allowed command line options #define GETOPTARGS "mh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -80,7 +84,7 @@ of the Afma4 robot.\n\ SYNOPSIS\n\ %s [-m] [-h]\n\ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -184,39 +188,39 @@ int main(int argc, const char **argv) // std::cout << "Velocity control: in articular..." << std::endl; - q = 0 ; - q[0] = vpMath::rad(2) ; // rotation around vertical axis + q = 0; + q[0] = vpMath::rad(2); // rotation around vertical axis std::cout << " rotation around vertical axis: " << q[0] << std::endl; if (control) - robot.setVelocity(vpRobot::ARTICULAR_FRAME, q) ; - sleep(5) ; + robot.setVelocity(vpRobot::ARTICULAR_FRAME, q); + sleep(5); - q = 0 ; - q[1] = 0.2 ; // Vertical translation + q = 0; + q[1] = 0.2; // Vertical translation std::cout << " vertical translation: " << q[1] << std::endl; if (control) - robot.setVelocity(vpRobot::ARTICULAR_FRAME, q) ; - sleep(5) ; + robot.setVelocity(vpRobot::ARTICULAR_FRAME, q); + sleep(5); - q = 0 ; - q[1] = -0.2 ; // Vertical translation + q = 0; + q[1] = -0.2; // Vertical translation std::cout << " vertical translation: " << q[1] << std::endl; if (control) - robot.setVelocity(vpRobot::ARTICULAR_FRAME, q) ; - sleep(5) ; - q = 0 ; - q[2] = vpMath::rad(3) ; // pan + robot.setVelocity(vpRobot::ARTICULAR_FRAME, q); + sleep(5); + q = 0; + q[2] = vpMath::rad(3); // pan std::cout << " pan rotation: " << q[2] << std::endl; if (control) - robot.setVelocity(vpRobot::ARTICULAR_FRAME, q) ; - sleep(5) ; + robot.setVelocity(vpRobot::ARTICULAR_FRAME, q); + sleep(5); - q = 0 ; - q[3] = vpMath::rad(2) ; // tilt + q = 0; + q[3] = vpMath::rad(2); // tilt std::cout << " tilt rotation: " << q[3] << std::endl; if (control) - robot.setVelocity(vpRobot::ARTICULAR_FRAME, q) ; - sleep(5) ; + robot.setVelocity(vpRobot::ARTICULAR_FRAME, q); + sleep(5); #endif // // Velocity control in camera frame @@ -241,7 +245,8 @@ int main(int argc, const char **argv) std::cout << "The end" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/example/servo-afma4/servoAfma4Point2DArtVelocity.cpp b/example/servo-afma4/servoAfma4Point2DArtVelocity.cpp index d6f9fa9033..f573583197 100644 --- a/example/servo-afma4/servoAfma4Point2DArtVelocity.cpp +++ b/example/servo-afma4/servoAfma4Point2DArtVelocity.cpp @@ -89,6 +89,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: diff --git a/example/servo-afma4/servoAfma4Point2DCamVelocity.cpp b/example/servo-afma4/servoAfma4Point2DCamVelocity.cpp index 495d65c96a..7d42b92cc6 100644 --- a/example/servo-afma4/servoAfma4Point2DCamVelocity.cpp +++ b/example/servo-afma4/servoAfma4Point2DCamVelocity.cpp @@ -85,6 +85,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: diff --git a/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp b/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp index 92b6e79237..ed853419f3 100644 --- a/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp +++ b/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp @@ -79,6 +79,10 @@ // List of allowed command line options #define GETOPTARGS "hK:l:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + typedef enum { K_NONE, K_VELOCITY, K_ACCELERATION } KalmanType; /*! diff --git a/example/servo-afma6/CMakeLists.txt b/example/servo-afma6/CMakeLists.txt index 20eee630ce..421e53d58f 100644 --- a/example/servo-afma6/CMakeLists.txt +++ b/example/servo-afma6/CMakeLists.txt @@ -103,6 +103,7 @@ if(VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-ignored-qualifiers") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-compare") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") visp_set_source_file_compile_flag(servoAfma6AprilTagIBVS.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(servoAfma6AprilTagPBVS.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/example/servo-afma6/servoAfma62DhalfCamVelocity.cpp b/example/servo-afma6/servoAfma62DhalfCamVelocity.cpp index 1933aa3007..f9fd83024c 100644 --- a/example/servo-afma6/servoAfma62DhalfCamVelocity.cpp +++ b/example/servo-afma6/servoAfma62DhalfCamVelocity.cpp @@ -96,6 +96,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; diff --git a/example/servo-afma6/servoAfma6AprilTagIBVS.cpp b/example/servo-afma6/servoAfma6AprilTagIBVS.cpp index c18c321ef5..af8c1f6535 100644 --- a/example/servo-afma6/servoAfma6AprilTagIBVS.cpp +++ b/example/servo-afma6/servoAfma6AprilTagIBVS.cpp @@ -54,6 +54,7 @@ #include #include +#include #include #include #include @@ -68,6 +69,10 @@ #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) { diff --git a/example/servo-afma6/servoAfma6AprilTagPBVS.cpp b/example/servo-afma6/servoAfma6AprilTagPBVS.cpp index e5e567549b..7481d7a968 100644 --- a/example/servo-afma6/servoAfma6AprilTagPBVS.cpp +++ b/example/servo-afma6/servoAfma6AprilTagPBVS.cpp @@ -51,6 +51,7 @@ #include #include +#include #include #include #include @@ -65,6 +66,10 @@ #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) { diff --git a/example/servo-afma6/servoAfma6Cylinder2DCamVelocity.cpp b/example/servo-afma6/servoAfma6Cylinder2DCamVelocity.cpp index dd9b5a756b..f795460c20 100644 --- a/example/servo-afma6/servoAfma6Cylinder2DCamVelocity.cpp +++ b/example/servo-afma6/servoAfma6Cylinder2DCamVelocity.cpp @@ -79,6 +79,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; diff --git a/example/servo-afma6/servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp b/example/servo-afma6/servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp index 82598ebebb..171e24f705 100644 --- a/example/servo-afma6/servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp +++ b/example/servo-afma6/servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp @@ -83,6 +83,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; diff --git a/example/servo-afma6/servoAfma6Ellipse2DCamVelocity.cpp b/example/servo-afma6/servoAfma6Ellipse2DCamVelocity.cpp index 3bbb90bc34..f417fd8b37 100644 --- a/example/servo-afma6/servoAfma6Ellipse2DCamVelocity.cpp +++ b/example/servo-afma6/servoAfma6Ellipse2DCamVelocity.cpp @@ -83,6 +83,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpServo task; diff --git a/example/servo-afma6/servoAfma6FourPoints2DArtVelocity.cpp b/example/servo-afma6/servoAfma6FourPoints2DArtVelocity.cpp index eb9580def4..dfed3fbf53 100644 --- a/example/servo-afma6/servoAfma6FourPoints2DArtVelocity.cpp +++ b/example/servo-afma6/servoAfma6FourPoints2DArtVelocity.cpp @@ -94,6 +94,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed joint velocities (m/s, rad/s) to achieve the task diff --git a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur.cpp b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur.cpp index 9cc611dd43..a34fd93593 100644 --- a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur.cpp +++ b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur.cpp @@ -90,6 +90,10 @@ #define L 0.06 // to deal with a 12cm by 12cm square +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Compute the pose \e cMo from the 3D coordinates of the points \e point and diff --git a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_des.cpp b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_des.cpp index 8da9ff666d..ce31d9306b 100644 --- a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_des.cpp +++ b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_des.cpp @@ -91,6 +91,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed camera velocities (m/s, rad/s) to achieve the task diff --git a/example/servo-afma6/servoAfma6Line2DCamVelocity.cpp b/example/servo-afma6/servoAfma6Line2DCamVelocity.cpp index 609d342d5a..b59498161e 100644 --- a/example/servo-afma6/servoAfma6Line2DCamVelocity.cpp +++ b/example/servo-afma6/servoAfma6Line2DCamVelocity.cpp @@ -79,6 +79,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; diff --git a/example/servo-afma6/servoAfma6MegaposePBVS.cpp b/example/servo-afma6/servoAfma6MegaposePBVS.cpp index ad9b59eb86..4016c14888 100644 --- a/example/servo-afma6/servoAfma6MegaposePBVS.cpp +++ b/example/servo-afma6/servoAfma6MegaposePBVS.cpp @@ -63,6 +63,7 @@ #include #include +#include #include #include #include @@ -89,6 +90,10 @@ using json = nlohmann::json; //! json namespace shortcut #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + std::optional detectObjectForInitMegaposeClick(const vpImage &I) { const bool startLabelling = vpDisplay::getClick(I, false); diff --git a/example/servo-afma6/servoAfma6Point2DArtVelocity.cpp b/example/servo-afma6/servoAfma6Point2DArtVelocity.cpp index c18f38a93e..e0d96a6dc8 100644 --- a/example/servo-afma6/servoAfma6Point2DArtVelocity.cpp +++ b/example/servo-afma6/servoAfma6Point2DArtVelocity.cpp @@ -88,6 +88,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed joint velocities (m/s, rad/s) to achieve the task diff --git a/example/servo-afma6/servoAfma6Point2DCamVelocity.cpp b/example/servo-afma6/servoAfma6Point2DCamVelocity.cpp index a2f8e06c0c..f2cbf4c61b 100644 --- a/example/servo-afma6/servoAfma6Point2DCamVelocity.cpp +++ b/example/servo-afma6/servoAfma6Point2DCamVelocity.cpp @@ -80,6 +80,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed cam velocities (m/s, rad/s) to achieve the task diff --git a/example/servo-afma6/servoAfma6Points2DCamVelocityEyeToHand.cpp b/example/servo-afma6/servoAfma6Points2DCamVelocityEyeToHand.cpp index aaae0a0205..e648fbc99f 100644 --- a/example/servo-afma6/servoAfma6Points2DCamVelocityEyeToHand.cpp +++ b/example/servo-afma6/servoAfma6Points2DCamVelocityEyeToHand.cpp @@ -87,6 +87,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { std::string username = vpIoTools::getUserName(); std::string logdirname = "/tmp/" + username; diff --git a/example/servo-afma6/servoAfma6Segment2DCamVelocity.cpp b/example/servo-afma6/servoAfma6Segment2DCamVelocity.cpp index c39eaac2ee..fb07398fcc 100644 --- a/example/servo-afma6/servoAfma6Segment2DCamVelocity.cpp +++ b/example/servo-afma6/servoAfma6Segment2DCamVelocity.cpp @@ -74,6 +74,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed cam velocities (m/s, rad/s) to achieve the task diff --git a/example/servo-afma6/servoAfma6SquareLines2DCamVelocity.cpp b/example/servo-afma6/servoAfma6SquareLines2DCamVelocity.cpp index 130afff54d..d0bc247c77 100644 --- a/example/servo-afma6/servoAfma6SquareLines2DCamVelocity.cpp +++ b/example/servo-afma6/servoAfma6SquareLines2DCamVelocity.cpp @@ -85,6 +85,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; diff --git a/example/servo-afma6/servoAfma6TwoLines2DCamVelocity.cpp b/example/servo-afma6/servoAfma6TwoLines2DCamVelocity.cpp index c0b496b4df..73bdd66dae 100644 --- a/example/servo-afma6/servoAfma6TwoLines2DCamVelocity.cpp +++ b/example/servo-afma6/servoAfma6TwoLines2DCamVelocity.cpp @@ -86,6 +86,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; diff --git a/example/servo-bebop2/keyboardControlBebop2.cpp b/example/servo-bebop2/keyboardControlBebop2.cpp index dc53acf7b5..bdf03033e8 100644 --- a/example/servo-bebop2/keyboardControlBebop2.cpp +++ b/example/servo-bebop2/keyboardControlBebop2.cpp @@ -48,6 +48,10 @@ #ifdef VISP_HAVE_ARSDK +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Sends movement commands to the \e drone based on a keyboard input \e key. @@ -129,7 +133,8 @@ bool handleKeyboardInput(vpRobotBebop2 &drone, int key) break; } vpTime::wait(25); // We wait 25ms to give the drone the time to process the command - } else { + } + else { running = false; } return running; @@ -159,37 +164,41 @@ int main(int argc, char **argv) if (std::string(argv[i]) == "--ip" && i + 1 < argc) { ip_address = std::string(argv[i + 1]); i++; - } else if (std::string(argv[i]) == "--hd_stream") { + } + else if (std::string(argv[i]) == "--hd_stream") { stream_res = 1; - } else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { + } + else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { verbose = true; - } else if (argc >= 2 && (std::string(argv[1]) == "--help" || std::string(argv[1]) == "-h")) { + } + else if (argc >= 2 && (std::string(argv[1]) == "--help" || std::string(argv[1]) == "-h")) { std::cout << "\nUsage:\n" - << " " << argv[0] << "[--ip ] [--hd_stream] [--verbose] [-v] [--help] [-h]\n" - << std::endl - << "Description:\n" - << " --ip \n" - << " Ip address of the drone to which you want to connect (default : 192.168.42.1).\n\n" - << " --hd_stream\n" - << " Enables HD 720p streaming instead of default 480p.\n" - << " --verbose, -v\n" - << " Enables verbose (drone information messages and velocity commands\n" - << " are then displayed).\n\n" - << " --help, -h\n" - << " Print help message.\n" - << std::endl; + << " " << argv[0] << "[--ip ] [--hd_stream] [--verbose] [-v] [--help] [-h]\n" + << std::endl + << "Description:\n" + << " --ip \n" + << " Ip address of the drone to which you want to connect (default : 192.168.42.1).\n\n" + << " --hd_stream\n" + << " Enables HD 720p streaming instead of default 480p.\n" + << " --verbose, -v\n" + << " Enables verbose (drone information messages and velocity commands\n" + << " are then displayed).\n\n" + << " --help, -h\n" + << " Print help message.\n" + << std::endl; return EXIT_SUCCESS; - } else { + } + else { std::cout << "Error : unknown parameter " << argv[i] << std::endl - << "See " << argv[0] << " --help" << std::endl; + << "See " << argv[0] << " --help" << std::endl; return EXIT_FAILURE; } } std::cout << "\nWARNING: this program does no sensing or avoiding of obstacles, " - "the drone WILL collide with any objects in the way! Make sure the " - "drone has approximately 3 meters of free space on all sides.\n" - << std::endl; + "the drone WILL collide with any objects in the way! Make sure the " + "drone has approximately 3 meters of free space on all sides.\n" + << std::endl; vpRobotBebop2 drone(verbose, true, ip_address); // Create the drone with low verbose level, settings reset and corresponding IP @@ -221,10 +230,10 @@ int main(int argc, char **argv) vpKeyboard keyboard; std::cout << "\n| Control the drone with the keyboard :\n" - "| 't' to takeoff / spacebar to land / 'e' for emergency stop\n" - "| ('r','f','d','g') and ('i','k','j','l') to move\n" - "| 'q' to quit.\n" - << std::endl; + "| 't' to takeoff / spacebar to land / 'e' for emergency stop\n" + "| ('r','f','d','g') and ('i','k','j','l') to move\n" + "| 'q' to quit.\n" + << std::endl; while (running && drone.isRunning() && drone.isStreaming()) { @@ -243,11 +252,13 @@ int main(int argc, char **argv) } std::cout << "\nQuitting ...\n" << std::endl; - } else { + } + else { std::cout << "ERROR : failed to setup drone control." << std::endl; return EXIT_FAILURE; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "\nCaught an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/example/servo-bebop2/servoBebop2.cpp b/example/servo-bebop2/servoBebop2.cpp index 90fe22ab2f..69e94fec9d 100644 --- a/example/servo-bebop2/servoBebop2.cpp +++ b/example/servo-bebop2/servoBebop2.cpp @@ -82,6 +82,10 @@ int main() #else +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool compareImagePoint(std::pair p1, std::pair p2) { return (p1.second.get_v() < p2.second.get_v()); diff --git a/example/servo-biclops/moveBiclops.cpp b/example/servo-biclops/moveBiclops.cpp index 55cce1c1a8..a0f1161aaa 100644 --- a/example/servo-biclops/moveBiclops.cpp +++ b/example/servo-biclops/moveBiclops.cpp @@ -53,6 +53,10 @@ // List of allowed command line options #define GETOPTARGS "c:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /* * Print the program options. * diff --git a/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp b/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp index 1f0bef8868..442263f789 100644 --- a/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp +++ b/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp @@ -67,6 +67,10 @@ // List of allowed command line options #define GETOPTARGS "c:d:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! * Print the program options. * diff --git a/example/servo-flir-ptu/servoFlirPtuIBVS.cpp b/example/servo-flir-ptu/servoFlirPtuIBVS.cpp index 6676140d35..f6145229f5 100644 --- a/example/servo-flir-ptu/servoFlirPtuIBVS.cpp +++ b/example/servo-flir-ptu/servoFlirPtuIBVS.cpp @@ -58,6 +58,7 @@ #include #include +#include #include #include #include @@ -74,6 +75,10 @@ #if defined(VISP_HAVE_FLIR_PTU_SDK) && defined(VISP_HAVE_FLYCAPTURE) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PUGIXML) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void display_point_trajectory(const vpImage &I, const vpImagePoint &ip, std::vector &traj_ip) { diff --git a/example/servo-franka/CMakeLists.txt b/example/servo-franka/CMakeLists.txt index cb254d7a89..8c2d5ceebb 100644 --- a/example/servo-franka/CMakeLists.txt +++ b/example/servo-franka/CMakeLists.txt @@ -64,6 +64,7 @@ if(VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-compare") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-function") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") visp_set_source_file_compile_flag(servoFrankaPBVS.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(servoFrankaIBVS.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/example/servo-franka/frankaGripper.cpp b/example/servo-franka/frankaGripper.cpp index eafd67d8b9..76a5c73938 100644 --- a/example/servo-franka/frankaGripper.cpp +++ b/example/servo-franka/frankaGripper.cpp @@ -40,11 +40,13 @@ #include +#include #include #if defined(VISP_HAVE_FRANKA) -typedef enum { +typedef enum +{ Gripper_Home, Gripper_Open, Gripper_Close, @@ -56,6 +58,10 @@ typedef enum { int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::string opt_robot_ip = "192.168.1.1"; double opt_grasping_width = 0.; GripperState_t opt_gripper_state = Gripper_None; @@ -63,28 +69,34 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { opt_robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--home") { + } + else if (std::string(argv[i]) == "--home") { opt_gripper_state = Gripper_Home; - } else if (std::string(argv[i]) == "--open") { + } + else if (std::string(argv[i]) == "--open") { opt_gripper_state = Gripper_Open; - } else if (std::string(argv[i]) == "--close") { + } + else if (std::string(argv[i]) == "--close") { opt_gripper_state = Gripper_Close; - } else if (std::string(argv[i]) == "--grasp" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--grasp" && i + 1 < argc) { opt_gripper_state = Gripper_Grasp; opt_grasping_width = std::atof(argv[i + 1]); - } else if (std::string(argv[i]) == "--test" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--test" && i + 1 < argc) { opt_gripper_state = Gripper_Test; opt_grasping_width = std::atof(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Control Panda gripper." << std::endl; std::cout << argv[0] << " [--ip ] [--home] [--open] [--close] [--grasp ] [--release] [--test ] [--help] [-h]\n" - << std::endl; + << ">] [--home] [--open] [--close] [--grasp ] [--release] [--test ] [--help] [-h]\n" + << std::endl; std::cout << "Example to grasp a 4cm width object by first opening the gripper, then grasping the object :\n" - << argv[0] << " --ip 192.168.100.1 --open\n" - << argv[0] << " --ip 192.168.100.1 --grasp 0.04\n" - << std::endl; + << argv[0] << " --ip 192.168.100.1 --open\n" + << argv[0] << " --ip 192.168.100.1 --grasp 0.04\n" + << std::endl; return EXIT_SUCCESS; } @@ -92,11 +104,12 @@ int main(int argc, char **argv) if (opt_gripper_state == Gripper_None) { std::cout << "Specify which action you want to achieve. Run \"" << argv[0] - << " --help\" to see how to use this binary." << std::endl; + << " --help\" to see how to use this binary." << std::endl; return EXIT_SUCCESS; - } else if ((opt_gripper_state == Gripper_Grasp || opt_gripper_state == Gripper_Test) && opt_grasping_width <= 0) { + } + else if ((opt_gripper_state == Gripper_Grasp || opt_gripper_state == Gripper_Test) && opt_grasping_width <= 0) { std::cout << "Object with in meter should be > 0. Run \"" << argv[0] << " --help\" to see how to use this binary." - << std::endl; + << std::endl; return EXIT_SUCCESS; } @@ -108,19 +121,24 @@ int main(int argc, char **argv) if (opt_gripper_state == Gripper_Home) { std::cout << "Gripper homing..." << std::endl; robot.gripperHoming(); - } else if (opt_gripper_state == Gripper_Close) { + } + else if (opt_gripper_state == Gripper_Close) { std::cout << "Gripper closing..." << std::endl; robot.gripperClose(); - } else if (opt_gripper_state == Gripper_Open) { + } + else if (opt_gripper_state == Gripper_Open) { std::cout << "Gripper opening..." << std::endl; robot.gripperOpen(); - } else if (opt_gripper_state == Gripper_Grasp) { + } + else if (opt_gripper_state == Gripper_Grasp) { std::cout << "Gripper grasp " << opt_grasping_width << "m object width..." << std::endl; robot.gripperGrasp(opt_grasping_width); - } else if (opt_gripper_state == Gripper_Release) { + } + else if (opt_gripper_state == Gripper_Release) { std::cout << "Gripper release object..." << std::endl; robot.gripperRelease(); - } else if (opt_gripper_state == Gripper_Test) { + } + else if (opt_gripper_state == Gripper_Test) { std::cout << "Test gripper performing the following actions:" << std::endl; std::cout << "- Gripper homing..." << std::endl; robot.gripperHoming(); @@ -141,16 +159,19 @@ int main(int argc, char **argv) robot.gripperRelease(); } std::cout << "The end!" << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " - << std::endl; + << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " + << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/example/servo-franka/frankaMoveToPosition.cpp b/example/servo-franka/frankaMoveToPosition.cpp index 1bf6b6129e..6934f24599 100644 --- a/example/servo-franka/frankaMoveToPosition.cpp +++ b/example/servo-franka/frankaMoveToPosition.cpp @@ -40,6 +40,7 @@ #include +#include #include #include @@ -47,18 +48,24 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::string opt_robot_ip = "192.168.1.1"; std::string opt_position_filename = ""; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { opt_robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--read" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--read" && i + 1 < argc) { opt_position_filename = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Move Panda robot to a position specified from a file." << std::endl; std::cout << argv[0] << " [--ip ] [--read ] [--help] [-h]\n" - << std::endl; + << std::endl; std::cout << "Example:\n" << argv[0] << " --ip 192.168.100.1 --read position.pos\n" << std::endl; return EXIT_SUCCESS; @@ -72,7 +79,7 @@ int main(int argc, char **argv) } if (!vpIoTools::checkFilename(opt_position_filename)) { std::cout << "\nError: position filename \"" << opt_position_filename << "\" given as input doesn't exist. " - << std::endl; + << std::endl; std::cout << "Call \"" << argv[0] << " --help\" to get usage" << std::endl; return EXIT_FAILURE; } @@ -83,18 +90,21 @@ int main(int argc, char **argv) robot.connect(opt_robot_ip); robot.move(opt_position_filename); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " - << std::endl; + << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " + << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/example/servo-franka/frankaSavePosition.cpp b/example/servo-franka/frankaSavePosition.cpp index a9ea627981..f10dbbbeba 100644 --- a/example/servo-franka/frankaSavePosition.cpp +++ b/example/servo-franka/frankaSavePosition.cpp @@ -40,25 +40,31 @@ #include +#include #include #if defined(VISP_HAVE_FRANKA) int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string opt_robot_ip = "192.168.1.1"; std::string opt_position_filename = "position.pos"; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { opt_robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--save" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--save" && i + 1 < argc) { opt_position_filename = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Save Panda robot position in a file." << std::endl; std::cout << "Usage:\n" << std::endl; std::cout << argv[0] << " [--ip ] [--save ] [--help] [-h]\n" - << std::endl; + << std::endl; std::cout << "Example:\n" << argv[0] << " --ip 192.168.100.1 --save position.pos\n" << std::endl; return EXIT_SUCCESS; @@ -75,18 +81,21 @@ int main(int argc, char **argv) robot.savePosFile(opt_position_filename, q); std::cout << "Robot position saved in \"" << opt_position_filename << "\"" << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " - << std::endl; + << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " + << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/example/servo-franka/servoFrankaIBVS.cpp b/example/servo-franka/servoFrankaIBVS.cpp index ebc5433d64..b255252a3d 100644 --- a/example/servo-franka/servoFrankaIBVS.cpp +++ b/example/servo-franka/servoFrankaIBVS.cpp @@ -62,6 +62,7 @@ #include #include +#include #include #include #include @@ -76,6 +77,10 @@ #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) { diff --git a/example/servo-franka/servoFrankaPBVS.cpp b/example/servo-franka/servoFrankaPBVS.cpp index d758747fbf..2f79bd7f74 100644 --- a/example/servo-franka/servoFrankaPBVS.cpp +++ b/example/servo-franka/servoFrankaPBVS.cpp @@ -59,6 +59,7 @@ #include #include +#include #include #include #include @@ -73,6 +74,10 @@ #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) { diff --git a/example/servo-kinova/servoKinovaJacoCart.cpp b/example/servo-kinova/servoKinovaJacoCart.cpp index deb8af0803..bd1f1a75b0 100644 --- a/example/servo-kinova/servoKinovaJacoCart.cpp +++ b/example/servo-kinova/servoKinovaJacoCart.cpp @@ -48,6 +48,10 @@ int main(int argc, char *argv[]) { #ifdef VISP_HAVE_JACOSDK +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::string opt_plugin_path = "./"; vpRobotKinova::CommandLayer opt_command_layer = vpRobotKinova::CMD_LAYER_UNSET; bool opt_verbose = false; @@ -61,44 +65,49 @@ int main(int argc, char *argv[]) if ((std::string(argv[i]) == "--command_layer" || std::string(argv[i]) == "-l") && i + 1 < argc) { if (std::string(argv[i + 1]) == "usb") { opt_command_layer = vpRobotKinova::CMD_LAYER_USB; - } else if (std::string(argv[i + 1]) == "ethernet") { + } + else if (std::string(argv[i + 1]) == "ethernet") { opt_command_layer = vpRobotKinova::CMD_LAYER_ETHERNET; - } else { + } + else { opt_command_layer = vpRobotKinova::CMD_LAYER_UNSET; } - } else if (std::string(argv[i]) == "--dof") { + } + else if (std::string(argv[i]) == "--dof") { opt_dof = static_cast(std::atoi(argv[i + 1])); - } else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { + } + else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { opt_verbose = true; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "SYNOPSYS" << std::endl - << " " << argv[0] << " [--plugin ] [--command_layer ] [--dof <4,6,7>] " - << "[--verbose] [--help] [-v] [-h]\n" - << std::endl; + << " " << argv[0] << " [--plugin ] [--command_layer ] [--dof <4,6,7>] " + << "[--verbose] [--help] [-v] [-h]\n" + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --plugin " << std::endl - << " Path to Jaco SDK .so or .dll plugin location. Default: \"./\"." << std::endl - << std::endl - << " --command_layer , -l " << std::endl - << " Command layer name, either \"usb\" or \"ethernet\"." << std::endl - << std::endl - << " --dof" << std::endl - << " Degrees of freedom. Possible values are 4, 6 or 7. Default value: 6." << std::endl - << std::endl - << " --verbose, -v" << std::endl - << " Enable verbose mode to print addition information." << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --plugin " << std::endl + << " Path to Jaco SDK .so or .dll plugin location. Default: \"./\"." << std::endl + << std::endl + << " --command_layer , -l " << std::endl + << " Command layer name, either \"usb\" or \"ethernet\"." << std::endl + << std::endl + << " --dof" << std::endl + << " Degrees of freedom. Possible values are 4, 6 or 7. Default value: 6." << std::endl + << std::endl + << " --verbose, -v" << std::endl + << " Enable verbose mode to print addition information." << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "EXAMPLE" << std::endl #ifdef __linux__ - << " " << argv[0] << " --plugin /opt/JACO-SDK/API" + << " " << argv[0] << " --plugin /opt/JACO-SDK/API" #elif _WIN32 - << " " << argv[0] << " --plugin \"C:\\Program Files(x86)\\JACO - SDK\\API\\x64\"" + << " " << argv[0] << " --plugin \"C:\\Program Files(x86)\\JACO - SDK\\API\\x64\"" #endif - << " --command_layer usb" << std::endl - << std::endl; + << " --command_layer usb" << std::endl + << std::endl; return EXIT_SUCCESS; } @@ -156,7 +165,8 @@ int main(int argc, char *argv[]) // Move back to home position robot.setPosition(vpRobot::END_EFFECTOR_FRAME, p); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch exception: " << e.getStringMessage() << std::endl; } diff --git a/example/servo-kinova/servoKinovaJacoJoint.cpp b/example/servo-kinova/servoKinovaJacoJoint.cpp index 81c27d559e..77a2a6a467 100644 --- a/example/servo-kinova/servoKinovaJacoJoint.cpp +++ b/example/servo-kinova/servoKinovaJacoJoint.cpp @@ -48,6 +48,10 @@ int main(int argc, char *argv[]) { #ifdef VISP_HAVE_JACOSDK +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::string opt_plugin_path = "./"; vpRobotKinova::CommandLayer opt_command_layer = vpRobotKinova::CMD_LAYER_UNSET; bool opt_verbose = false; @@ -61,44 +65,49 @@ int main(int argc, char *argv[]) if ((std::string(argv[i]) == "--command_layer" || std::string(argv[i]) == "-l") && i + 1 < argc) { if (std::string(argv[i + 1]) == "usb") { opt_command_layer = vpRobotKinova::CMD_LAYER_USB; - } else if (std::string(argv[i + 1]) == "ethernet") { + } + else if (std::string(argv[i + 1]) == "ethernet") { opt_command_layer = vpRobotKinova::CMD_LAYER_ETHERNET; - } else { + } + else { opt_command_layer = vpRobotKinova::CMD_LAYER_UNSET; } - } else if (std::string(argv[i]) == "--dof") { + } + else if (std::string(argv[i]) == "--dof") { opt_dof = static_cast(std::atoi(argv[i + 1])); - } else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { + } + else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") { opt_verbose = true; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "SYNOPSYS" << std::endl - << " " << argv[0] << " [--plugin ] [--command_layer ] [--dof <4,6,7>] " - << "[--verbose] [--help] [-v] [-h]\n" - << std::endl; + << " " << argv[0] << " [--plugin ] [--command_layer ] [--dof <4,6,7>] " + << "[--verbose] [--help] [-v] [-h]\n" + << std::endl; std::cout << "DESCRIPTION" << std::endl - << " --plugin " << std::endl - << " Path to Jaco SDK .so or .dll plugin location. Default: \"./\"." << std::endl - << std::endl - << " --command_layer , -l " << std::endl - << " Command layer name, either \"usb\" or \"ethernet\"." << std::endl - << std::endl - << " --dof" << std::endl - << " Degrees of freedom. Possible values are 4, 6 or 7. Default value: 6." << std::endl - << std::endl - << " --verbose, -v" << std::endl - << " Enable verbose mode to print addition information." << std::endl - << std::endl - << " --help, -h" << std::endl - << " Print this helper message." << std::endl - << std::endl; + << " --plugin " << std::endl + << " Path to Jaco SDK .so or .dll plugin location. Default: \"./\"." << std::endl + << std::endl + << " --command_layer , -l " << std::endl + << " Command layer name, either \"usb\" or \"ethernet\"." << std::endl + << std::endl + << " --dof" << std::endl + << " Degrees of freedom. Possible values are 4, 6 or 7. Default value: 6." << std::endl + << std::endl + << " --verbose, -v" << std::endl + << " Enable verbose mode to print addition information." << std::endl + << std::endl + << " --help, -h" << std::endl + << " Print this helper message." << std::endl + << std::endl; std::cout << "EXAMPLE" << std::endl #ifdef __linux__ - << " " << argv[0] << " --plugin /opt/JACO-SDK/API" + << " " << argv[0] << " --plugin /opt/JACO-SDK/API" #elif _WIN32 - << " " << argv[0] << " --plugin \"C:\\Program Files(x86)\\JACO - SDK\\API\\x64\"" + << " " << argv[0] << " --plugin \"C:\\Program Files(x86)\\JACO - SDK\\API\\x64\"" #endif - << " --command_layer usb" << std::endl - << std::endl; + << " --command_layer usb" << std::endl + << std::endl; return EXIT_SUCCESS; } @@ -155,9 +164,10 @@ int main(int argc, char *argv[]) // Move back to home position robot.setPosition(vpRobot::JOINT_STATE, q); - } catch (const vpException &e) { - std::cout << "Catch exception: " << e.getStringMessage() << std::endl; } + catch (const vpException &e) { + std::cout << "Catch exception: " << e.getStringMessage() << std::endl; +} std::cout << "The end" << std::endl; return EXIT_SUCCESS; diff --git a/example/servo-pioneer/movePioneer.cpp b/example/servo-pioneer/movePioneer.cpp index 65c0707534..a7e97f9f78 100644 --- a/example/servo-pioneer/movePioneer.cpp +++ b/example/servo-pioneer/movePioneer.cpp @@ -43,8 +43,8 @@ int main() { std::cout << "\nThis example requires Aria 3rd party library. You should " - "install it.\n" - << std::endl; + "install it.\n" + << std::endl; return EXIT_SUCCESS; } @@ -64,13 +64,17 @@ int main() */ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { std::cout << "\nWARNING: this program does no sensing or avoiding of " - "obstacles, \n" - "the robot WILL collide with any objects in the way! Make sure " - "the \n" - "robot has approximately 3 meters of free space on all sides.\n" - << std::endl; + "obstacles, \n" + "the robot WILL collide with any objects in the way! Make sure " + "the \n" + "robot has approximately 3 meters of free space on all sides.\n" + << std::endl; vpRobotPioneer robot; @@ -138,7 +142,8 @@ int main(int argc, char **argv) // exit ArLog::log(ArLog::Normal, "simpleMotionCommands: Exiting."); 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/example/servo-pioneer/servoPioneerPanSegment3D.cpp b/example/servo-pioneer/servoPioneerPanSegment3D.cpp index e85c553c72..c9e0bbccb9 100644 --- a/example/servo-pioneer/servoPioneerPanSegment3D.cpp +++ b/example/servo-pioneer/servoPioneerPanSegment3D.cpp @@ -80,6 +80,10 @@ #if defined(VISP_HAVE_PIONEER) && defined(VISP_HAVE_BICLOPS) int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + #if defined(VISP_HAVE_DC1394) || defined(VISP_HAVE_V4L2) || defined(VISP_HAVE_CMU1394) #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) try { @@ -266,7 +270,7 @@ int main(int argc, char **argv) // Use here a feature segment builder vpFeatureSegment s_segment(normalized), - s_segment_d(normalized); // From the segment feature we use only alpha + s_segment_d(normalized); // From the segment feature we use only alpha vpFeatureBuilder::create(s_segment, cam, dot[0], dot[1]); s_segment.setZ1(Z[0]); s_segment.setZ2(Z[1]); @@ -378,7 +382,7 @@ int main(int argc, char **argv) v_biclops[1] = 0; std::cout << "Send velocity to the pionner: " << v_pioneer[0] << " m/s " << vpMath::deg(v_pioneer[1]) - << " deg/s" << std::endl; + << " deg/s" << std::endl; std::cout << "Send velocity to the Biclops head: " << vpMath::deg(v_biclops[0]) << " deg/s" << std::endl; pioneer.setVelocity(vpRobot::REFERENCE_FRAME, v_pioneer); @@ -397,7 +401,8 @@ int main(int argc, char **argv) iter++; // break; } - } catch (...) { + } + catch (...) { } #ifdef USE_REAL_ROBOT @@ -411,7 +416,8 @@ int main(int argc, char **argv) // Kill the servo task task.print(); 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/example/servo-pioneer/servoPioneerPoint2DDepth.cpp b/example/servo-pioneer/servoPioneerPoint2DDepth.cpp index f263086b6f..d6427e9ed9 100644 --- a/example/servo-pioneer/servoPioneerPoint2DDepth.cpp +++ b/example/servo-pioneer/servoPioneerPoint2DDepth.cpp @@ -93,6 +93,10 @@ #ifdef TEST_COULD_BE_ACHIEVED int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; // Create a gray level image container double depth = 1.; diff --git a/example/servo-pioneer/servoPioneerPoint2DDepthWithoutVpServo.cpp b/example/servo-pioneer/servoPioneerPoint2DDepthWithoutVpServo.cpp index 212fd073fe..0cd8ac0d8f 100644 --- a/example/servo-pioneer/servoPioneerPoint2DDepthWithoutVpServo.cpp +++ b/example/servo-pioneer/servoPioneerPoint2DDepthWithoutVpServo.cpp @@ -91,6 +91,10 @@ #ifdef TEST_COULD_BE_ACHIEVED int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; // Create a gray level image container double depth = 1.; diff --git a/example/servo-pioneer/sonarPioneerReader.cpp b/example/servo-pioneer/sonarPioneerReader.cpp index 048b9f610a..8b093c7ed2 100644 --- a/example/servo-pioneer/sonarPioneerReader.cpp +++ b/example/servo-pioneer/sonarPioneerReader.cpp @@ -49,13 +49,17 @@ int main() { std::cout << "\nThis example requires Aria 3rd party library. You should " - "install it.\n" - << std::endl; + "install it.\n" + << std::endl; return EXIT_SUCCESS; } #else +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + ArSonarDevice sonar; vpRobotPioneer *robot; #if defined(VISP_HAVE_X11) @@ -290,7 +294,8 @@ int main(int argc, char **argv) try { // Create the dirname vpIoTools::makeDirectory(opath); - } catch (...) { + } + catch (...) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; return EXIT_FAILURE; @@ -341,7 +346,8 @@ int main(int argc, char **argv) // exit ArLog::log(ArLog::Normal, "simpleMotionCommands: Exiting."); 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/example/servo-pixhawk/sendMocapToPixhawk.cpp b/example/servo-pixhawk/sendMocapToPixhawk.cpp index e646a8599b..6e9d666ad8 100644 --- a/example/servo-pixhawk/sendMocapToPixhawk.cpp +++ b/example/servo-pixhawk/sendMocapToPixhawk.cpp @@ -58,6 +58,10 @@ using std::chrono::seconds; using std::this_thread::sleep_for; +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + // ------------------------------------------------------------------------------ // Modifications Qualisys // ------------------------------------------------------------------------------ diff --git a/example/servo-pixhawk/servoPixhawkDroneIBVS.cpp b/example/servo-pixhawk/servoPixhawkDroneIBVS.cpp index 9e319c4b52..6c93bfd933 100644 --- a/example/servo-pixhawk/servoPixhawkDroneIBVS.cpp +++ b/example/servo-pixhawk/servoPixhawkDroneIBVS.cpp @@ -69,6 +69,10 @@ // Comment next line to disable sending commands to the robot #define CONTROL_UAV +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool compareImagePoint(std::pair p1, std::pair p2) { return (p1.second.get_v() < p2.second.get_v()); diff --git a/example/servo-pololu-ptu/CMakeLists.txt b/example/servo-pololu-ptu/CMakeLists.txt index ec785de8d1..913e3097b8 100644 --- a/example/servo-pololu-ptu/CMakeLists.txt +++ b/example/servo-pololu-ptu/CMakeLists.txt @@ -57,6 +57,7 @@ if(VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-ignored-qualifiers") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-compare") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") visp_set_source_file_compile_flag(servoPololuPtuPoint2DJointVelocity.cpp ${CXX_FLAGS_MUTE_WARNINGS}) endif() diff --git a/example/servo-pololu-ptu/servoPololuPtuPoint2DJointVelocity.cpp b/example/servo-pololu-ptu/servoPololuPtuPoint2DJointVelocity.cpp index 6e7f3f033e..af6f443a9d 100644 --- a/example/servo-pololu-ptu/servoPololuPtuPoint2DJointVelocity.cpp +++ b/example/servo-pololu-ptu/servoPololuPtuPoint2DJointVelocity.cpp @@ -98,6 +98,10 @@ void usage(const char **argv, int error, const std::string &device, int baudrate int main(int argc, const char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + #ifdef _WIN32 std::string opt_device = "COM4"; #else diff --git a/example/servo-ptu46/movePtu46.cpp b/example/servo-ptu46/movePtu46.cpp index 1d201dc43e..7f8b5b2ac7 100644 --- a/example/servo-ptu46/movePtu46.cpp +++ b/example/servo-ptu46/movePtu46.cpp @@ -59,6 +59,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpRobotPtu46 robot; vpColVector q(2); @@ -83,21 +87,21 @@ int main() vpColVector qdot(2); robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL); #if 0 - qdot = 0 ; - qdot[0] = vpMath::rad(10) ; - qdot[1] = vpMath::rad(10) ; - vpCTRACE << "Set camera frame velocity " << qdot.t() ; + qdot = 0; + qdot[0] = vpMath::rad(10); + qdot[1] = vpMath::rad(10); + vpCTRACE << "Set camera frame velocity " << qdot.t(); - robot.setVelocity(vpRobot::CAMERA_FRAME, qdot) ; - sleep(2) ; + robot.setVelocity(vpRobot::CAMERA_FRAME, qdot); + sleep(2); - qdot = 0 ; - qdot[0] = vpMath::rad(-10) ; - qdot[1] = vpMath::rad(-10) ; + qdot = 0; + qdot[0] = vpMath::rad(-10); + qdot[1] = vpMath::rad(-10); - vpCTRACE << "Set camera frame velocity " << qdot.t() ; - robot.setVelocity(vpRobot::CAMERA_FRAME, qdot) ; - sleep(2) ; + vpCTRACE << "Set camera frame velocity " << qdot.t(); + robot.setVelocity(vpRobot::CAMERA_FRAME, qdot); + sleep(2); #endif qdot = 0; @@ -114,7 +118,8 @@ int main() vpCTRACE << "Set articular frame velocity " << qdot.t(); robot.setVelocity(vpRobot::ARTICULAR_FRAME, qdot); sleep(2); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Sorry PtU46 not available. Got exception: " << e << std::endl; return EXIT_FAILURE } diff --git a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp index 577261c02b..a10d201ba4 100644 --- a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp +++ b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp @@ -95,6 +95,10 @@ void signalCtrC(int signumber) int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::cout << std::endl; std::cout << "-------------------------------------------------------" << std::endl; std::cout << " Test program for vpServo " << std::endl; diff --git a/example/servo-universal-robots/CMakeLists.txt b/example/servo-universal-robots/CMakeLists.txt index 2e702d50db..d9a2acc0a8 100644 --- a/example/servo-universal-robots/CMakeLists.txt +++ b/example/servo-universal-robots/CMakeLists.txt @@ -69,6 +69,7 @@ if(VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-compare") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-function") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") endif() visp_set_source_file_compile_flag(servoUniversalRobotsIBVS.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/example/servo-universal-robots/UniversalRobotsMoveToPosition.cpp b/example/servo-universal-robots/UniversalRobotsMoveToPosition.cpp index 4cb3808e1f..99ace5c775 100644 --- a/example/servo-universal-robots/UniversalRobotsMoveToPosition.cpp +++ b/example/servo-universal-robots/UniversalRobotsMoveToPosition.cpp @@ -49,6 +49,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string opt_robot_ip = "192.168.0.100"; std::string opt_position_filename = ""; diff --git a/example/servo-universal-robots/UniversalRobotsSavePosition.cpp b/example/servo-universal-robots/UniversalRobotsSavePosition.cpp index 851e82f532..02c3f72eed 100644 --- a/example/servo-universal-robots/UniversalRobotsSavePosition.cpp +++ b/example/servo-universal-robots/UniversalRobotsSavePosition.cpp @@ -48,6 +48,10 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::string opt_robot_ip = "192.168.0.100"; std::string opt_position_filename = "position.pos"; diff --git a/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp b/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp index 69e0f23a00..bc347cf85b 100644 --- a/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp +++ b/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp @@ -59,6 +59,7 @@ #include #include +#include #include #include #include @@ -73,6 +74,10 @@ #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) { diff --git a/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp b/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp index efdd08f9fb..7205eee427 100644 --- a/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp +++ b/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp @@ -56,6 +56,7 @@ #include #include +#include #include #include #include @@ -70,6 +71,10 @@ #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void display_point_trajectory(const vpImage &I, const std::vector &vip, std::vector *traj_vip) { diff --git a/example/servo-viper650/servoViper650FourPoints2DArtVelocityLs_cur.cpp b/example/servo-viper650/servoViper650FourPoints2DArtVelocityLs_cur.cpp index 414b834aff..e8d0dbaaa2 100644 --- a/example/servo-viper650/servoViper650FourPoints2DArtVelocityLs_cur.cpp +++ b/example/servo-viper650/servoViper650FourPoints2DArtVelocityLs_cur.cpp @@ -75,6 +75,10 @@ #define L 0.05 // to deal with a 10cm by 10cm square +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Compute the pose \e cMo from the 3D coordinates of the points \e point and @@ -111,7 +115,8 @@ void compute_pose(std::vector &point, std::vector &dot, vpCamer if (init == true) { pose.computePose(vpPose::DEMENTHON_LAGRANGE_VIRTUAL_VS, cMo); - } else { + } + else { pose.computePose(vpPose::VIRTUAL_VS, cMo); } } @@ -137,7 +142,8 @@ int main() try { // Create the dirname vpIoTools::makeDirectory(logdirname); - } catch (...) { + } + catch (...) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << logdirname << std::endl; return EXIT_FAILURE; @@ -274,7 +280,8 @@ int main() vpImagePoint cog = dot[i].getCog(); vpDisplay::displayCross(I, cog, 10, vpColor::green); } - } catch (...) { + } + catch (...) { std::cout << "Error detected while tracking visual features.." << std::endl; break; } @@ -355,7 +362,8 @@ int main() task.print(); flog.close(); // Close the log file return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { flog.close(); // Close the log file std::cout << "Catched an exception: " << e.getMessage() << std::endl; return EXIT_FAILURE; diff --git a/example/servo-viper650/servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp b/example/servo-viper650/servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp index fc24418c70..02a11aba34 100644 --- a/example/servo-viper650/servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp +++ b/example/servo-viper650/servoViper650FourPoints2DCamVelocityLs_cur-SR300.cpp @@ -78,6 +78,10 @@ #define L 0.05 // to deal with a 10cm by 10cm square +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Compute the pose \e cMo from the 3D coordinates of the points \e point and @@ -114,7 +118,8 @@ void compute_pose(std::vector &point, std::vector &dot, vpCamer if (init == true) { pose.computePose(vpPose::DEMENTHON_LAGRANGE_VIRTUAL_VS, cMo); - } else { + } + else { pose.computePose(vpPose::VIRTUAL_VS, cMo); } } @@ -140,7 +145,8 @@ int main() try { // Create the dirname vpIoTools::makeDirectory(logdirname); - } catch (...) { + } + catch (...) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << logdirname << std::endl; return EXIT_FAILURE; @@ -178,7 +184,7 @@ int main() // Update camera parameters vpCameraParameters cam = - g.getCameraParameters(rs::stream::color, vpCameraParameters::perspectiveProjWithDistortion); + g.getCameraParameters(rs::stream::color, vpCameraParameters::perspectiveProjWithDistortion); std::cout << "Camera intrinsic parameters: \n" << cam << std::endl; g.acquire(I); @@ -269,7 +275,8 @@ int main() vpImagePoint cog = dot[i].getCog(); vpDisplay::displayCross(I, cog, 10, vpColor::green); } - } catch (...) { + } + catch (...) { std::cout << "Error detected while tracking visual features.." << std::endl; break; } @@ -343,7 +350,8 @@ int main() task.print(); flog.close(); // Close the log file return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { flog.close(); // Close the log file std::cout << "Catch an exception: " << e.getMessage() << std::endl; return EXIT_FAILURE; diff --git a/example/servo-viper650/servoViper650FourPoints2DCamVelocityLs_cur.cpp b/example/servo-viper650/servoViper650FourPoints2DCamVelocityLs_cur.cpp index b0eee66934..92127252a0 100644 --- a/example/servo-viper650/servoViper650FourPoints2DCamVelocityLs_cur.cpp +++ b/example/servo-viper650/servoViper650FourPoints2DCamVelocityLs_cur.cpp @@ -76,6 +76,10 @@ #define L 0.05 // to deal with a 10cm by 10cm square +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Compute the pose \e cMo from the 3D coordinates of the points \e point and @@ -112,7 +116,8 @@ void compute_pose(std::vector &point, std::vector &dot, vpCamer if (init == true) { pose.computePose(vpPose::DEMENTHON_LAGRANGE_VIRTUAL_VS, cMo); - } else { + } + else { pose.computePose(vpPose::VIRTUAL_VS, cMo); } } @@ -138,7 +143,8 @@ int main() try { // Create the dirname vpIoTools::makeDirectory(logdirname); - } catch (...) { + } + catch (...) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << logdirname << std::endl; return EXIT_FAILURE; @@ -264,7 +270,8 @@ int main() vpImagePoint cog = dot[i].getCog(); vpDisplay::displayCross(I, cog, 10, vpColor::green); } - } catch (...) { + } + catch (...) { std::cout << "Error detected while tracking visual features.." << std::endl; break; } @@ -340,7 +347,8 @@ int main() task.print(); flog.close(); // Close the log file return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { flog.close(); // Close the log file std::cout << "Catched an exception: " << e.getMessage() << std::endl; return EXIT_FAILURE; diff --git a/example/servo-viper650/servoViper650Point2DCamVelocity.cpp b/example/servo-viper650/servoViper650Point2DCamVelocity.cpp index 52f4af6c6e..4ff6c3993a 100644 --- a/example/servo-viper650/servoViper650Point2DCamVelocity.cpp +++ b/example/servo-viper650/servoViper650Point2DCamVelocity.cpp @@ -75,6 +75,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed camera velocities (m/s, rad/s) to achieve the task diff --git a/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_cur.cpp b/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_cur.cpp index d58d2e1834..b02fd2b47f 100644 --- a/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_cur.cpp +++ b/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_cur.cpp @@ -75,6 +75,10 @@ #define L 0.05 // to deal with a 10cm by 10cm square +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Compute the pose \e cMo from the 3D coordinates of the points \e point and diff --git a/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_des.cpp b/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_des.cpp index 2666b97362..e2f684e637 100644 --- a/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_des.cpp +++ b/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_des.cpp @@ -75,6 +75,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed joint velocities (m/s, rad/s) to achieve the task diff --git a/example/servo-viper850/servoViper850FourPoints2DCamVelocityLs_cur.cpp b/example/servo-viper850/servoViper850FourPoints2DCamVelocityLs_cur.cpp index 047ad2e650..9021648803 100644 --- a/example/servo-viper850/servoViper850FourPoints2DCamVelocityLs_cur.cpp +++ b/example/servo-viper850/servoViper850FourPoints2DCamVelocityLs_cur.cpp @@ -76,6 +76,10 @@ #define L 0.05 // to deal with a 10cm by 10cm square +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Compute the pose \e cMo from the 3D coordinates of the points \e point and diff --git a/example/servo-viper850/servoViper850FourPointsKinect.cpp b/example/servo-viper850/servoViper850FourPointsKinect.cpp index a5779dbaaf..3ff87e68b3 100644 --- a/example/servo-viper850/servoViper850FourPointsKinect.cpp +++ b/example/servo-viper850/servoViper850FourPointsKinect.cpp @@ -80,6 +80,10 @@ #include #define L 0.05 // to deal with a 10cm by 10cm square +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Compute the pose \e cMo from the 3D coordinates of the points \e point and diff --git a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp index d5a15601e5..701a63b87d 100644 --- a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp +++ b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp @@ -78,6 +78,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpRobotViper850 robot; diff --git a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp index b1d9ec058b..abba0b997a 100644 --- a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp +++ b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp @@ -75,6 +75,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpRobotViper850 robot; diff --git a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-large.cpp b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-large.cpp index 360b7376b9..1a341d4285 100644 --- a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-large.cpp +++ b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-large.cpp @@ -75,6 +75,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpRobotViper850 robot; diff --git a/example/servo-viper850/servoViper850Point2DArtVelocity.cpp b/example/servo-viper850/servoViper850Point2DArtVelocity.cpp index ae290dd50d..9ad92b46f8 100644 --- a/example/servo-viper850/servoViper850Point2DArtVelocity.cpp +++ b/example/servo-viper850/servoViper850Point2DArtVelocity.cpp @@ -78,6 +78,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed joint velocities (m/s, rad/s) to achieve the task diff --git a/example/servo-viper850/servoViper850Point2DCamVelocity.cpp b/example/servo-viper850/servoViper850Point2DCamVelocity.cpp index 3e7f8c9a6e..f71aec8334 100644 --- a/example/servo-viper850/servoViper850Point2DCamVelocity.cpp +++ b/example/servo-viper850/servoViper850Point2DCamVelocity.cpp @@ -77,6 +77,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed joint velocities (m/s, rad/s) to achieve the task diff --git a/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp b/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp index 4ffd794967..f1b7ae735f 100644 --- a/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp +++ b/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp @@ -80,6 +80,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + // Log file creation in /tmp/$USERNAME/log.dat // This file contains by line: // - the 6 computed joint velocities (m/s, rad/s) to achieve the task diff --git a/example/tools/histogram.cpp b/example/tools/histogram.cpp index df3923794a..8d8e364b1a 100644 --- a/example/tools/histogram.cpp +++ b/example/tools/histogram.cpp @@ -40,6 +40,7 @@ \brief Histogram manipulation. */ +#include #include #include #include @@ -55,6 +56,10 @@ // List of allowed command line options #define GETOPTARGS "i:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! \example histogram.cpp @@ -84,7 +89,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n\ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -207,7 +212,8 @@ int main(int argc, const char **argv) try { // Create the dirname vpIoTools::makeDirectory(dirname); - } catch (...) { + } + catch (...) { usage(argv[0], nullptr, ipath, opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << dirname << std::endl; @@ -222,8 +228,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; } } @@ -232,9 +238,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, 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; } @@ -300,7 +306,8 @@ int main(int argc, const char **argv) nbpeaks = h.getPeaks(distance, peak1, peak2); if (nbpeaks != 2) { std::cout << "Not a bimodal histogram..." << std::endl; - } else { + } + else { vpTRACE("Bimodal histogram: main peak1: %d-%d second peak2: %d-%d", peak1.getLevel(), peak1.getValue(), peak2.getLevel(), peak2.getValue()); } @@ -309,7 +316,8 @@ int main(int argc, const char **argv) vpHistogramValey valey; if (h.getValey(peak1, peak2, valey) == false) { vpTRACE("No valey found..."); - } else { + } + else { vpTRACE("Valey: %d-%d", valey.getLevel(), valey.getValue()); } @@ -320,13 +328,16 @@ int main(int argc, const char **argv) unsigned ret = h.getValey(distance, peak1, valeyl, valeyr); if (ret == 0x00) { vpTRACE("No left and right valey for peak %d-%d...", peak1.getLevel(), peak1.getValue()); - } else if (ret == 0x10) { + } + else if (ret == 0x10) { vpTRACE("No right valey for peak %d-%d...", peak1.getLevel(), peak1.getValue()); vpTRACE("Left valey: %d-%d", valeyl.getLevel(), valeyl.getValue()); - } else if (ret == 0x01) { + } + else if (ret == 0x01) { vpTRACE("No left valey for peak %d-%d...", peak1.getLevel(), peak1.getValue()); vpTRACE("Right valey: %d-%d", valeyr.getLevel(), valeyr.getValue()); - } else if (ret == 0x11) { + } + else if (ret == 0x11) { vpTRACE("Left valey: %d-%d", valeyl.getLevel(), valeyl.getValue()); vpTRACE("Right valey: %d-%d", valeyr.getLevel(), valeyr.getValue()); } @@ -336,13 +347,16 @@ int main(int argc, const char **argv) unsigned ret = h.getValey(distance, peak2, valeyl, valeyr); if (ret == 0x00) { vpTRACE("No left and right valey for peak %d-%d...", peak2.getLevel(), peak2.getValue()); - } else if (ret == 0x10) { + } + else if (ret == 0x10) { vpTRACE("No right valey for peak %d-%d...", peak2.getLevel(), peak2.getValue()); vpTRACE("Left valey: %d-%d", valeyl.getLevel(), valeyl.getValue()); - } else if (ret == 0x01) { + } + else if (ret == 0x01) { vpTRACE("No left valey for peak %d-%d...", peak2.getLevel(), peak2.getValue()); vpTRACE("Right valey: %d-%d", valeyr.getLevel(), valeyr.getValue()); - } else if (ret == 0x11) { + } + else if (ret == 0x11) { vpTRACE("Left valey: %d-%d", valeyl.getLevel(), valeyl.getValue()); vpTRACE("Right valey: %d-%d", valeyr.getLevel(), valeyr.getValue()); } @@ -354,12 +368,14 @@ int main(int argc, const char **argv) vpHistogramPeak peakl, peakr; if (h.getPeaks(distance, peakl, peakr, valey) == false) { std::cout << "Not a bimodal histogram..." << std::endl; - } else { + } + else { vpTRACE("Bimodal histogram: valey %d-%d for peakl: %d-%d peakr: %d-%d", valey.getLevel(), valey.getValue(), peakl.getLevel(), peakl.getValue(), peakr.getLevel(), peakr.getValue()); } 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/example/tools/keyboard.cpp b/example/tools/keyboard.cpp index f240607785..14be77d7cd 100644 --- a/example/tools/keyboard.cpp +++ b/example/tools/keyboard.cpp @@ -48,6 +48,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::cout << "Push some characters on the keyboard..." << std::endl; printf("Hit 'q' or 'Q' to stop the loop ...\n"); vpKeyboard keyboard; diff --git a/example/tools/parallelPort.cpp b/example/tools/parallelPort.cpp index d3b55d54e0..0a7f74a759 100644 --- a/example/tools/parallelPort.cpp +++ b/example/tools/parallelPort.cpp @@ -54,6 +54,10 @@ // List of allowed command line options #define GETOPTARGS "d:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/example/tools/plot2d.cpp b/example/tools/plot2d.cpp index 5a8264d0d2..8665e74b9b 100644 --- a/example/tools/plot2d.cpp +++ b/example/tools/plot2d.cpp @@ -49,6 +49,10 @@ int main() { #if defined(VISP_HAVE_DISPLAY) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpPlot plot(2, 700, 700, 100, 200, "Curves..."); @@ -106,15 +110,16 @@ int main() plot.saveData(0, "dataCos.txt", "# "); plot.saveData(1, "dataSin.txt", "# "); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } #else std::cout << "Plot functionalities are not avalaible since no display is " - "available." - << std::endl; + "available." + << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/tools/plot3d.cpp b/example/tools/plot3d.cpp index 099049111b..6cc8ba4244 100644 --- a/example/tools/plot3d.cpp +++ b/example/tools/plot3d.cpp @@ -47,6 +47,10 @@ int main() { #if defined(VISP_HAVE_DISPLAY) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { // Create a window with one graphic vpPlot plot(1); @@ -99,9 +103,10 @@ int main() y += dy; if (fabs(y) >= 1.0) zsign = -zsign; - } else { - // Tip: to allows modifying the point of view with the mouse we - // plot always the last point + } + else { + // Tip: to allows modifying the point of view with the mouse we + // plot always the last point if (plot.plot(0, 0, x, y, z * zsign) == vpMouseButton::button3) end = true; if (plot.plot(0, 1, x, -y, -z * zsign) == vpMouseButton::button3) @@ -110,14 +115,15 @@ int main() iter++; } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } #else std::cout << "Plot functionalities are not avalaible since no display is " - "available." - << std::endl; + "available." + << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/example/tracking/mbtEdgeKltTracking.cpp b/example/tracking/mbtEdgeKltTracking.cpp index baf7c281e5..121b704ccf 100644 --- a/example/tracking/mbtEdgeKltTracking.cpp +++ b/example/tracking/mbtEdgeKltTracking.cpp @@ -62,6 +62,10 @@ #define GETOPTARGS "x:m:i:n:de:chtfColwvp" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam) { #if VISP_HAVE_DATASET_VERSION >= 0x030600 @@ -325,8 +329,8 @@ int main(int argc, const char **argv) std::cerr << "Coin is not detected in ViSP. Use the .cao model instead." << std::endl; modelFile = vpIoTools::createFilePath(opt_ipath, modelFileCao); #endif - } } + } else { if (cao3DModel) { modelFile = vpIoTools::createFilePath(env_ipath, modelFileCao); @@ -338,9 +342,9 @@ int main(int argc, const char **argv) std::cerr << "Coin is not detected in ViSP. Use the .cao model instead." << std::endl; modelFile = vpIoTools::createFilePath(env_ipath, modelFileCao); #endif - } } - } + } +} if (!opt_initFile.empty()) initFile = opt_initFile; diff --git a/example/tracking/mbtEdgeTracking.cpp b/example/tracking/mbtEdgeTracking.cpp index 6f4ba9cff2..424afe0261 100644 --- a/example/tracking/mbtEdgeTracking.cpp +++ b/example/tracking/mbtEdgeTracking.cpp @@ -62,6 +62,10 @@ #define GETOPTARGS "x:m:i:n:de:chtfColwvp" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam) { #if VISP_HAVE_DATASET_VERSION >= 0x030600 diff --git a/example/tracking/mbtGenericTracking.cpp b/example/tracking/mbtGenericTracking.cpp index 1e5cce70bf..d02b9f92fa 100644 --- a/example/tracking/mbtGenericTracking.cpp +++ b/example/tracking/mbtGenericTracking.cpp @@ -62,6 +62,10 @@ #define GETOPTARGS "x:m:i:n:de:chtfColwvpT:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam) { #if VISP_HAVE_DATASET_VERSION >= 0x030600 diff --git a/example/tracking/mbtGenericTracking2.cpp b/example/tracking/mbtGenericTracking2.cpp index 2c70106c85..f2b7f6f203 100644 --- a/example/tracking/mbtGenericTracking2.cpp +++ b/example/tracking/mbtGenericTracking2.cpp @@ -62,6 +62,10 @@ #define GETOPTARGS "x:m:i:n:de:chtfColwvpT:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam) { #if VISP_HAVE_DATASET_VERSION >= 0x030600 diff --git a/example/tracking/mbtGenericTrackingDepth.cpp b/example/tracking/mbtGenericTrackingDepth.cpp index 1a37d4ab4b..129acfeb71 100644 --- a/example/tracking/mbtGenericTrackingDepth.cpp +++ b/example/tracking/mbtGenericTrackingDepth.cpp @@ -64,6 +64,10 @@ #define USE_SMALL_DATASET 1 // small depth dataset in ViSP-images +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void usage(const char *name, const char *badparam) @@ -812,7 +816,7 @@ int main(int argc, const char **argv) } frame_index++; - } + } std::cout << "\nFinal poses, c1Mo:\n" << c1Mo << "\nc2Mo:\n" << c2Mo << std::endl; std::cout << "\nComputation time, Mean: " << vpMath::getMean(time_vec) @@ -827,12 +831,12 @@ int main(int argc, const char **argv) tracker = nullptr; return EXIT_SUCCESS; - } + } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } -} + } #elif !(defined(VISP_HAVE_MODULE_MBT) && defined(VISP_HAVE_DISPLAY)) int main() diff --git a/example/tracking/mbtGenericTrackingDepthOnly.cpp b/example/tracking/mbtGenericTrackingDepthOnly.cpp index b2c07179a8..efe398fda8 100644 --- a/example/tracking/mbtGenericTrackingDepthOnly.cpp +++ b/example/tracking/mbtGenericTrackingDepthOnly.cpp @@ -64,6 +64,10 @@ #define USE_SMALL_DATASET 1 // small depth dataset in ViSP-images +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void usage(const char *name, const char *badparam) @@ -758,7 +762,7 @@ int main(int argc, const char **argv) } frame_index++; - } + } std::cout << "\nFinal poses, cMo:\n" << cMo << std::endl; std::cout << "\nComputation time, Mean: " << vpMath::getMean(time_vec) @@ -773,12 +777,12 @@ int main(int argc, const char **argv) tracker = nullptr; return EXIT_SUCCESS; - } + } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } -} + } #elif !(defined(VISP_HAVE_MODULE_MBT) && defined(VISP_HAVE_DISPLAY)) int main() diff --git a/example/tracking/mbtKltTracking.cpp b/example/tracking/mbtKltTracking.cpp index 0efab6467d..4b699827d2 100644 --- a/example/tracking/mbtKltTracking.cpp +++ b/example/tracking/mbtKltTracking.cpp @@ -61,6 +61,10 @@ #define GETOPTARGS "x:m:i:n:de:chtfolwv" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam) { #if VISP_HAVE_DATASET_VERSION >= 0x030600 @@ -575,6 +579,6 @@ int main() "this example." << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/tracking/templateTracker.cpp b/example/tracking/templateTracker.cpp index 2fec809a78..949481c5bd 100644 --- a/example/tracking/templateTracker.cpp +++ b/example/tracking/templateTracker.cpp @@ -85,8 +85,13 @@ #define GETOPTARGS "cdhi:l:Lprs:t:w:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS -typedef enum { +typedef enum +{ WARP_AFFINE, WARP_HOMOGRAPHY, WARP_HOMOGRAPHY_SL3, @@ -98,7 +103,8 @@ typedef enum { WARP_LAST } WarpType; -typedef enum { +typedef enum +{ TRACKER_SSD_ESM, TRACKER_SSD_FORWARD_ADDITIONAL, TRACKER_SSD_FORWARD_COMPOSITIONAL, @@ -305,7 +311,7 @@ bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_all usage(argv[0], nullptr, warp_type, tracker_type, last_frame, threshold_residual); std::cerr << "ERROR: " << std::endl; std::cerr << " Bad argument -t with \"tracker type\"=" << (int)tracker_type << std::endl - << std::endl; + << std::endl; return false; } if ((c == 1) || (c == -1)) { @@ -377,9 +383,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, opt_warp_type, opt_tracker_type, opt_last_frame, opt_threshold_residual); 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; } @@ -402,7 +408,8 @@ int main(int argc, const char **argv) reader.setLastFrameIndex(opt_last_frame); try { reader.open(I); - } catch (...) { + } + catch (...) { std::cout << "Cannot open sequence: " << ipath << std::endl; return EXIT_FAILURE; } @@ -553,7 +560,8 @@ int main(int argc, const char **argv) vpDisplay::displayText(I, 10, 10, "Re-init simulation", vpColor::red); vpDisplay::flush(I); tracker->initClick(I, delaunay); - } else { + } + else { std::vector v_ip; vpImagePoint ip; ip.set_ij(146, 60); @@ -611,7 +619,8 @@ int main(int argc, const char **argv) delete tracker; 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/example/tracking/trackDot.cpp b/example/tracking/trackDot.cpp index ee24e66073..1305f12461 100644 --- a/example/tracking/trackDot.cpp +++ b/example/tracking/trackDot.cpp @@ -70,6 +70,10 @@ // List of allowed command line options #define GETOPTARGS "cdf:hi:l:p:s:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -255,8 +259,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; } } @@ -265,11 +269,11 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); 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 - << " Use -p option if you want to " << std::endl - << " use personal images." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << " Use -p option if you want to " << std::endl + << " use personal images." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -315,13 +319,14 @@ int main(int argc, const char **argv) vpCTRACE << "Load: " << filename << std::endl; vpImageIo::read(I, filename); - } catch (...) { - // If an exception is thrown by vpImageIo::read() it will result in the end of the program. + } + catch (...) { + // If an exception is thrown by vpImageIo::read() it will result in the end of the program. std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot read " << filename << std::endl; if (opt_ppath.empty()) { std::cerr << " Check your -i " << ipath << " option " << std::endl - << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; + << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; } else { std::cerr << " Check your -p " << opt_ppath << " option " << std::endl; @@ -360,7 +365,8 @@ int main(int argc, const char **argv) // It uses the overlay image plane. // The default of this setting is that it is time consuming d.setGraphics(true); - } else { + } + else { d.setGraphics(false); } // we also request to compute the dot moment m00, m10, m01, m11, m20, m02 @@ -373,10 +379,11 @@ int main(int argc, const char **argv) // a right mouse click on the dot is expected std::cout << "Click on a white dot you want to track..." << std::endl; d.initTracking(I); - } else { - // dot location can also be specified explicitly in the - // initTracking method : d.initTracking(I,ip) where ip is the - // image point from which the dot is searched + } + else { + // dot location can also be specified explicitly in the + // initTracking method : d.initTracking(I,ip) where ip is the + // image point from which the dot is searched vpImagePoint ip; ip.set_u(160); ip.set_v(212); @@ -390,7 +397,8 @@ int main(int argc, const char **argv) s.str(""); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } @@ -443,7 +451,8 @@ int main(int argc, const char **argv) vpDisplay::getClick(I); } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -454,9 +463,9 @@ int main(int argc, const char **argv) int main() { std::cout << "visp_blob module or X11, GTK, GDI or OpenCV display " - "functionalities are required..." - << std::endl; + "functionalities are required..." + << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/tracking/trackDot2.cpp b/example/tracking/trackDot2.cpp index a3e0bd9f12..66bb5e507a 100644 --- a/example/tracking/trackDot2.cpp +++ b/example/tracking/trackDot2.cpp @@ -63,6 +63,10 @@ // List of allowed command line options #define GETOPTARGS "cdf:i:l:p:s:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! \example trackDot2.cpp Example of dot tracking on an image sequence using vpDot2. @@ -254,8 +258,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; } } @@ -264,11 +268,11 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); 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 - << " Use -p option if you want to " << std::endl - << " use personal images." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << " Use -p option if you want to " << std::endl + << " use personal images." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -300,7 +304,8 @@ int main(int argc, const char **argv) s.setf(std::ios::right, std::ios::adjustfield); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } @@ -314,13 +319,14 @@ int main(int argc, const char **argv) vpCTRACE << "Load: " << filename << std::endl; vpImageIo::read(I, filename); - } catch (...) { - // If an exception is thrown by vpImageIo::read() it will result in the end of the program. + } + catch (...) { + // If an exception is thrown by vpImageIo::read() it will result in the end of the program. std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot read " << filename << std::endl; if (opt_ppath.empty()) { std::cerr << " Check your -i " << ipath << " option " << std::endl - << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; + << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; } else { std::cerr << " Check your -p " << opt_ppath << " option " << std::endl; @@ -367,7 +373,8 @@ int main(int argc, const char **argv) // The default of this setting is that it is time consuming d.setGraphics(true); - } else { + } + else { d.setGraphics(false); } @@ -386,7 +393,8 @@ int main(int argc, const char **argv) if (opt_display && opt_click_allowed) { std::cout << "Click on a dot to track it." << std::endl; d.initTracking(I); - } else { + } + else { vpImagePoint ip; ip.set_u(160); ip.set_v(212); @@ -416,7 +424,8 @@ int main(int argc, const char **argv) s.str(""); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } @@ -481,7 +490,8 @@ int main(int argc, const char **argv) vpDisplay::getClick(I); } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -492,9 +502,9 @@ int main(int argc, const char **argv) int main() { std::cout << "visp_me module or X11, GTK, GDI or OpenCV display " - "functionalities are required..." - << std::endl; + "functionalities are required..." + << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/tracking/trackDot2WithAutoDetection.cpp b/example/tracking/trackDot2WithAutoDetection.cpp index 4372509e7d..b5fe2cdb0a 100644 --- a/example/tracking/trackDot2WithAutoDetection.cpp +++ b/example/tracking/trackDot2WithAutoDetection.cpp @@ -69,6 +69,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:p:f:l:s:S:G:E:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -152,8 +156,8 @@ OPTIONS: Default\n\ whereas values close to 0 show a very bad precision.\n\ 0 means the shape of dots is not tested \n\ \n", - ipath.c_str(), ext.c_str(), ppath.c_str(), ext.c_str(), first, last, step, sizePrecision, grayLevelPrecision, - ellipsoidShapePrecision); +ipath.c_str(), ext.c_str(), ppath.c_str(), ext.c_str(), first, last, step, sizePrecision, grayLevelPrecision, +ellipsoidShapePrecision); fprintf(stdout, "\ -c\n\ @@ -302,8 +306,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; } } @@ -313,11 +317,11 @@ int main(int argc, const char **argv) opt_grayLevelPrecision, opt_ellipsoidShapePrecision); 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 - << " Use -p option if you want to " << std::endl - << " use personal images." << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl + << " Use -p option if you want to " << std::endl + << " use personal images." << std::endl; return EXIT_FAILURE; } @@ -347,7 +351,8 @@ int main(int argc, const char **argv) s.setf(std::ios::right, std::ios::adjustfield); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } @@ -360,13 +365,14 @@ int main(int argc, const char **argv) vpCTRACE << "Load: " << filename << std::endl; vpImageIo::read(I, filename); - } catch (...) { - // If an exception is thrown by vpImageIo::read() it will result in the end of the program. + } + catch (...) { + // If an exception is thrown by vpImageIo::read() it will result in the end of the program. std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot read " << filename << std::endl; if (opt_ppath.empty()) { std::cerr << " Check your -i " << ipath << " option " << std::endl - << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; + << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; } else { std::cerr << " Check your -p " << opt_ppath << " option " << std::endl; @@ -424,8 +430,9 @@ int main(int argc, const char **argv) printf(" grayLevelPrecision: %lf\n", d.getGrayLevelPrecision()); printf(" sizePrecision: %lf\n", d.getSizePrecision()); printf(" ellipsoidShapePrecision: %lf\n", d.getEllipsoidShapePrecision()); - } else { - // Set dot characteristics for the auto detection + } + else { + // Set dot characteristics for the auto detection d.setGraphics(true); d.setWidth(15.0); d.setHeight(12.0); @@ -445,7 +452,8 @@ int main(int argc, const char **argv) s.str(""); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } @@ -499,7 +507,8 @@ int main(int argc, const char **argv) } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -510,9 +519,9 @@ int main(int argc, const char **argv) int main() { std::cout << "visp_me module or X11, GTK, GDI or OpenCV display " - "functionalities are required..." - << std::endl; + "functionalities are required..." + << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/example/tracking/trackKltOpencv.cpp b/example/tracking/trackKltOpencv.cpp index 73df296ded..041515471b 100644 --- a/example/tracking/trackKltOpencv.cpp +++ b/example/tracking/trackKltOpencv.cpp @@ -63,6 +63,10 @@ // List of allowed command line options #define GETOPTARGS "cdf:i:l:p:s:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string ppath, unsigned first, unsigned last, unsigned step); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &ppath, unsigned &first, unsigned &last, @@ -262,8 +266,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; } } @@ -272,11 +276,11 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step); 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 - << " Use -p option if you want to " << std::endl - << " use personal images." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << " Use -p option if you want to " << std::endl + << " use personal images." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -326,13 +330,14 @@ int main(int argc, const char **argv) // Load a ViSP image used for the display vpImageIo::read(vpI, filename); vpImageConvert::convert(vpI, cvI); - } catch (...) { - // If an exception is thrown by vpImageIo::read() it will result in the end of the program. + } + catch (...) { + // If an exception is thrown by vpImageIo::read() it will result in the end of the program. std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot read " << filename << std::endl; if (opt_ppath.empty()) { std::cerr << " Check your -i " << ipath << " option " << std::endl - << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; + << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; } else { std::cerr << " Check your -p " << opt_ppath << " option " << std::endl; @@ -398,7 +403,8 @@ int main(int argc, const char **argv) s.str(""); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } @@ -437,7 +443,8 @@ int main(int argc, const char **argv) vpDisplay::getClick(vpI); } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -457,8 +464,8 @@ int main() int main() { std::cout << "visp_klt module or X11, GTK, GDI or OpenCV display " - "functionalities are required..." - << std::endl; -} + "functionalities are required..." + << std::endl; + } #endif diff --git a/example/tracking/trackMeCircle.cpp b/example/tracking/trackMeCircle.cpp index 7baf042c21..2597ed0538 100644 --- a/example/tracking/trackMeCircle.cpp +++ b/example/tracking/trackMeCircle.cpp @@ -70,6 +70,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath); bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_allowed, bool &display); diff --git a/example/tracking/trackMeEllipse.cpp b/example/tracking/trackMeEllipse.cpp index b9ddd05ae0..36f25fded1 100644 --- a/example/tracking/trackMeEllipse.cpp +++ b/example/tracking/trackMeEllipse.cpp @@ -71,6 +71,10 @@ // List of allowed command line options #define GETOPTARGS "Aabcdf:hi:l:p:r:s:S:t:vw:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -326,8 +330,8 @@ int main(int argc, const char **argv) // Read the command line options if (getOptions(argc, argv, opt_ipath, opt_ppath, opt_first, opt_last, opt_step, opt_click_allowed, - opt_display, opt_display_scale_auto, opt_track_circle, opt_track_arc, opt_save, - opt_me_range, opt_me_sample_step, opt_me_threshold, opt_verbose) == false) { + opt_display, opt_display_scale_auto, opt_track_circle, opt_track_arc, opt_save, + opt_me_range, opt_me_sample_step, opt_me_threshold, opt_verbose) == false) { return EXIT_FAILURE; } diff --git a/example/tracking/trackMeLine.cpp b/example/tracking/trackMeLine.cpp index 2057390cf4..5bc03dda0d 100644 --- a/example/tracking/trackMeLine.cpp +++ b/example/tracking/trackMeLine.cpp @@ -76,6 +76,10 @@ // List of allowed command line options #define GETOPTARGS "cdf:hi:l:p:s:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -247,7 +251,7 @@ int main(int argc, const char **argv) // Read the command line options if (getOptions(argc, argv, opt_ipath, opt_ppath, opt_first, opt_last, opt_step, opt_click_allowed, - opt_display) == false) { + opt_display) == false) { return EXIT_FAILURE; } diff --git a/example/tracking/trackMeNurbs.cpp b/example/tracking/trackMeNurbs.cpp index 82a7d3c3e6..eabe0ef6aa 100644 --- a/example/tracking/trackMeNurbs.cpp +++ b/example/tracking/trackMeNurbs.cpp @@ -73,6 +73,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath); bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_allowed, bool &display); @@ -344,6 +348,6 @@ int main() std::cout << "visp_me module or X11, GTK, GDI or OpenCV display " "functionalities are required..." << std::endl; -} + } #endif diff --git a/example/video/imageSequenceReader.cpp b/example/video/imageSequenceReader.cpp index a8e841bbfa..aec623acb3 100644 --- a/example/video/imageSequenceReader.cpp +++ b/example/video/imageSequenceReader.cpp @@ -43,6 +43,7 @@ Reading an image sequence using vpVideoReader class. */ +#include #include #include #include @@ -59,6 +60,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:p:f:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string ppath); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &ppath, int &first, bool &click_allowed, bool &display); diff --git a/example/video/videoReader.cpp b/example/video/videoReader.cpp index 57992dd3bc..a6893ca10c 100644 --- a/example/video/videoReader.cpp +++ b/example/video/videoReader.cpp @@ -60,6 +60,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:p:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string ppath); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &ppath, bool &click_allowed, bool &display); @@ -83,7 +87,7 @@ SYNOPSIS\n\ %s [-i ] \n\ [-h]\n\ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -212,8 +216,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; } } @@ -222,9 +226,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_ppath); 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 - << " video path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " video path where test images are located." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -239,7 +243,8 @@ int main(int argc, const char **argv) if (opt_ppath.empty()) { filename = vpIoTools::createFilePath(ipath, "video/cube.mpeg"); - } else { + } + else { filename.assign(opt_ppath); } @@ -305,7 +310,8 @@ int main(int argc, const char **argv) std::cout << "Click to exit this example" << std::endl; vpDisplay::getClick(I); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } return EXIT_SUCCESS; diff --git a/example/wireframe-simulator/wireframeSimulator.cpp b/example/wireframe-simulator/wireframeSimulator.cpp index 8638b2061c..9eb333d71b 100644 --- a/example/wireframe-simulator/wireframeSimulator.cpp +++ b/example/wireframe-simulator/wireframeSimulator.cpp @@ -42,6 +42,7 @@ #include #include +#include #include #include #include @@ -59,6 +60,10 @@ #ifdef VISP_HAVE_DISPLAY +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &display, bool &click); @@ -265,17 +270,17 @@ Create a display for each different cameras. std::cout << std::endl; std::cout << "Here are presented the effect of the basic functions of " - "the simulator" - << std::endl; + "the simulator" + << std::endl; std::cout << std::endl; if (opt_display) { if (opt_click) { std::cout << "Click on the internal view window to continue. the " - "object will move. The external cameras are fixed. The " - "main camera moves too because the homogeneous matrix " - "cMo didn't change." - << std::endl; + "object will move. The external cameras are fixed. The " + "main camera moves too because the homogeneous matrix " + "cMo didn't change." + << std::endl; vpDisplay::getClick(Iint); } vpDisplay::display(Iint); @@ -313,9 +318,9 @@ Create a display for each different cameras. } std::cout << std::endl; std::cout << "Now you can move the main external camera. Click inside " - "the corresponding window with one of the three buttons of " - "your mouse and move the pointer." - << std::endl; + "the corresponding window with one of the three buttons of " + "your mouse and move the pointer." + << std::endl; std::cout << std::endl; std::cout << "Click on the internal view window when you are finished" << std::endl; @@ -334,12 +339,13 @@ Create a display for each different cameras. std::cout << std::endl; std::cout << "You have seen the main capabilities of the simulator. " - "Other specific functionalities are available. Please " - "refers to the html documentation to access the list of all " - "functions" - << std::endl; + "Other specific functionalities are available. Please " + "refers to the html documentation to access the list of all " + "functions" + << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_SUCCESS; } @@ -348,12 +354,12 @@ Create a display for each different cameras. int main() { std::cout << "You do not have X11, or GDI (Graphical Device Interface), or GTK 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; std::cout << "- Install GDI, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; -} + } #endif diff --git a/modules/ar/include/visp3/ar/vpAR.h b/modules/ar/include/visp3/ar/vpAR.h index aa60da66bf..da0f5585c6 100644 --- a/modules/ar/include/visp3/ar/vpAR.h +++ b/modules/ar/include/visp3/ar/vpAR.h @@ -64,6 +64,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpAR @@ -143,13 +144,13 @@ class VISP_EXPORT vpAR : public vpSimulator bool background; public: - vpAR() : background(false){}; + vpAR() : background(false) { }; virtual ~vpAR(); void initInternalViewer(unsigned int width, unsigned int height, vpImageType type = grayImage); void setImage(vpImage &I); void setImage(vpImage &I); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/ar/include/visp3/ar/vpAROgre.h b/modules/ar/include/visp3/ar/vpAROgre.h index 038db61e0d..62046d5505 100644 --- a/modules/ar/include/visp3/ar/vpAROgre.h +++ b/modules/ar/include/visp3/ar/vpAROgre.h @@ -70,6 +70,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! \class vpAROgre @@ -88,10 +89,10 @@ */ class VISP_EXPORT vpAROgre : public Ogre::FrameListener, - public Ogre::WindowEventListener + public Ogre::WindowEventListener #ifdef VISP_HAVE_OIS , - public OIS::KeyListener + public OIS::KeyListener #endif { public: @@ -296,7 +297,7 @@ class VISP_EXPORT vpAROgre : public Ogre::FrameListener, * Build the 3D scene * Override this to show what you want */ - virtual void createScene(void){}; + virtual void createScene(void) { }; virtual void closeOIS(void); @@ -391,7 +392,7 @@ class VISP_EXPORT vpAROgre : public Ogre::FrameListener, std::list mOptionalResourceLocation; /** Optional resource location (used to load mesh and material) */ }; - +END_VISP_NAMESPACE #endif // VISP_HAVE_OGRE #endif diff --git a/modules/ar/include/visp3/ar/vpSimulator.h b/modules/ar/include/visp3/ar/vpSimulator.h index 512ad4e019..cf6604a11c 100644 --- a/modules/ar/include/visp3/ar/vpSimulator.h +++ b/modules/ar/include/visp3/ar/vpSimulator.h @@ -82,6 +82,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpSimulator @@ -291,6 +292,6 @@ class VISP_EXPORT vpSimulator //! get the intrinsic parameters of the camera void getCameraParameters(vpCameraParameters &cam) { cam = internalCameraParameters; } }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/ar/include/visp3/ar/vpSimulatorException.h b/modules/ar/include/visp3/ar/vpSimulatorException.h index e5a75bffe8..f494e16552 100644 --- a/modules/ar/include/visp3/ar/vpSimulatorException.h +++ b/modules/ar/include/visp3/ar/vpSimulatorException.h @@ -31,24 +31,26 @@ * Exceptions that can be emitted by the simulator classes. */ -#ifndef _vpSimulatorException_h_ -#define _vpSimulatorException_h_ - /*! * \file vpSimulatorException.h * \brief Error that can be emitted by the vpSimulator class and its derivatives */ +#ifndef _vpSimulatorException_h_ +#define _vpSimulatorException_h_ + +#include #include #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS #include /* Classe std::ostream. */ #include /* Classe string. */ +BEGIN_VISP_NAMESPACE /*! * \class vpSimulatorException * \brief Error that can be emitted by the vpSimulator class and its derivatives. - */ +*/ class VISP_EXPORT vpSimulatorException : public vpException { public: @@ -81,6 +83,6 @@ class VISP_EXPORT vpSimulatorException : public vpException */ explicit vpSimulatorException(int id); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/ar/include/visp3/ar/vpViewer.h b/modules/ar/include/visp3/ar/vpViewer.h index 35c8d45b02..4e76034a3f 100644 --- a/modules/ar/include/visp3/ar/vpViewer.h +++ b/modules/ar/include/visp3/ar/vpViewer.h @@ -33,8 +33,6 @@ * *****************************************************************************/ -#ifndef vpViewer_HH -#define vpViewer_HH /*! \file vpViewer.h @@ -47,6 +45,9 @@ */ +#ifndef vpViewer_HH +#define vpViewer_HH + #include #ifdef VISP_HAVE_COIN3D_AND_GUI @@ -94,6 +95,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpViewer \ingroup group_ar_simulator @@ -153,7 +155,7 @@ class VISP_EXPORT vpViewer : public SoXtExaminerViewer static void exitMainLoop() { SoXt::exitMainLoop(); }; #endif }; - +END_VISP_NAMESPACE #endif // VISP_HAVE_COIN3D_AND_GUI #endif diff --git a/modules/ar/src/coin-simulator/vpAR.cpp b/modules/ar/src/coin-simulator/vpAR.cpp index 42c8dc35fc..9c7c85996d 100644 --- a/modules/ar/src/coin-simulator/vpAR.cpp +++ b/modules/ar/src/coin-simulator/vpAR.cpp @@ -64,6 +64,7 @@ #include /* Groupement de noeuds (sans separation)*/ #include /* Matiere (couleur) des objets. */ +BEGIN_VISP_NAMESPACE /*! Basic Destructor that calls the kill() method of the vpSimulator class. @@ -148,8 +149,8 @@ void vpAR::setImage(vpImage &I) } } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_ar.a(vpAR.cpp.o) has no symbols -void dummy_vpAR(){}; +void dummy_vpAR() { }; #endif diff --git a/modules/ar/src/coin-simulator/vpSimulator.cpp b/modules/ar/src/coin-simulator/vpSimulator.cpp index 8d154d9931..a3d2da3227 100644 --- a/modules/ar/src/coin-simulator/vpSimulator.cpp +++ b/modules/ar/src/coin-simulator/vpSimulator.cpp @@ -71,6 +71,7 @@ #include /* Groupement de noeuds (sans separation)*/ #include /* Matiere (couleur) des objets. */ +BEGIN_VISP_NAMESPACE // Positions of all of the vertices: // static float pyramidVertexes[5][3] = { {0.33f, 0.33f, 0.f}, @@ -1002,7 +1003,7 @@ void vpSimulator::getInternalImage(vpImage &I) vpImageConvert::RGBToGrey(bufferView, I.bitmap, internal_width, internal_height, true); get = 1; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_ar.a(vpSimulator.cpp.o) has no symbols void dummy_vpSimulator() { }; diff --git a/modules/ar/src/coin-simulator/vpViewer.cpp b/modules/ar/src/coin-simulator/vpViewer.cpp index 084f4836bd..c987ceb469 100644 --- a/modules/ar/src/coin-simulator/vpViewer.cpp +++ b/modules/ar/src/coin-simulator/vpViewer.cpp @@ -48,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE #if defined(VISP_HAVE_SOWIN) vpViewer::vpViewer(HWND parent, vpSimulator *_simu, vpViewerType type) : SoWinExaminerViewer(parent, (char *)nullptr, false), viewerType(type), simu(_simu) @@ -67,7 +68,7 @@ vpViewer::vpViewer(Widget parent, vpSimulator *_simu, vpViewerType type) setAutoRedraw(false); } -vpViewer::~vpViewer() {} +vpViewer::~vpViewer() { } void vpViewer::actualRedraw(void) { @@ -231,8 +232,8 @@ SbBool vpViewer::processSoEvent(const SoEvent *const event) return SoXtExaminerViewer::processSoEvent(event); #endif } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_ar.a(vpViewer.cpp.o) has no symbols -void dummy_vpViewer(){}; +void dummy_vpViewer() { }; #endif diff --git a/modules/ar/src/ogre-simulator/vpAROgre.cpp b/modules/ar/src/ogre-simulator/vpAROgre.cpp index aa4dcf39b5..e371043efa 100644 --- a/modules/ar/src/ogre-simulator/vpAROgre.cpp +++ b/modules/ar/src/ogre-simulator/vpAROgre.cpp @@ -55,6 +55,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Constructor. @@ -73,16 +74,15 @@ vpAROgre::vpAROgre(const vpCameraParameters &cam, unsigned int width, unsigned int height, const char *resourcePath, const char *pluginsPath) : name("ViSP - Augmented Reality"), mRoot(0), mCamera(0), mSceneMgr(0), mWindow(0), mResourcePath(resourcePath), - mPluginsPath(pluginsPath), + mPluginsPath(pluginsPath), #ifdef VISP_HAVE_OIS - mInputManager(0), mKeyboard(0), + mInputManager(0), mKeyboard(0), #endif - keepOn(true), // When created no reason to stop displaying - mImageRGBA(), mImage(), mPixelBuffer(), mBackground(nullptr), mBackgroundHeight(0), mBackgroundWidth(0), - mWindowHeight(height), mWindowWidth(width), windowHidden(false), mNearClipping(0.001), mFarClipping(200), mcam(cam), - mshowConfigDialog(true), mOptionalResourceLocation() -{ -} + keepOn(true), // When created no reason to stop displaying + mImageRGBA(), mImage(), mPixelBuffer(), mBackground(nullptr), mBackgroundHeight(0), mBackgroundWidth(0), + mWindowHeight(height), mWindowWidth(width), windowHidden(false), mNearClipping(0.001), mFarClipping(200), mcam(cam), + mshowConfigDialog(true), mOptionalResourceLocation() +{ } /*! Initialisation of Ogre with a grey level background. @@ -235,11 +235,11 @@ void vpAROgre::init(bool if (!pluginsFileExists) { std::string errorMsg = std::string("Error: the requested plugins file \"") #if defined(NDEBUG) || !defined(_WIN32) - + std::string("plugins.cfg") + +std::string("plugins.cfg") #else - + std::string("plugins_d.cfg") + + std::string("plugins_d.cfg") #endif - + std::string("\" doesn't exist in ") + std::string(mPluginsPath); + + std::string("\" doesn't exist in ") + std::string(mPluginsPath); std::cout << errorMsg << std::endl; throw(vpException(vpException::ioError, errorMsg)); @@ -248,7 +248,8 @@ void vpAROgre::init(bool if (Ogre::Root::getSingletonPtr() == nullptr) { mRoot = new Ogre::Root(pluginFile, "ogre.cfg", "Ogre.log"); - } else { + } + else { mRoot = Ogre::Root::getSingletonPtr(); } @@ -276,7 +277,7 @@ void vpAROgre::init(bool } if (!resourcesFileExists) { std::string errorMsg = std::string("Error: the requested resource file \"resources.cfg\"") + - std::string("doesn't exist in ") + std::string(mResourcePath); + std::string("doesn't exist in ") + std::string(mResourcePath); std::cout << errorMsg << std::endl; @@ -315,7 +316,8 @@ void vpAROgre::init(bool if (!mRoot->showConfigDialog()) { canInit = false; } - } else { + } + else { if (!mRoot->restoreConfig()) { canInit = false; } @@ -353,15 +355,18 @@ void vpAROgre::init(bool if (ss.fail()) { std::cout << "Cannot read Ogre video mode" << std::endl; } - } else if (mWindowWidth == 0 && mWindowHeight == 0) { + } + else if (mWindowWidth == 0 && mWindowHeight == 0) { mWindowWidth = mBackgroundWidth; mWindowHeight = mBackgroundHeight; } - } else if (leftconf == "Full Screen") { + } + else if (leftconf == "Full Screen") { if (canInit && (rightconf == "Yes")) { fullscreen = true; } - } else { + } + else { misc[leftconf] = rightconf; } @@ -485,7 +490,8 @@ bool vpAROgre::stopTest(const Ogre::FrameEvent &evt) // Always keep this part if (keepOn) { return updateScene(evt); - } else { + } + else { return keepOn; } } @@ -625,7 +631,8 @@ void vpAROgre::display(const vpImage &I, const vpHomogeneousMatri if (renderOneFrame(I, cMw)) { mWindow->update(); keepOn = true; - } else + } + else keepOn = false; } @@ -640,7 +647,8 @@ void vpAROgre::display(const vpImage &I, const vpHomogeneousMatrix &cMw) if (renderOneFrame(I, cMw)) { mWindow->update(); keepOn = true; - } else + } + else keepOn = false; } @@ -801,7 +809,8 @@ void vpAROgre::createBackground(vpImage & /* I */) mBackgroundHeight, // height 0, // num of mip maps Ogre::PF_BYTE_L, Ogre::TU_DYNAMIC_WRITE_ONLY_DISCARDABLE); - } else { + } + else { Ogre::TextureManager::getSingleton().createManual( "BackgroundTexture", Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, Ogre::TEX_TYPE_2D, mBackgroundWidth, // width @@ -870,8 +879,9 @@ void vpAROgre::createBackground(vpImage & /* I */) 0, // num of mip maps // Ogre::PF_BYTE_RGBA, Ogre::PF_BYTE_BGRA, Ogre::TU_DYNAMIC_WRITE_ONLY_DISCARDABLE); - } else { // As that texture does not seem to work properly with direct3D we - // use a default texture + } + else { // As that texture does not seem to work properly with direct3D we + // use a default texture Ogre::TextureManager::getSingleton().createManual( "BackgroundTexture", Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, Ogre::TEX_TYPE_2D, mBackgroundWidth, // width @@ -1025,10 +1035,10 @@ void vpAROgre::updateCameraParameters(const vpHomogeneousMatrix &cMw) Ogre::Matrix4 ModelView // = Ogre::Matrix4( (Ogre::Real)-cMo[0][0], (Ogre::Real)-cMo[0][1], // (Ogre::Real)-cMo[0][2], (Ogre::Real)-cMo[0][3], - = Ogre::Matrix4((Ogre::Real)cMw[0][0], (Ogre::Real)cMw[0][1], (Ogre::Real)cMw[0][2], (Ogre::Real)cMw[0][3], - (Ogre::Real)-cMw[1][0], (Ogre::Real)-cMw[1][1], (Ogre::Real)-cMw[1][2], (Ogre::Real)-cMw[1][3], - (Ogre::Real)-cMw[2][0], (Ogre::Real)-cMw[2][1], (Ogre::Real)-cMw[2][2], (Ogre::Real)-cMw[2][3], - (Ogre::Real)0, (Ogre::Real)0, (Ogre::Real)0, (Ogre::Real)1); + = Ogre::Matrix4((Ogre::Real)cMw[0][0], (Ogre::Real)cMw[0][1], (Ogre::Real)cMw[0][2], (Ogre::Real)cMw[0][3], + (Ogre::Real)-cMw[1][0], (Ogre::Real)-cMw[1][1], (Ogre::Real)-cMw[1][2], (Ogre::Real)-cMw[1][3], + (Ogre::Real)-cMw[2][0], (Ogre::Real)-cMw[2][1], (Ogre::Real)-cMw[2][2], (Ogre::Real)-cMw[2][3], + (Ogre::Real)0, (Ogre::Real)0, (Ogre::Real)0, (Ogre::Real)1); mCamera->setCustomViewMatrix(true, ModelView); } @@ -1075,8 +1085,8 @@ void vpAROgre::getRenderingOutput(vpImage &I, const vpHomogeneousMatrix // Unlock the pixel buffer mPixelBuffer->unlock(); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_ar.a(vpAROgre.cpp.o) has no symbols -void dummy_vpAROgre(){}; +void dummy_vpAROgre() { }; #endif diff --git a/modules/ar/src/vpSimulatorException.cpp b/modules/ar/src/vpSimulatorException.cpp index 565a6cc6d0..a8049c364a 100644 --- a/modules/ar/src/vpSimulatorException.cpp +++ b/modules/ar/src/vpSimulatorException.cpp @@ -41,7 +41,7 @@ #include #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - +BEGIN_VISP_NAMESPACE vpSimulatorException::vpSimulatorException(int id, const char *format, ...) { this->code = id; @@ -54,9 +54,9 @@ vpSimulatorException::vpSimulatorException(int id, const char *format, ...) vpSimulatorException::vpSimulatorException(int id, const std::string &msg) : vpException(id, msg) { ; } vpSimulatorException::vpSimulatorException(int id) : vpException(id) { ; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_ar.a(vpSimulatorException.cpp.o) has no symbols -void dummy_vpSimulatorException(){}; +void dummy_vpSimulatorException() { }; #endif diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index d466f451b6..3137c6a8a2 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -50,6 +50,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! * \class vpArray2D * \ingroup group_core_matrices @@ -912,48 +913,49 @@ template class vpArray2D file.close(); return true; } - /*! - Save an array in a YAML-formatted file. - - \param filename : absolute file name. - \param A : array to be saved in the file. - \param header : optional lines that will be saved at the beginning of the - file. Should be YAML-formatted and will adapt to the indentation if any. - \return Returns true if success. - - Here is an example of outputs. - \code - vpArray2D M(3,4); - vpArray2D::saveYAML("matrix.yml", M, "example: a YAML-formatted header"); - vpArray2D::saveYAML("matrixIndent.yml", M, "example:\n - a YAML-formatted \ - header\n - with inner indentation"); - \endcode - Content of matrix.yml: - \code - example: a YAML-formatted header - rows: 3 - cols: 4 - data: - - [0, 0, 0, 0] - - [0, 0, 0, 0] - - [0, 0, 0, 0] - \endcode - Content of matrixIndent.yml: - \code - example: - - a YAML-formatted header - - with inner indentation - rows: 3 - cols: 4 - data: + /*! + Save an array in a YAML-formatted file. + + \param filename : absolute file name. + \param A : array to be saved in the file. + \param header : optional lines that will be saved at the beginning of the + file. Should be YAML-formatted and will adapt to the indentation if any. + + \return Returns true if success. + + Here is an example of outputs. + \code + vpArray2D M(3,4); + vpArray2D::saveYAML("matrix.yml", M, "example: a YAML-formatted header"); + vpArray2D::saveYAML("matrixIndent.yml", M, "example:\n - a YAML-formatted \ + header\n - with inner indentation"); + \endcode + Content of matrix.yml: + \code + example: a YAML-formatted header + rows: 3 + cols: 4 + data: - [0, 0, 0, 0] - [0, 0, 0, 0] - [0, 0, 0, 0] - \endcode - - \sa loadYAML() - */ + \endcode + Content of matrixIndent.yml: + \code + example: + - a YAML-formatted header + - with inner indentation + rows: 3 + cols: 4 + data: + - [0, 0, 0, 0] + - [0, 0, 0, 0] + - [0, 0, 0, 0] + \endcode + + \sa loadYAML() + */ static bool saveYAML(const std::string &filename, const vpArray2D &A, const char *header = "") { std::fstream file; @@ -1325,8 +1327,6 @@ template <> inline bool vpArray2D::operator==(const vpArray2D &A) template bool vpArray2D::operator!=(const vpArray2D &A) const { return !(*this == A); } #ifdef VISP_HAVE_NLOHMANN_JSON - - template inline void from_json(const nlohmann::json &j, vpArray2D &array) { @@ -1397,4 +1397,7 @@ inline void to_json(nlohmann::json &j, const vpArray2D &array) j["data"] = data; } #endif + +END_VISP_NAMESPACE + #endif diff --git a/modules/core/include/visp3/core/vpBSpline.h b/modules/core/include/visp3/core/vpBSpline.h index 7181f7f491..7e7703ded8 100644 --- a/modules/core/include/visp3/core/vpBSpline.h +++ b/modules/core/include/visp3/core/vpBSpline.h @@ -31,20 +31,21 @@ * This class implements the B-Spline */ -#ifndef vpBSpline_H -#define vpBSpline_H - /*! \file vpBSpline.h \brief Class that provides tools to compute and manipulate a B-Spline curve. */ +#ifndef vpBSpline_H +#define vpBSpline_H + #include #include #include #include +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS /*! @@ -234,5 +235,5 @@ public /*protected*/: const std::vector &l_knots, const std::vector &l_controlPoints); vpImagePoint *computeCurveDers(double u, unsigned int der) const; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpCPUFeatures.h b/modules/core/include/visp3/core/vpCPUFeatures.h index 53878cf6b4..7947b8fe0b 100644 --- a/modules/core/include/visp3/core/vpCPUFeatures.h +++ b/modules/core/include/visp3/core/vpCPUFeatures.h @@ -31,16 +31,17 @@ * CPU features (hardware capabilities). */ -#ifndef _vpCPUFeatures_h_ -#define _vpCPUFeatures_h_ - /*! \file vpCPUFeatures.h \brief Check CPU features (hardware capabilities). */ +#ifndef _vpCPUFeatures_h_ +#define _vpCPUFeatures_h_ + #include +BEGIN_VISP_NAMESPACE /*! \ingroup group_core_cpu_features \brief Check CPU features (hardware capabilities). @@ -48,14 +49,14 @@ The example below shows how to check or get CPU capabilities. \code -#include + #include -int main() -{ - std::cout << "checkSSE2: " << vpCPUFeatures::checkSSE2() << std::endl; - std::cout << "CPU info: " << vpCPUFeatures::printCPUInfo() << std::endl; - return 0; -} + int main() + { + std::cout << "checkSSE2: " << vpCPUFeatures::checkSSE2() << std::endl; + std::cout << "CPU info: " << vpCPUFeatures::printCPUInfo() << std::endl; + return 0; + } \endcode */ @@ -77,5 +78,5 @@ VISP_EXPORT size_t getCPUCacheL3(); #endif VISP_EXPORT void printCPUInfo(); } // namespace vpCPUFeatures - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpCameraParameters.h b/modules/core/include/visp3/core/vpCameraParameters.h index 1a9f2b283d..ef165a8b20 100644 --- a/modules/core/include/visp3/core/vpCameraParameters.h +++ b/modules/core/include/visp3/core/vpCameraParameters.h @@ -41,6 +41,7 @@ #ifndef _vpCameraParameters_h_ #define _vpCameraParameters_h_ +#include #include #include @@ -52,6 +53,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! \class vpCameraParameters @@ -299,7 +301,8 @@ $ cat cam.json {"model":"perspectiveWithoutDistortion","px":801.0,"py":802.0,"u0":325.0,"v0":245.0} \endcode - */ +*/ + class VISP_EXPORT vpCameraParameters { friend class vpMeterPixelConversion; @@ -544,5 +547,5 @@ inline void from_json(const nlohmann::json &j, vpCameraParameters &cam) } } #endif - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpCannyEdgeDetection.h b/modules/core/include/visp3/core/vpCannyEdgeDetection.h index b8f80f520b..723de821e4 100644 --- a/modules/core/include/visp3/core/vpCannyEdgeDetection.h +++ b/modules/core/include/visp3/core/vpCannyEdgeDetection.h @@ -45,6 +45,12 @@ #include #endif +BEGIN_VISP_NAMESPACE +/** + * \brief Class that implements the Canny's edge detector. + * It is possible to use a boolean mask to ignore some pixels of + * the input gray-scale image. +*/ class VISP_EXPORT vpCannyEdgeDetection { @@ -106,19 +112,7 @@ class VISP_EXPORT vpCannyEdgeDetection * \param[in] j : The JSON object, resulting from the parsing of a JSON file. * \param[out] detector : The detector that will be initialized from the JSON data. */ - friend inline void from_json(const nlohmann::json &j, vpCannyEdgeDetection &detector) - { - std::string filteringAndGradientName = vpImageFilter::vpCannyFiltAndGradTypeToStr(detector.m_filteringAndGradientType); - filteringAndGradientName = j.value("filteringAndGradientType", filteringAndGradientName); - detector.m_filteringAndGradientType = vpImageFilter::vpCannyFiltAndGradTypeFromStr(filteringAndGradientName); - detector.m_gaussianKernelSize = j.value("gaussianSize", detector.m_gaussianKernelSize); - detector.m_gaussianStdev = j.value("gaussianStdev", detector.m_gaussianStdev); - detector.m_lowerThreshold = j.value("lowerThreshold", detector.m_lowerThreshold); - detector.m_lowerThresholdRatio = j.value("lowerThresholdRatio", detector.m_lowerThresholdRatio); - detector.m_gradientFilterKernelSize = j.value("gradientFilterKernelSize", detector.m_gradientFilterKernelSize); - detector.m_upperThreshold = j.value("upperThreshold", detector.m_upperThreshold); - detector.m_upperThresholdRatio = j.value("upperThresholdRatio", detector.m_upperThresholdRatio); - } + friend void from_json(const nlohmann::json &j, vpCannyEdgeDetection &detector); /** * \brief Parse a vpCannyEdgeDetection object into JSON format. @@ -126,20 +120,7 @@ class VISP_EXPORT vpCannyEdgeDetection * \param[out] j : A JSON parser object. * \param[in] detector : The vpCannyEdgeDetection object that must be parsed into JSON format. */ - friend inline void to_json(nlohmann::json &j, const vpCannyEdgeDetection &detector) - { - std::string filteringAndGradientName = vpImageFilter::vpCannyFiltAndGradTypeToStr(detector.m_filteringAndGradientType); - j = nlohmann::json { - {"filteringAndGradientType", filteringAndGradientName}, - {"gaussianSize", detector.m_gaussianKernelSize}, - {"gaussianStdev", detector.m_gaussianStdev}, - {"lowerThreshold", detector.m_lowerThreshold}, - {"lowerThresholdRatio", detector.m_lowerThresholdRatio}, - {"gradientFilterKernelSize", detector.m_gradientFilterKernelSize}, - {"upperThreshold", detector.m_upperThreshold}, - {"upperThresholdRatio", detector.m_upperThresholdRatio} - }; - } + friend void to_json(nlohmann::json &j, const vpCannyEdgeDetection &detector); #endif //@} @@ -383,4 +364,5 @@ class VISP_EXPORT vpCannyEdgeDetection void performEdgeTracking(); //@} }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpCircle.h b/modules/core/include/visp3/core/vpCircle.h index e2a1447a6d..71b4361107 100644 --- a/modules/core/include/visp3/core/vpCircle.h +++ b/modules/core/include/visp3/core/vpCircle.h @@ -36,15 +36,17 @@ \brief class that defines what is a circle */ -#ifndef vpCircle_hh -#define vpCircle_hh +#ifndef _vpCircle_h_ +#define _vpCircle_h_ #include +#include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpCircle * \ingroup group_core_geometry @@ -81,7 +83,7 @@ * projection(const vpColVector &cP, vpColVector &p) const. They could be retrieved using get_x(), get_y(), get_n20(), * get_n11() and get_n02(). They correspond to 2D normalized circle parameters with values expressed in meters. * To get theses parameters use get_p(). - */ +*/ class VISP_EXPORT vpCircle : public vpForwardProjection { public: @@ -164,7 +166,6 @@ class VISP_EXPORT vpCircle : public vpForwardProjection #endif protected: void init() vp_override; - }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpClient.h b/modules/core/include/visp3/core/vpClient.h index ed64dc76a8..a74eee5789 100644 --- a/modules/core/include/visp3/core/vpClient.h +++ b/modules/core/include/visp3/core/vpClient.h @@ -44,6 +44,7 @@ // inet_ntop() not supported on win XP #ifdef VISP_HAVE_FUNC_INET_NTOP +BEGIN_VISP_NAMESPACE /*! * \class vpClient * @@ -158,7 +159,7 @@ * \sa vpClient * \sa vpRequest * \sa vpNetwork - */ +*/ class VISP_EXPORT vpClient : public vpNetwork { private: @@ -203,6 +204,6 @@ class VISP_EXPORT vpClient : public vpNetwork void stop(); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpColVector.h b/modules/core/include/visp3/core/vpColVector.h index 08bc97d1b6..b78e6b3d32 100644 --- a/modules/core/include/visp3/core/vpColVector.h +++ b/modules/core/include/visp3/core/vpColVector.h @@ -31,27 +31,35 @@ * Provide some simple operation on column vectors. */ +/*! + * \file vpColVector.h + * \brief definition of column vector class as well + * as a set of operations on these vector + */ + #ifndef _vpColVector_h_ #define _vpColVector_h_ -#include -#include -#include -#include -#include +#include +#ifdef VISP_HAVE_NLOHMANN_JSON +#include +#endif +BEGIN_VISP_NAMESPACE class vpMatrix; class vpRowVector; class vpRotationVector; class vpTranslationVector; class vpPoseVector; +END_VISP_NAMESPACE -/*! - * \file vpColVector.h - * \brief definition of column vector class as well - * as a set of operations on these vector - */ +#include +#include +#include +#include +#include +BEGIN_VISP_NAMESPACE /*! * \class vpColVector * \ingroup group_core_matrices @@ -158,7 +166,7 @@ class vpPoseVector; * $ cat col-vector.json * {"cols":1,"data":[1.0,2.0,3.0,4.0],"rows":4,"type":"vpColVector"} * \endcode - */ +*/ class VISP_EXPORT vpColVector : public vpArray2D { friend class vpMatrix; @@ -1457,6 +1465,7 @@ VISP_EXPORT #endif vpColVector operator*(const double &x, const vpColVector &v); + #ifdef VISP_HAVE_NLOHMANN_JSON inline void to_json(nlohmann::json &j, const vpColVector &v) { @@ -1464,6 +1473,7 @@ inline void to_json(nlohmann::json &j, const vpColVector &v) to_json(j, *asArray); j["type"] = "vpColVector"; } + inline void from_json(const nlohmann::json &j, vpColVector &v) { vpArray2D *asArray = (vpArray2D*) & v; @@ -1472,8 +1482,6 @@ inline void from_json(const nlohmann::json &j, vpColVector &v) throw vpException(vpException::badValue, "From JSON, tried to read a 2D array into a vpColVector"); } } - - #endif - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpColor.h b/modules/core/include/visp3/core/vpColor.h index 509a736aa8..4e42fec9a9 100644 --- a/modules/core/include/visp3/core/vpColor.h +++ b/modules/core/include/visp3/core/vpColor.h @@ -37,6 +37,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpColor @@ -96,55 +97,55 @@ a circle) and a specific brown color (used to draw a rectangle). \code -#include -#include -#include -#include -#include + #include + #include + #include + #include + #include -int main() -{ - vpImage I(240, 320); // Create a black grey level image - - vpDisplay *d; - - // Depending on the detected third party libraries, we instantiate here the - // first video device which is available -#if defined(VISP_HAVE_X11) - d = new vpDisplayX; -#elif defined(VISP_HAVE_GTK) - d = new vpDisplayGTK; -#elif defined(VISP_HAVE_GDI) - d = new vpDisplayGDI; -#elif defined(VISP_HAVE_D3D9) - d = new vpDisplayD3D; -#elif defined(HAVE_OPENCV_HIGHGUI) - d = new vpDisplayOpenCV; -#endif - - // Initialize the display with the image I. Display and image are - // now link together. -#ifdef VISP_HAVE_DISPLAY - d->init(I); -#endif - - // Set the display background with image I content - vpDisplay::display(I); - - // Draw a filled circle with the predefined blue color - vpDisplay::displayCircle(I, 100, 200, 30, vpColor::blue, true); - - // Creation of a new brown color with its RGB values - vpColor color(128, 100, 50); - - // Draw a brown rectangle in the display overlay (foreground) - vpDisplay::displayRectangle(I, 10, 10, 100, 20, color, true); - - // Flush the foreground and background display - vpDisplay::flush(I); - - delete d; -} + int main() + { + vpImage I(240, 320); // Create a black grey level image + + vpDisplay *d; + + // Depending on the detected third party libraries, we instantiate here the + // first video device which is available + #if defined(VISP_HAVE_X11) + d = new vpDisplayX; + #elif defined(VISP_HAVE_GTK) + d = new vpDisplayGTK; + #elif defined(VISP_HAVE_GDI) + d = new vpDisplayGDI; + #elif defined(VISP_HAVE_D3D9) + d = new vpDisplayD3D; + #elif defined(HAVE_OPENCV_HIGHGUI) + d = new vpDisplayOpenCV; + #endif + + // Initialize the display with the image I. Display and image are + // now link together. + #ifdef VISP_HAVE_DISPLAY + d->init(I); + #endif + + // Set the display background with image I content + vpDisplay::display(I); + + // Draw a filled circle with the predefined blue color + vpDisplay::displayCircle(I, 100, 200, 30, vpColor::blue, true); + + // Creation of a new brown color with its RGB values + vpColor color(128, 100, 50); + + // Draw a brown rectangle in the display overlay (foreground) + vpDisplay::displayRectangle(I, 10, 10, 100, 20, color, true); + + // Flush the foreground and background display + vpDisplay::flush(I); + + delete d; + } \endcode */ @@ -152,7 +153,8 @@ class VISP_EXPORT vpColor : public vpRGBa { public: /*! Predefined colors identifier. */ - typedef enum { + typedef enum + { id_black = 0, /*!< Identifier associated to the predefined vpColor::black color. */ id_white, /*!< Identifier associated to the predefined vpColor::white @@ -232,7 +234,7 @@ class VISP_EXPORT vpColor : public vpRGBa that this color is not a predefined one. */ - inline vpColor() : vpRGBa(), id(id_unknown) {} + inline vpColor() : vpRGBa(), id(id_unknown) { } /*! Construct a color from its RGB values. @@ -246,8 +248,7 @@ class VISP_EXPORT vpColor : public vpRGBa inline vpColor(unsigned char r, unsigned char g, unsigned char b, vpColor::vpColorIdentifier cid = vpColor::id_unknown) : vpRGBa(r, g, b), id(cid) - { - } + { } /*! Construct a color from its RGB values and alpha channel. @@ -262,18 +263,17 @@ class VISP_EXPORT vpColor : public vpRGBa inline vpColor(unsigned char r, unsigned char g, unsigned char b, unsigned char alpha, vpColor::vpColorIdentifier cid = vpColor::id_unknown) : vpRGBa(r, g, b, alpha), id(cid) - { - } + { } /*! Construct a color with an alpha channel. \param color : RGB color. \param alpha : Alpha channel for transparency. */ - inline vpColor(const vpColor &color, unsigned char alpha) : vpRGBa(color.R, color.G, color.B, alpha), id(color.id) {} + inline vpColor(const vpColor &color, unsigned char alpha) : vpRGBa(color.R, color.G, color.B, alpha), id(color.id) { } /*! Default destructor. */ - inline virtual ~vpColor() {} + inline virtual ~vpColor() { } friend VISP_EXPORT bool operator==(const vpColor &c1, const vpColor &c2); friend VISP_EXPORT bool operator!=(const vpColor &c1, const vpColor &c2); @@ -367,7 +367,7 @@ vpColor const __declspec(selectany) vpColor::none = vpColor(0, 0, 0, id_unknown) const __declspec(selectany) unsigned int vpColor::nbColors = 18; /*!< Array of available colors. */ -vpColor const __declspec(selectany) vpColor::allColors[vpColor::nbColors] = {vpColor::blue, // 12 +vpColor const __declspec(selectany) vpColor::allColors[vpColor::nbColors] = { vpColor::blue, // 12 vpColor::green, // 9 vpColor::red, // 6 vpColor::cyan, // 15 @@ -384,8 +384,9 @@ vpColor const __declspec(selectany) vpColor::allColors[vpColor::nbColors] = {vpC vpColor::gray, // 3 vpColor::darkGray, // 4 vpColor::black, // 0 - vpColor::white}; // 17 + vpColor::white +}; // 17 #endif - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpColorDepthConversion.h b/modules/core/include/visp3/core/vpColorDepthConversion.h index 5b34e0739d..f5dfb51185 100644 --- a/modules/core/include/visp3/core/vpColorDepthConversion.h +++ b/modules/core/include/visp3/core/vpColorDepthConversion.h @@ -39,6 +39,7 @@ #include "vpCameraParameters.h" #include "vpImage.h" +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpColorDepthConversion { public: @@ -54,3 +55,4 @@ class VISP_EXPORT vpColorDepthConversion const vpHomogeneousMatrix &color_M_depth, const vpHomogeneousMatrix &depth_M_color, const vpImagePoint &from_pixel); }; +END_VISP_NAMESPACE diff --git a/modules/core/include/visp3/core/vpColormap.h b/modules/core/include/visp3/core/vpColormap.h index 74147bcdcd..39ac1d862e 100644 --- a/modules/core/include/visp3/core/vpColormap.h +++ b/modules/core/include/visp3/core/vpColormap.h @@ -32,20 +32,20 @@ * some corresponding color values, for better visualization for example. */ -#ifndef _vpColormap_h_ -#define _vpColormap_h_ - /*! * \file vpColormap.h * * \brief Colormap tool to have a mapping between 256 values and RGB values. */ +#ifndef _vpColormap_h_ +#define _vpColormap_h_ + #include #include #include - +BEGIN_VISP_NAMESPACE /*! * \class vpColormap * @@ -53,7 +53,7 @@ * * \brief Creates a colormap class to be able to recolor an image with different grayscale * values into some corresponding color values, for better visualization for example. - */ +*/ class VISP_EXPORT vpColormap { public: @@ -99,5 +99,5 @@ class VISP_EXPORT vpColormap unsigned char m_colormapSrgbBytes[256][3]; #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpConvert.h b/modules/core/include/visp3/core/vpConvert.h index b87095f7bc..eb012e5759 100644 --- a/modules/core/include/visp3/core/vpConvert.h +++ b/modules/core/include/visp3/core/vpConvert.h @@ -31,14 +31,14 @@ * Directory management. */ -#ifndef _vpConvert_h_ -#define _vpConvert_h_ - /*! \file vpConvert.h \brief Tools for type or general conversion. */ +#ifndef _vpConvert_h_ +#define _vpConvert_h_ + #include #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_FEATURES2D) @@ -47,11 +47,12 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpConvert \ingroup group_core_bridges Bridges over other frameworks like OpenCV. - */ +*/ class VISP_EXPORT vpConvert { public: @@ -98,6 +99,6 @@ class VISP_EXPORT vpConvert static cv::Point3d vpObjectPointToPoint3d(const vpPoint &point); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpCylinder.h b/modules/core/include/visp3/core/vpCylinder.h index aaf327d2fd..b533955bae 100644 --- a/modules/core/include/visp3/core/vpCylinder.h +++ b/modules/core/include/visp3/core/vpCylinder.h @@ -40,11 +40,13 @@ #define vpCylinder_hh #include +#include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpCylinder * \ingroup group_core_geometry @@ -94,7 +96,7 @@ * Perspective projection is achieved using projection() methods. The methods * get_p(), getRho1(), getTheta1() and getRho2(), getTheta2() allow to access to the * projected line parameters. - */ +*/ class VISP_EXPORT vpCylinder : public vpForwardProjection { public: @@ -193,5 +195,5 @@ class VISP_EXPORT vpCylinder : public vpForwardProjection void setWorldCoordinates(const vpColVector &oP) vp_override; void setWorldCoordinates(double oA, double oB, double oC, double oX, double oY, double oZ, double R); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpDebug.h b/modules/core/include/visp3/core/vpDebug.h index f45f88c476..ef6e1eff3c 100644 --- a/modules/core/include/visp3/core/vpDebug.h +++ b/modules/core/include/visp3/core/vpDebug.h @@ -61,6 +61,7 @@ #define VP_DEBUG_MODE 0 #endif +BEGIN_VISP_NAMESPACE /*! \class vpTraceOutput @@ -547,5 +548,5 @@ inline void vpDEBUG_TRACE(int /* level */, const char * /* a */, ...) { } #else #define DEFENSIF(a) (0) #endif /*#ifdef DEFENSIF*/ - +END_VISP_NAMESPACE #endif /* #ifdef __DEBUG_HH */ diff --git a/modules/core/include/visp3/core/vpDisplay.h b/modules/core/include/visp3/core/vpDisplay.h index ed7b59577c..24b57cad3c 100644 --- a/modules/core/include/visp3/core/vpDisplay.h +++ b/modules/core/include/visp3/core/vpDisplay.h @@ -31,6 +31,12 @@ * Image display. */ +/*! + * \file vpDisplay.h + * \brief Generic class for image display, also provide the interface + * with the image. + */ + #ifndef _vpDisplay_h_ #define _vpDisplay_h_ @@ -48,12 +54,7 @@ #include #include -/*! - * \file vpDisplay.h - * \brief Generic class for image display, also provide the interface - * with the image. - */ - +BEGIN_VISP_NAMESPACE /*! * \class vpDisplay * @@ -168,7 +169,7 @@ * * Other examples are available in tutorial-image-viewer.cpp and * tutorial-viewer.cpp. - */ +*/ class VISP_EXPORT vpDisplay { public: @@ -929,5 +930,5 @@ class VISP_EXPORT vpDisplay //! Get the window pixmap and put it in vpRGBa image. virtual void getImage(vpImage &I) = 0; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpDisplayException.h b/modules/core/include/visp3/core/vpDisplayException.h index 4214b7eaf3..0cc16ba313 100644 --- a/modules/core/include/visp3/core/vpDisplayException.h +++ b/modules/core/include/visp3/core/vpDisplayException.h @@ -31,24 +31,25 @@ * Exception that can be emitted by the vpDisplay class and its derivatives. */ -#ifndef _vpDisplayException_h_ -#define _vpDisplayException_h_ - /*! * \file vpDisplayException.h * \brief error that can be emitted by the vpDisplay class and its derivatives */ +#ifndef _vpDisplayException_h_ +#define _vpDisplayException_h_ + #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpDisplayException * \ingroup group_core_debug * \brief Error that can be emitted by the vpDisplay class and its derivatives. - */ +*/ class VISP_EXPORT vpDisplayException : public vpException { public: @@ -90,5 +91,5 @@ class VISP_EXPORT vpDisplayException : public vpException */ explicit vpDisplayException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpEigenConversion.h b/modules/core/include/visp3/core/vpEigenConversion.h index a5463b6bdc..ac07ffc791 100644 --- a/modules/core/include/visp3/core/vpEigenConversion.h +++ b/modules/core/include/visp3/core/vpEigenConversion.h @@ -40,42 +40,42 @@ #endif #include -namespace vp +namespace VISP_NAMESPACE_NAME { #ifdef VISP_HAVE_EIGEN3 /* Eigen to ViSP */ -VISP_EXPORT void eigen2visp(const Eigen::MatrixXd &src, vpMatrix &dst); +VISP_EXPORT void eigen2visp(const Eigen::MatrixXd &src, VISP_NAMESPACE_ADDRESSING vpMatrix &dst); -VISP_EXPORT void eigen2visp(const Eigen::MatrixXd &src, vpHomogeneousMatrix &dst); +VISP_EXPORT void eigen2visp(const Eigen::MatrixXd &src, VISP_NAMESPACE_ADDRESSING vpHomogeneousMatrix &dst); -template void eigen2visp(const Eigen::Quaternion &src, vpQuaternionVector &dst) +template void eigen2visp(const Eigen::Quaternion &src, VISP_NAMESPACE_ADDRESSING vpQuaternionVector &dst) { dst.build(src.x(), src.y(), src.z(), src.w()); } -template void eigen2visp(const Eigen::AngleAxis &src, vpThetaUVector &dst) +template void eigen2visp(const Eigen::AngleAxis &src, VISP_NAMESPACE_ADDRESSING vpThetaUVector &dst) { dst.build(src.angle() * src.axis()(0), src.angle() * src.axis()(1), src.angle() * src.axis()(2)); } -VISP_EXPORT void eigen2visp(const Eigen::VectorXd &src, vpColVector &dst); +VISP_EXPORT void eigen2visp(const Eigen::VectorXd &src, VISP_NAMESPACE_ADDRESSING vpColVector &dst); -VISP_EXPORT void eigen2visp(const Eigen::RowVectorXd &src, vpRowVector &dst); +VISP_EXPORT void eigen2visp(const Eigen::RowVectorXd &src, VISP_NAMESPACE_ADDRESSING vpRowVector &dst); /* ViSP to Eigen */ -template void visp2eigen(const vpMatrix &src, Eigen::MatrixBase &dst) +template void visp2eigen(const VISP_NAMESPACE_ADDRESSING vpMatrix &src, Eigen::MatrixBase &dst) { dst = Eigen::Map >(src.data, src.getRows(), src.getCols()); } -template void visp2eigen(const vpHomogeneousMatrix &src, Eigen::MatrixBase &dst) +template void visp2eigen(const VISP_NAMESPACE_ADDRESSING vpHomogeneousMatrix &src, Eigen::MatrixBase &dst) { dst = Eigen::Map >(src.data, src.getRows(), src.getCols()); } -template void visp2eigen(const vpQuaternionVector &src, Eigen::Quaternion &dst) +template void visp2eigen(const VISP_NAMESPACE_ADDRESSING vpQuaternionVector &src, Eigen::Quaternion &dst) { dst.w() = static_cast(src.w()); dst.x() = static_cast(src.x()); @@ -83,7 +83,7 @@ template void visp2eigen(const vpQuaternionVector &src, Eigen::Q dst.z() = static_cast(src.z()); } -template void visp2eigen(const vpThetaUVector &src, Eigen::AngleAxis &dst) +template void visp2eigen(const VISP_NAMESPACE_ADDRESSING vpThetaUVector &src, Eigen::AngleAxis &dst) { dst.angle() = static_cast(src.getTheta()); dst.axis()(0) = static_cast(src.getU()[0]); @@ -91,9 +91,9 @@ template void visp2eigen(const vpThetaUVector &src, Eigen::Angle dst.axis()(2) = static_cast(src.getU()[2]); } -VISP_EXPORT void visp2eigen(const vpColVector &src, Eigen::VectorXd &dst); +VISP_EXPORT void visp2eigen(const VISP_NAMESPACE_ADDRESSING vpColVector &src, Eigen::VectorXd &dst); -VISP_EXPORT void visp2eigen(const vpRowVector &src, Eigen::RowVectorXd &dst); +VISP_EXPORT void visp2eigen(const VISP_NAMESPACE_ADDRESSING vpRowVector &src, Eigen::RowVectorXd &dst); #endif -} // namespace vp +} // namespace VISP_NAMESPACE_NAME #endif diff --git a/modules/core/include/visp3/core/vpEndian.h b/modules/core/include/visp3/core/vpEndian.h index a55ec06854..06202b6ffd 100644 --- a/modules/core/include/visp3/core/vpEndian.h +++ b/modules/core/include/visp3/core/vpEndian.h @@ -36,8 +36,8 @@ \brief Determine machine endianness and define VISP_LITTLE_ENDIAN, VISP_BIG_ENDIAN and VISP_PDP_ENDIAN macros. */ -#ifndef vpEndian_h -#define vpEndian_h +#ifndef _vpEndian_h_ +#define _vpEndian_h_ // Visual Studio 2010 or previous is missing inttypes.h #if defined(_MSC_VER) && (_MSC_VER < 1700) @@ -86,6 +86,7 @@ typedef unsigned short uint16_t; #error Cannot detect host machine endianness. #endif +BEGIN_VISP_NAMESPACE namespace vpEndian { VISP_EXPORT uint16_t swap16bits(uint16_t val); @@ -98,5 +99,5 @@ VISP_EXPORT double swapDouble(double d); VISP_EXPORT uint16_t reinterpret_cast_uchar_to_uint16_LE(unsigned char *const ptr); } // namespace vpEndian - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpException.h b/modules/core/include/visp3/core/vpException.h index 30fb93e2ff..9bdb1ffbd6 100644 --- a/modules/core/include/visp3/core/vpException.h +++ b/modules/core/include/visp3/core/vpException.h @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpException * \ingroup group_core_debug @@ -54,7 +55,7 @@ * STL. * It is therefore possible to catch vpException with any other derivative of * std::exception in the same catch. - */ +*/ class VISP_EXPORT vpException : public std::exception { public: @@ -145,5 +146,5 @@ class VISP_EXPORT vpException : public std::exception vpException() : code(notInitialized), message("") { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpExponentialMap.h b/modules/core/include/visp3/core/vpExponentialMap.h index 95637be0f4..9ee15ffec8 100644 --- a/modules/core/include/visp3/core/vpExponentialMap.h +++ b/modules/core/include/visp3/core/vpExponentialMap.h @@ -36,12 +36,14 @@ \brief Provides exponential map computation */ -#ifndef vpExponentialMap_h -#define vpExponentialMap_h +#ifndef _vpExponentialMap_h_ +#define _vpExponentialMap_h_ +#include #include #include +BEGIN_VISP_NAMESPACE /*! \class vpExponentialMap @@ -92,4 +94,5 @@ class VISP_EXPORT vpExponentialMap static vpColVector inverse(const vpHomogeneousMatrix &M); static vpColVector inverse(const vpHomogeneousMatrix &M, const double &delta_t); }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpFeatureDisplay.h b/modules/core/include/visp3/core/vpFeatureDisplay.h index 66c3af9643..442f1c4fa8 100644 --- a/modules/core/include/visp3/core/vpFeatureDisplay.h +++ b/modules/core/include/visp3/core/vpFeatureDisplay.h @@ -31,14 +31,16 @@ * Interface with the image for feature display. */ -#ifndef vpFeatureDisplay_H -#define vpFeatureDisplay_H - /*! \file vpFeatureDisplay.h \brief interface with the image for feature display */ +#ifndef _vpFeatureDisplay_H_ +#define _vpFeatureDisplay_H_ + +#include + // Color / image / display #include #include @@ -47,6 +49,7 @@ // Meter/pixel conversion #include +BEGIN_VISP_NAMESPACE /*! \class vpFeatureDisplay @@ -82,5 +85,5 @@ class VISP_EXPORT vpFeatureDisplay static void displayPoint(double x, double y, const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpFont.h b/modules/core/include/visp3/core/vpFont.h index 39031505c2..7ae460434c 100644 --- a/modules/core/include/visp3/core/vpFont.h +++ b/modules/core/include/visp3/core/vpFont.h @@ -31,18 +31,19 @@ * Draw text in an image. */ -#ifndef _vpFont_h_ -#define _vpFont_h_ - /*! \file vpFont.h \brief Draw text in an image. */ +#ifndef _vpFont_h_ +#define _vpFont_h_ + #include #include +BEGIN_VISP_NAMESPACE /*! \class vpFont @@ -80,5 +81,5 @@ class VISP_EXPORT vpFont class Impl; Impl *m_impl; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpForceTwistMatrix.h b/modules/core/include/visp3/core/vpForceTwistMatrix.h index b7da80e2f7..c2d74b89e1 100644 --- a/modules/core/include/visp3/core/vpForceTwistMatrix.h +++ b/modules/core/include/visp3/core/vpForceTwistMatrix.h @@ -32,8 +32,14 @@ * frame to an other. */ -#ifndef vpForceTwistMatrix_h -#define vpForceTwistMatrix_h +#ifndef _vpForceTwistMatrix_h_ +#define _vpForceTwistMatrix_h_ + +#include + +BEGIN_VISP_NAMESPACE +class vpMatrix; +END_VISP_NAMESPACE #include #include @@ -41,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpForceTwistMatrix @@ -133,30 +140,30 @@ int main() from probe frame to a sensor frame. \code -#include -#include + #include + #include -int main() -{ - // Twist transformation matrix from sensor to probe frame - vpForceTwistMatrix sFp; + int main() + { + // Twist transformation matrix from sensor to probe frame + vpForceTwistMatrix sFp; - // Force/torque sensor frame to probe frame transformation - vpHomogeneousMatrix sMp; - // ... sMp need here to be initialized + // Force/torque sensor frame to probe frame transformation + vpHomogeneousMatrix sMp; + // ... sMp need here to be initialized - sFp.build(sMp); + sFp.build(sMp); - // Force/torque skew in the probe frame: fx,fy,fz,tx,ty,tz - vpColVector p_H(6); - // ... p_H should here have an initial value + // Force/torque skew in the probe frame: fx,fy,fz,tx,ty,tz + vpColVector p_H(6); + // ... p_H should here have an initial value - // Force/torque skew in the sensor frame: fx,fy,fz,tx,ty,tz - vpColVector s_H(6); + // Force/torque skew in the sensor frame: fx,fy,fz,tx,ty,tz + vpColVector s_H(6); - // Compute the value of the force/torque in the sensor frame - s_H = sFp * p_H; -} + // Compute the value of the force/torque in the sensor frame + s_H = sFp * p_H; + } \endcode */ class VISP_EXPORT vpForceTwistMatrix : public vpArray2D @@ -236,5 +243,5 @@ class VISP_EXPORT vpForceTwistMatrix : public vpArray2D //@} #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpForwardProjection.h b/modules/core/include/visp3/core/vpForwardProjection.h index a51e4ff384..60f81141e8 100644 --- a/modules/core/include/visp3/core/vpForwardProjection.h +++ b/modules/core/include/visp3/core/vpForwardProjection.h @@ -31,20 +31,22 @@ * Forward projection. */ -#ifndef vpForwardProjection_H -#define vpForwardProjection_H - /*! * \file vpForwardProjection.h * \brief class that defines what is a generic geometric feature */ +#ifndef _vpForwardProjection_H_ +#define _vpForwardProjection_H_ + +#include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpForwardProjection * \brief Class that defines what is a generic geometric feature. @@ -58,7 +60,7 @@ * - in the image plane \e p. These parameters are located in the public * attribute vpTracker::p. They correspond to normalized coordinates * of the feature expressed in meters. - */ +*/ class VISP_EXPORT vpForwardProjection : public vpTracker { public: @@ -218,5 +220,5 @@ class VISP_EXPORT vpForwardProjection : public vpTracker private: vpForwardProjectionDeallocatorType deallocate; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpFrameGrabber.h b/modules/core/include/visp3/core/vpFrameGrabber.h index 8ad08f4263..b2c62a553e 100644 --- a/modules/core/include/visp3/core/vpFrameGrabber.h +++ b/modules/core/include/visp3/core/vpFrameGrabber.h @@ -31,18 +31,20 @@ * Frame grabbing. */ -#ifndef vpFrameGrabber_hh -#define vpFrameGrabber_hh - -#include -#include - /*! * \file vpFrameGrabber.h * \brief Base class for all video devices. It is * designed to provide a generic front end to video sources. */ +#ifndef _vpFrameGrabber_h_ +#define _vpFrameGrabber_h_ + +#include +#include +#include + +BEGIN_VISP_NAMESPACE /*! * \class vpFrameGrabber * @@ -89,7 +91,7 @@ * #endif * } * \endcode - */ +*/ class VISP_EXPORT vpFrameGrabber { public: @@ -128,5 +130,5 @@ class VISP_EXPORT vpFrameGrabber unsigned int height; //!< Number of rows in the image. unsigned int width; //!< Number of columns in the image. }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpFrameGrabberException.h b/modules/core/include/visp3/core/vpFrameGrabberException.h index 1229b44cb5..a0ce41e17f 100644 --- a/modules/core/include/visp3/core/vpFrameGrabberException.h +++ b/modules/core/include/visp3/core/vpFrameGrabberException.h @@ -32,25 +32,25 @@ * derivates. */ -#ifndef _vpFrameGrabberException_h_ -#define _vpFrameGrabberException_h_ - /*! * \file vpFrameGrabberException.h * \brief error that can be emitted by the vpFrameGrabber class and its * derivates */ +#ifndef _vpFrameGrabberException_h_ +#define _vpFrameGrabberException_h_ + #include #include #include #include - +BEGIN_VISP_NAMESPACE /*! * \brief Error that can be emitted by the vpFrameGrabber class and its * derivates. - */ +*/ class VISP_EXPORT vpFrameGrabberException : public vpException { public: @@ -88,5 +88,5 @@ class VISP_EXPORT vpFrameGrabberException : public vpException */ explicit vpFrameGrabberException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpGEMM.h b/modules/core/include/visp3/core/vpGEMM.h index 23837d406b..f9d385be45 100644 --- a/modules/core/include/visp3/core/vpGEMM.h +++ b/modules/core/include/visp3/core/vpGEMM.h @@ -37,6 +37,7 @@ #include #include +BEGIN_VISP_NAMESPACE const vpArray2D null(0, 0); /*! @@ -443,5 +444,5 @@ inline void vpGEMM(const vpArray2D &A, const vpArray2D &B, const break; } } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpGaussRand.h b/modules/core/include/visp3/core/vpGaussRand.h index 79c5f1d356..1c44371d6f 100644 --- a/modules/core/include/visp3/core/vpGaussRand.h +++ b/modules/core/include/visp3/core/vpGaussRand.h @@ -37,6 +37,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpGaussRand \ingroup group_core_random @@ -81,37 +82,37 @@ different values using seed(). For example, this could be done using the current time. The code becomes: \verbatim -#include -#include -#include - -int main() -{ - vpGaussRand noise(0.5, 10); - long seed = (long)vpTime::measureTimeMs(); + #include + #include + #include - noise.seed(seed); - for(int i=0; i< 10; i++) { - std::cout << "noise " << i << ": " << noise() << std::endl; + int main() + { + vpGaussRand noise(0.5, 10); + long seed = (long)vpTime::measureTimeMs(); + + noise.seed(seed); + for(int i=0; i< 10; i++) { + std::cout << "noise " << i << ": " << noise() << std::endl; + } + return 0; } - return 0; -} \endverbatim Now if you run the previous example you will always get different values: \verbatim -noise 0: 10.5982 -noise 1: 9.19111 -noise 2: 9.82498 -noise 3: 9.07857 -noise 4: 9.9285 -noise 5: 10.3688 -noise 6: 9.75621 -noise 7: 10.3259 -noise 8: 10.4238 -noise 9: 10.2391 + noise 0: 10.5982 + noise 1: 9.19111 + noise 2: 9.82498 + noise 3: 9.07857 + noise 4: 9.9285 + noise 5: 10.3688 + noise 6: 9.75621 + noise 7: 10.3259 + noise 8: 10.4238 + noise 9: 10.2391 \endverbatim - */ +*/ class VISP_EXPORT vpGaussRand { private: @@ -127,7 +128,7 @@ class VISP_EXPORT vpGaussRand /*! Default noise generator constructor. */ - vpGaussRand() : m_rng(), m_mean(0), m_sigma(0), m_AlreadyDone(false), m_x2(0) {} + vpGaussRand() : m_rng(), m_mean(0), m_sigma(0), m_AlreadyDone(false), m_x2(0) { } /*! Gaussian noise random generator constructor. @@ -138,8 +139,7 @@ class VISP_EXPORT vpGaussRand */ vpGaussRand(double sigma_val, double mean_val, long noise_seed = 0) : m_rng(noise_seed), m_mean(mean_val), m_sigma(sigma_val), m_AlreadyDone(false), m_x2(0) - { - } + { } /*! Set the standard deviation and mean for gaussian noise. @@ -165,5 +165,5 @@ class VISP_EXPORT vpGaussRand */ double operator()() { return m_sigma * gaussianDraw() + m_mean; } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpGaussianFilter.h b/modules/core/include/visp3/core/vpGaussianFilter.h index dbc9861a47..96bef2341a 100644 --- a/modules/core/include/visp3/core/vpGaussianFilter.h +++ b/modules/core/include/visp3/core/vpGaussianFilter.h @@ -36,13 +36,15 @@ \brief Gaussian filter class */ -#ifndef vpGaussianFilter_H -#define vpGaussianFilter_H +#ifndef _vpGaussianFilter_H_ +#define _vpGaussianFilter_H_ +#include #include #if defined(VISP_HAVE_SIMDLIB) +BEGIN_VISP_NAMESPACE /*! \class vpGaussianFilter @@ -69,6 +71,6 @@ class VISP_EXPORT vpGaussianFilter class Impl; Impl *m_impl; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpHinkley.h b/modules/core/include/visp3/core/vpHinkley.h index 046e6fa8ae..8cd60dd173 100644 --- a/modules/core/include/visp3/core/vpHinkley.h +++ b/modules/core/include/visp3/core/vpHinkley.h @@ -31,16 +31,19 @@ * Hinkley's cumulative sum test implementation. */ -#ifndef vpHinkley_H -#define vpHinkley_H - /*! \file vpHinkley.h \brief class for Hinkley's cumulative test computation. */ + +#ifndef vpHinkley_H +#define vpHinkley_H + #include #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) + +BEGIN_VISP_NAMESPACE /*! \class vpHinkley \deprecated This class is deprecated. You should rather use vpStatisticalTestHinkley. @@ -165,5 +168,6 @@ class VISP_EXPORT vpHinkley double Tk; double Nk; }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpHistogram.h b/modules/core/include/visp3/core/vpHistogram.h index 2e2b99fdb5..a9b2190c44 100644 --- a/modules/core/include/visp3/core/vpHistogram.h +++ b/modules/core/include/visp3/core/vpHistogram.h @@ -38,11 +38,12 @@ */ -#ifndef vpHistogram_h -#define vpHistogram_h +#ifndef _vpHistogram_h_ +#define _vpHistogram_h_ #include +#include #include #include #include @@ -54,6 +55,7 @@ #include +BEGIN_VISP_NAMESPACE /*! \class vpHistogram \ingroup group_core_histogram @@ -317,5 +319,5 @@ class VISP_EXPORT vpHistogram const vpImage *mp_mask; /*!< Mask that permits to consider only the pixels for which the mask is true.*/ unsigned int m_total; /*!< Cumulated number of pixels in the input image. */ }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpHistogramPeak.h b/modules/core/include/visp3/core/vpHistogramPeak.h index 8d5f63eb89..e1d8e3a8cc 100644 --- a/modules/core/include/visp3/core/vpHistogramPeak.h +++ b/modules/core/include/visp3/core/vpHistogramPeak.h @@ -37,13 +37,14 @@ Class vpHistogramPeak defines a gray level histogram peak. */ -#ifndef vpHistogramPeak_h -#define vpHistogramPeak_h +#ifndef _vpHistogramPeak_h_ +#define _vpHistogramPeak_h_ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpHistogramPeak @@ -64,7 +65,7 @@ class VISP_EXPORT vpHistogramPeak vpHistogramPeak(const vpHistogramPeak &p); /*! Destructor that does nothing. */ - virtual ~vpHistogramPeak() {} + virtual ~vpHistogramPeak() { } vpHistogramPeak &operator=(const vpHistogramPeak &p); bool operator==(const vpHistogramPeak &p) const; @@ -145,5 +146,5 @@ class VISP_EXPORT vpHistogramPeak * c-basic-offset: 2 * End: */ - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpHistogramValey.h b/modules/core/include/visp3/core/vpHistogramValey.h index d0a753b17e..215c6caf8c 100644 --- a/modules/core/include/visp3/core/vpHistogramValey.h +++ b/modules/core/include/visp3/core/vpHistogramValey.h @@ -38,11 +38,12 @@ */ -#ifndef vpHistogramValey_h -#define vpHistogramValey_h +#ifndef _vpHistogramValey_h_ +#define _vpHistogramValey_h_ #include +BEGIN_VISP_NAMESPACE /*! \class vpHistogramValey @@ -139,5 +140,5 @@ class VISP_EXPORT vpHistogramValey : vpHistogramPeak * c-basic-offset: 2 * End: */ - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpHomogeneousMatrix.h b/modules/core/include/visp3/core/vpHomogeneousMatrix.h index 6eb0e353de..9e0e20522d 100644 --- a/modules/core/include/visp3/core/vpHomogeneousMatrix.h +++ b/modules/core/include/visp3/core/vpHomogeneousMatrix.h @@ -39,6 +39,13 @@ #ifndef _vpHomogeneousMatrix_h_ #define _vpHomogeneousMatrix_h_ +#include +#include + +#include + +BEGIN_VISP_NAMESPACE + class vpTranslationVector; class vpPoseVector; class vpMatrix; @@ -48,10 +55,8 @@ class vpThetaUVector; class vpQuaternionVector; class vpPoint; -#include -#include +END_VISP_NAMESPACE -#include #include #include #include @@ -61,6 +66,7 @@ class vpPoint; #include #endif +BEGIN_VISP_NAMESPACE /*! \class vpHomogeneousMatrix @@ -379,7 +385,7 @@ class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D public: static const std::string jsonTypeName; private: - friend void to_json(nlohmann::json &j, const vpHomogeneousMatrix &cam); + friend void to_json(nlohmann::json &j, const vpHomogeneousMatrix &T); friend void from_json(const nlohmann::json &j, vpHomogeneousMatrix &T); // Conversion helper function to avoid circular dependencies and MSVC errors that are not exported in the DLL void parse_json(const nlohmann::json &j); @@ -414,10 +420,11 @@ inline void to_json(nlohmann::json &j, const vpHomogeneousMatrix &T) { T.convert_to_json(j); } + inline void from_json(const nlohmann::json &j, vpHomogeneousMatrix &T) { T.parse_json(j); } #endif - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index f65545cc1f..39552fa9c1 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -66,8 +66,23 @@ typedef unsigned short uint16_t; #include #endif +BEGIN_VISP_NAMESPACE class vpDisplay; +// Ref: http://en.cppreference.com/w/cpp/language/friend#Template_friends +template class vpImage; // forward declare to make function declaration possible + +// declarations +template std::ostream &operator<<(std::ostream &s, const vpImage &I); + +std::ostream &operator<<(std::ostream &s, const vpImage &I); +std::ostream &operator<<(std::ostream &s, const vpImage &I); +std::ostream &operator<<(std::ostream &s, const vpImage &I); +std::ostream &operator<<(std::ostream &s, const vpImage &I); +END_VISP_NAMESPACE +template void swap(VISP_NAMESPACE_ADDRESSING vpImage &first, VISP_NAMESPACE_ADDRESSING vpImage &second); + +BEGIN_VISP_NAMESPACE /*! \class vpImage @@ -117,20 +132,6 @@ value = I[i][j]; // Here we will get the pixel value at position (101, 80) \endcode */ - -// Ref: http://en.cppreference.com/w/cpp/language/friend#Template_friends -template class vpImage; // forward declare to make function declaration possible - -// declarations -template std::ostream &operator<<(std::ostream &, const vpImage &); - -std::ostream &operator<<(std::ostream &, const vpImage &); -std::ostream &operator<<(std::ostream &, const vpImage &); -std::ostream &operator<<(std::ostream &, const vpImage &); -std::ostream &operator<<(std::ostream &, const vpImage &); - -template void swap(vpImage &first, vpImage &second); - template class vpImage { friend class vpImageConvert; @@ -272,7 +273,7 @@ template class vpImage \return Value of the image point (i, j). */ - inline Type operator()(unsigned int i, unsigned int j) const { return bitmap[i * width + j]; } + inline Type operator()(unsigned int i, unsigned int j) const { return bitmap[(i * width) + j]; } /*! Set the value \e v of an image point with coordinates (i, j), with i the @@ -328,7 +329,7 @@ template class vpImage friend std::ostream &operator<<(std::ostream &s, const vpImage &I); friend std::ostream &operator<<(std::ostream &s, const vpImage &I); - // Perform a look-up table transformation + // Perform a look-up table transformation void performLut(const Type(&lut)[256], unsigned int nbThreads = 1); // Returns a new image that's a quarter size of the current image @@ -343,7 +344,7 @@ template class vpImage void sub(const vpImage &A, const vpImage &B, vpImage &C) const; void subsample(unsigned int v_scale, unsigned int h_scale, vpImage &sampled) const; - friend void swap<>(vpImage &first, vpImage &second); + friend void ::swap<>(vpImage &first, vpImage &second); //@} @@ -562,7 +563,7 @@ struct vpImageLutRGBa_Param_t unsigned int m_start_index; unsigned int m_end_index; - vpRGBa m_lut[256]; + VISP_NAMESPACE_ADDRESSING vpRGBa m_lut[256]; unsigned char *m_bitmap; vpImageLutRGBa_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_bitmap(nullptr) { } @@ -1504,7 +1505,7 @@ void vpImage::getMinMaxLoc(vpImagePoint *minLoc, vpImagePoint *maxLoc, Typ */ template vpImage &vpImage::operator=(vpImage other) { - swap(*this, other); + ::swap(*this, other); if (other.display != nullptr) { display = other.display; } @@ -1806,13 +1807,13 @@ template void vpImage::quarterSizeImage(vpImage &res) c */ template void vpImage::doubleSizeImage(vpImage &res) { - int h = height * 2; - int w = width * 2; + unsigned int h = height * 2; + unsigned int w = width * 2; res.resize(h, w); - for (int i = 0; i < h; ++i) { - for (int j = 0; j < w; ++j) { + for (unsigned int i = 0; i < h; ++i) { + for (unsigned int j = 0; j < w; ++j) { res[i][j] = (*this)[i >> 1][j >> 1]; } } @@ -1826,24 +1827,24 @@ template void vpImage::doubleSizeImage(vpImage &res) */ // interpolate pixels B and I - for (int i = 0; i < h; i += 2) { - for (int j = 1; j < (w - 1); j += 2) { - res[i][j] = (Type)(0.5 * ((*this)[i >> 1][j >> 1] + (*this)[i >> 1][(j >> 1) + 1])); + for (unsigned int i = 0; i < h; i += 2) { + for (unsigned int j = 1; j < (w - 1); j += 2) { + res[i][j] = static_cast(0.5 * ((*this)[i >> 1][j >> 1] + (*this)[i >> 1][(j >> 1) + 1])); } } // interpolate pixels E and G - for (int i = 1; i < (h - 1); i += 2) { - for (int j = 0; j < w; j += 2) { - res[i][j] = (Type)(0.5 * ((*this)[i >> 1][j >> 1] + (*this)[(i >> 1) + 1][j >> 1])); + for (unsigned int i = 1; i < (h - 1); i += 2) { + for (unsigned int j = 0; j < w; j += 2) { + res[i][j] = static_cast(0.5 * ((*this)[i >> 1][j >> 1] + (*this)[(i >> 1) + 1][j >> 1])); } } // interpolate pixel F - for (int i = 1; i < (h - 1); i += 2) { - for (int j = 1; j < (w - 1); j += 2) { - res[i][j] = (Type)(0.25 * ((*this)[i >> 1][j >> 1] + (*this)[i >> 1][(j >> 1) + 1] + - (*this)[(i >> 1) + 1][j >> 1] + (*this)[(i >> 1) + 1][(j >> 1) + 1])); + for (unsigned int i = 1; i < (h - 1); i += 2) { + for (unsigned int j = 1; j < (w - 1); j += 2) { + res[i][j] = static_cast(0.25 * ((*this)[i >> 1][j >> 1] + (*this)[i >> 1][(j >> 1) + 1] + + (*this)[(i >> 1) + 1][j >> 1] + (*this)[(i >> 1) + 1][(j >> 1) + 1])); } } } @@ -1957,21 +1958,21 @@ template <> inline unsigned char vpImage::getValue(double i, doub // alpha architecture is bi-endianness. The following optimization makes testImageGetValue failing #if (defined(VISP_LITTLE_ENDIAN) || defined(VISP_BIG_ENDIAN)) && !(defined(__alpha__) || defined(_M_ALPHA)) // Fixed-point arithmetic - const int32_t precision = 1 << 16; - int64_t y = static_cast(i * precision); - int64_t x = static_cast(j * precision); + const uint32_t precision = 1U << 16; + uint64_t y = static_cast(i * precision); + uint64_t x = static_cast(j * precision); - int64_t iround = y & (~0xFFFF); - int64_t jround = x & (~0xFFFF); + uint64_t iround = y & (~0xFFFFU); + uint64_t jround = x & (~0xFFFFU); - int64_t rratio = y - iround; - int64_t cratio = x - jround; + uint64_t rratio = y - iround; + uint64_t cratio = x - jround; - int64_t rfrac = precision - rratio; - int64_t cfrac = precision - cratio; + uint64_t rfrac = precision - rratio; + uint64_t cfrac = precision - cratio; - int64_t x_ = x >> 16; - int64_t y_ = y >> 16; + uint64_t x_ = x >> 16; + uint64_t y_ = y >> 16; if (((y_ + 1) < height) && ((x_ + 1) < width)) { uint16_t up = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + (y_ * width) + x_); @@ -1982,7 +1983,7 @@ template <> inline unsigned char vpImage::getValue(double i, doub 32); } else if ((y_ + 1) < height) { - return static_cast(((row[y_][x_] * rfrac + row[y_ + 1][x_] * rratio)) >> 16); + return static_cast((row[y_][x_] * rfrac + row[y_ + 1][x_] * rratio) >> 16); } else if ((x_ + 1) < width) { uint16_t up = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + (y_ * width) + x_); @@ -2549,8 +2550,8 @@ template <> inline void vpImage::performLut(const vpRGBa(&lut)[256], uns #endif } } - -template void swap(vpImage &first, vpImage &second) +END_VISP_NAMESPACE +template void swap(VISP_NAMESPACE_ADDRESSING vpImage &first, VISP_NAMESPACE_ADDRESSING vpImage &second) { using std::swap; swap(first.bitmap, second.bitmap); @@ -2560,5 +2561,4 @@ template void swap(vpImage &first, vpImage &second) swap(first.height, second.height); swap(first.row, second.row); } - #endif diff --git a/modules/core/include/visp3/core/vpImageCircle.h b/modules/core/include/visp3/core/vpImageCircle.h index 80a7f167a3..997d5c4d54 100644 --- a/modules/core/include/visp3/core/vpImageCircle.h +++ b/modules/core/include/visp3/core/vpImageCircle.h @@ -49,9 +49,10 @@ #include #endif +BEGIN_VISP_NAMESPACE /** * \brief Class that defines a 2D circle in an image. - */ +*/ class VISP_EXPORT vpImageCircle { public: @@ -141,4 +142,5 @@ class VISP_EXPORT vpImageCircle vpImagePoint m_center; float m_radius; }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpImageConvert.h b/modules/core/include/visp3/core/vpImageConvert.h index cf1ad4278f..4a58922a55 100644 --- a/modules/core/include/visp3/core/vpImageConvert.h +++ b/modules/core/include/visp3/core/vpImageConvert.h @@ -75,6 +75,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! \class vpImageConvert @@ -331,5 +332,5 @@ class VISP_EXPORT vpImageConvert static int vpCgr[256]; static int vpCbb[256]; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpImageDraw.h b/modules/core/include/visp3/core/vpImageDraw.h index 88425623a6..0d7aff4406 100644 --- a/modules/core/include/visp3/core/vpImageDraw.h +++ b/modules/core/include/visp3/core/vpImageDraw.h @@ -31,15 +31,16 @@ * Drawing functions. */ -#ifndef _vpImageDraw_h_ -#define _vpImageDraw_h_ - /*! \file vpImageDraw.h \brief Drawing functions for image. */ +#ifndef _vpImageDraw_h_ +#define _vpImageDraw_h_ + +#include #include #include #include @@ -47,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpImageDraw @@ -115,5 +117,5 @@ class VISP_EXPORT vpImageDraw static void drawRectangle(vpImage &I, const vpRect &rectangle, const vpColor &color, bool fill = false, unsigned int thickness = 1); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpImageException.h b/modules/core/include/visp3/core/vpImageException.h index 9770d62326..aa43d9732d 100644 --- a/modules/core/include/visp3/core/vpImageException.h +++ b/modules/core/include/visp3/core/vpImageException.h @@ -31,26 +31,26 @@ * Exceptions that can be emitted by the vpImage class and its derivatives. */ -#ifndef _vpImageException_h_ -#define _vpImageException_h_ - /*! * \file vpImageException.h * \brief error that can be emitted by the vpImage class and its derivatives */ +#ifndef _vpImageException_h_ +#define _vpImageException_h_ + #include #include #include #include - +BEGIN_VISP_NAMESPACE /*! * \class vpImageException * \ingroup group_core_debug * \brief Error that can be emitted by the vpImage class and its derivatives. - */ +*/ class VISP_EXPORT vpImageException : public vpException { public: @@ -90,5 +90,5 @@ class VISP_EXPORT vpImageException : public vpException */ explicit vpImageException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpImageFilter.h b/modules/core/include/visp3/core/vpImageFilter.h index 867f827f3d..365df9407c 100644 --- a/modules/core/include/visp3/core/vpImageFilter.h +++ b/modules/core/include/visp3/core/vpImageFilter.h @@ -31,14 +31,14 @@ * Various image tools, convolution, ... */ +/*! + * \file vpImageFilter.h + * \brief Various image filter, convolution, etc... + */ + #ifndef _vpImageFilter_h_ #define _vpImageFilter_h_ - /*! - * \file vpImageFilter.h - * \brief Various image filter, convolution, etc... - */ - #include #include #include @@ -59,13 +59,14 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! * \class vpImageFilter * * \ingroup group_core_image * * \brief Various image filter, convolution, etc... - */ +*/ class VISP_EXPORT vpImageFilter { public: @@ -1692,9 +1693,9 @@ class VISP_EXPORT vpImageFilter filter[r][c] = filter[r][c] * scale; } } -} + } #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpImageMorphology.h b/modules/core/include/visp3/core/vpImageMorphology.h index 4a2363328f..9ebf79e53b 100644 --- a/modules/core/include/visp3/core/vpImageMorphology.h +++ b/modules/core/include/visp3/core/vpImageMorphology.h @@ -31,14 +31,16 @@ * Morphology tools. */ -#ifndef _vpImageMorphology_h_ -#define _vpImageMorphology_h_ - /*! \file vpImageMorphology.h \brief Various mathematical morphology tools, erosion, dilatation... */ + +#ifndef _vpImageMorphology_h_ +#define _vpImageMorphology_h_ + +#include #include #include #include @@ -48,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpImageMorphology @@ -530,6 +533,7 @@ void vpImageMorphology::dilatation(vpImage &I, const int &size) const T &(*operation)(const T & a, const T & b) = std::max; vpImageMorphology::imageOperation(I, operation, size); } +END_VISP_NAMESPACE #endif /* diff --git a/modules/core/include/visp3/core/vpImagePoint.h b/modules/core/include/visp3/core/vpImagePoint.h index 120385f7b1..e8d34d66dc 100644 --- a/modules/core/include/visp3/core/vpImagePoint.h +++ b/modules/core/include/visp3/core/vpImagePoint.h @@ -31,22 +31,22 @@ * 2D point useful for image processing */ -#ifndef _vpImagePoint_h_ -#define _vpImagePoint_h_ - /*! \file vpImagePoint.h \brief Class that defines a 2D point in an image. This class is useful for image processing */ +#ifndef _vpImagePoint_h_ +#define _vpImagePoint_h_ + #include #include // std::fabs -#include // numeric_limits #include #include +BEGIN_VISP_NAMESPACE class vpRect; /*! @@ -378,5 +378,5 @@ class VISP_EXPORT vpImagePoint private: double i, j; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpImageTools.h b/modules/core/include/visp3/core/vpImageTools.h index a9b0acbd33..89b66be3c4 100644 --- a/modules/core/include/visp3/core/vpImageTools.h +++ b/modules/core/include/visp3/core/vpImageTools.h @@ -31,9 +31,6 @@ * Image tools. */ -#ifndef vpImageTools_H -#define vpImageTools_H - /*! \file vpImageTools.h @@ -41,6 +38,9 @@ the look up table, binarisation... */ +#ifndef _vpImageTools_H_ +#define _vpImageTools_H_ + #include #ifdef VISP_HAVE_THREADS @@ -63,6 +63,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! \class vpImageTools @@ -1464,9 +1465,9 @@ void vpImageTools::warpLinear(const vpImage &src, const vpMatrix &T, vpIma { if (fixedPoint && (!centerCorner)) { const int nbits = 16; - const int64_t precision = 1 << nbits; + const uint64_t precision = 1 << nbits; const float precision_1 = 1 / static_cast(precision); - const int64_t precision2 = 1ULL << (2 * nbits); + const uint64_t precision2 = 1ULL << (2 * nbits); const float precision_2 = 1 / static_cast(precision2); int64_t a0_i64 = static_cast(T[0][0] * precision); @@ -1937,5 +1938,5 @@ inline void vpImageTools::warpLinear(const vpImage &src, const vpMatrix } } } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpIoException.h b/modules/core/include/visp3/core/vpIoException.h index 55cf163360..100721f44f 100644 --- a/modules/core/include/visp3/core/vpIoException.h +++ b/modules/core/include/visp3/core/vpIoException.h @@ -31,25 +31,26 @@ * Exceptions that can be emitted by the vpIo class and its derivatives. */ -#ifndef _vpIoException_h_ -#define _vpIoException_h_ - /*! * \file vpIoException.h * \brief Error that can be emitted by the vpIoTools class and its derivatives. */ +#ifndef _vpIoException_h_ +#define _vpIoException_h_ + #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpIoException * \ingroup group_core_debug * \brief Error that can be emitted by the vpIoTools class and its derivatives. - */ +*/ class VISP_EXPORT vpIoException : public vpException { public: @@ -88,5 +89,5 @@ class VISP_EXPORT vpIoException : public vpException */ explicit vpIoException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpIoTools.h b/modules/core/include/visp3/core/vpIoTools.h index b204c83c6e..e7eb2017c3 100644 --- a/modules/core/include/visp3/core/vpIoTools.h +++ b/modules/core/include/visp3/core/vpIoTools.h @@ -31,14 +31,14 @@ * Directory management. */ -#ifndef _vpIoTools_h_ -#define _vpIoTools_h_ - /*! * \file vpIoTools.h * \brief File and directories basic tools. */ +#ifndef _vpIoTools_h_ +#define _vpIoTools_h_ + #include #include @@ -63,7 +63,7 @@ static inline unsigned long vp_mz_crc32(unsigned long crc, const unsigned char * { static const unsigned int s_crc32[16] = { 0, 0x1db71064, 0x3b6e20c8, 0x26d930ac, 0x76dc4190, 0x6b6b51f4, 0x4db26158, 0x5005713c, 0xedb88320, 0xf00f9344, 0xd6d6a3e8, 0xcb61b38c, 0x9b64c2b0, 0x86d3d2d4, 0xa00ae278, 0xbdbdf21c }; - unsigned int crcu32 = (unsigned int)crc; + unsigned int crcu32 = static_cast(crc); if (!ptr) return 0; crcu32 = ~crcu32; while (buf_len--) { @@ -74,6 +74,7 @@ static inline unsigned long vp_mz_crc32(unsigned long crc, const unsigned char * return ~crcu32; } +#ifdef VISP_HAVE_MINIZ namespace cnpy { // Copyright (C) 2011 Carl Rogers @@ -274,42 +275,42 @@ template void npz_save(std::string zipname, std::string fname, const //build the local header std::vector local_header; local_header += "PK"; //first part of sig - local_header += (uint16_t)0x0403; //second part of sig - local_header += (uint16_t)20; //min version to extract - local_header += (uint16_t)0; //general purpose bit flag - local_header += (uint16_t)0; //compression method - local_header += (uint16_t)0; //file last mod time - local_header += (uint16_t)0; //file last mod date - local_header += (uint32_t)crc; //crc - local_header += (uint32_t)nbytes; //compressed size - local_header += (uint32_t)nbytes; //uncompressed size - local_header += (uint16_t)fname.size(); //fname length - local_header += (uint16_t)0; //extra field length + local_header += static_cast(0x0403); //second part of sig + local_header += static_cast(20); //min version to extract + local_header += static_cast(0); //general purpose bit flag + local_header += static_cast(0); //compression method + local_header += static_cast(0); //file last mod time + local_header += static_cast(0); //file last mod date + local_header += static_cast(crc); //crc + local_header += static_cast(nbytes); //compressed size + local_header += static_cast(nbytes); //uncompressed size + local_header += static_cast(fname.size()); //fname length + local_header += static_cast(0); //extra field length local_header += fname; //build global header global_header += "PK"; //first part of sig - global_header += (uint16_t)0x0201; //second part of sig - global_header += (uint16_t)20; //version made by + global_header += static_cast(0x0201); //second part of sig + global_header += static_cast(20); //version made by global_header.insert(global_header.end(), local_header.begin()+4, local_header.begin()+30); - global_header += (uint16_t)0; //file comment length - global_header += (uint16_t)0; //disk number where file starts - global_header += (uint16_t)0; //internal file attributes - global_header += (uint32_t)0; //external file attributes - global_header += (uint32_t)global_header_offset; //relative offset of local file header, since it begins where the global header used to begin + global_header += static_cast(0); //file comment length + global_header += static_cast(0); //disk number where file starts + global_header += static_cast(0); //internal file attributes + global_header += static_cast(0); //external file attributes + global_header += static_cast(global_header_offset); //relative offset of local file header, since it begins where the global header used to begin global_header += fname; //build footer std::vector footer; footer += "PK"; //first part of sig - footer += (uint16_t)0x0605; //second part of sig - footer += (uint16_t)0; //number of this disk - footer += (uint16_t)0; //disk where footer starts - footer += (uint16_t)(nrecs+1); //number of records on this disk - footer += (uint16_t)(nrecs+1); //total number of records - footer += (uint32_t)global_header.size(); //nbytes of global headers - footer += (uint32_t)(global_header_offset + nbytes + local_header.size()); //offset of start of global headers, since global header now starts after newly written array - footer += (uint16_t)0; //zip file comment length + footer += static_cast(0x0605); //second part of sig + footer += static_cast(0); //number of this disk + footer += static_cast(0); //disk where footer starts + footer += static_cast(nrecs+1); //number of records on this disk + footer += static_cast(nrecs+1); //total number of records + footer += static_cast(global_header.size()); //nbytes of global headers + footer += static_cast(global_header_offset + nbytes + local_header.size()); //offset of start of global headers, since global header now starts after newly written array + footer += static_cast(0); //zip file comment length //write everything fwrite(&local_header[0], sizeof(char), local_header.size(), fp); @@ -374,18 +375,19 @@ template std::vector create_npy_header(const std::vector header; - header += (char)0x93; + header += static_cast(0x93); header += "NUMPY"; - header += (char)0x01; //major version of numpy format - header += (char)0x00; //minor version of numpy format - header += (uint16_t)dict.size(); + header += static_cast(0x01); //major version of numpy format + header += static_cast(0x00); //minor version of numpy format + header += static_cast(dict.size()); header.insert(header.end(), dict.begin(), dict.end()); return header; } } // namespace cnpy -} // namespace visp +#endif +} // namespace VISP_NAMESPACE_NAME #endif /*! @@ -487,6 +489,7 @@ template std::vector create_npy_header(const std::vector +BEGIN_VISP_NAMESPACE /*! -Parse the flag values defined in a JSON object. -if the flags are defined as an int, then this is int is directly returned. -If it is defined as a combination of options (defined from an enumeration E) then the logical or of theses enum values is returned. -Beware that invalid values may be defined in the JSON object: the int value may be invalid, or the parsing of enum values may fail. + Parse the flag values defined in a JSON object. + if the flags are defined as an int, then this is int is directly returned. + If it is defined as a combination of options (defined from an enumeration E) then the logical or of theses enum values is returned. + Beware that invalid values may be defined in the JSON object: the int value may be invalid, or the parsing of enum values may fail. -\param j: the JSON object to parse + \param j: the JSON object to parse -\return an int, corresponding to the combination of boolean flags + \return an int, corresponding to the combination of boolean flags */ template @@ -68,11 +69,11 @@ int flagsFromJSON(const nlohmann::json &j) } /*! - Serialize flag values as a json array. - \param flags the value to serialize - \param options the possible values that can be contained in flags. A flag i is set if flags & options[i] != 0. + Serialize flag values as a json array. + \param flags the value to serialize + \param options the possible values that can be contained in flags. A flag i is set if flags & options[i] != 0. - \return a json object (an array) that contains the different flags of the variable flags. + \return a json object (an array) that contains the different flags of the variable flags. */ template @@ -97,7 +98,8 @@ template bool convertFromTypeAndBuildFrom(const nlohmann::json &j, T &t) { if (j["type"] == O::jsonTypeName) { - O other = j; + O other; + from_json(j, other); t.build(other); return true; } @@ -105,6 +107,6 @@ bool convertFromTypeAndBuildFrom(const nlohmann::json &j, T &t) return convertFromTypeAndBuildFrom(j, t); } } - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpKalmanFilter.h b/modules/core/include/visp3/core/vpKalmanFilter.h index b9461884ec..32ee2b78de 100644 --- a/modules/core/include/visp3/core/vpKalmanFilter.h +++ b/modules/core/include/visp3/core/vpKalmanFilter.h @@ -31,6 +31,11 @@ * Kalman filtering. */ +/*! + \file vpKalmanFilter.h + \brief Generic kalman filtering implementation +*/ + #ifndef vpKalmanFilter_h #define vpKalmanFilter_h @@ -39,11 +44,7 @@ #include -/*! - \file vpKalmanFilter.h - \brief Generic kalman filtering implementation -*/ - +BEGIN_VISP_NAMESPACE /*! \class vpKalmanFilter \ingroup group_core_kalman @@ -125,7 +126,7 @@ class VISP_EXPORT vpKalmanFilter explicit vpKalmanFilter(unsigned int n_signal); vpKalmanFilter(unsigned int size_state, unsigned int size_measure, unsigned int n_signal); /*! Destructor that does noting. */ - virtual ~vpKalmanFilter(){}; + virtual ~vpKalmanFilter() { }; /*! Set the number of signal to filter. */ @@ -211,5 +212,5 @@ class VISP_EXPORT vpKalmanFilter //! Identity matrix \f$ \bf I\f$. vpMatrix I; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpLinProg.h b/modules/core/include/visp3/core/vpLinProg.h index 7edbb3c2d3..d8dd28bf6b 100644 --- a/modules/core/include/visp3/core/vpLinProg.h +++ b/modules/core/include/visp3/core/vpLinProg.h @@ -31,6 +31,11 @@ * Linear Programming with simplex */ +/*! + \file vpLinProg.h + \brief Implementation of Linear Program with simplex algorithm. +*/ + #ifndef vpLinProgh #define vpLinProgh @@ -41,11 +46,7 @@ #include #include -/*! - \file vpLinProg.h - \brief Implementation of Linear Program with simplex algorithm. -*/ - +BEGIN_VISP_NAMESPACE /*! \class vpLinProg \ingroup group_core_optim @@ -222,4 +223,5 @@ class VISP_EXPORT vpLinProg } //@} }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpLine.h b/modules/core/include/visp3/core/vpLine.h index 44082d8da2..61ea644b47 100644 --- a/modules/core/include/visp3/core/vpLine.h +++ b/modules/core/include/visp3/core/vpLine.h @@ -31,19 +31,21 @@ * Line feature. */ -#ifndef vpLine_H -#define vpLine_H - /*! * \file vpLine.h * \brief class that defines what is a line */ +#ifndef _vpLine_H_ +#define _vpLine_H_ + +#include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpLine * \ingroup group_core_geometry @@ -96,7 +98,7 @@ * in the vpTracker::p public attribute, where \e p is a vector defined * as: \f[ p = \left[\begin{array}{c} \rho \\ \theta \end{array}\right] \f] * To compute these parameters use projection(). To get the corresponding values use get_p(). - */ +*/ class VISP_EXPORT vpLine : public vpForwardProjection { public: @@ -172,5 +174,5 @@ class VISP_EXPORT vpLine : public vpForwardProjection protected: void init() vp_override; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpLinearKalmanFilterInstantiation.h b/modules/core/include/visp3/core/vpLinearKalmanFilterInstantiation.h index d6d7b207ac..584fd9734c 100644 --- a/modules/core/include/visp3/core/vpLinearKalmanFilterInstantiation.h +++ b/modules/core/include/visp3/core/vpLinearKalmanFilterInstantiation.h @@ -31,6 +31,11 @@ * Kalman filtering. */ +/*! + \file vpLinearKalmanFilterInstantiation.h + \brief Implementation of some specific linear Kalman filters. +*/ + #ifndef vpLinearKalmanFilterInstantiation_h #define vpLinearKalmanFilterInstantiation_h @@ -38,11 +43,7 @@ #include -/*! - \file vpLinearKalmanFilterInstantiation.h - \brief Implementation of some specific linear Kalman filters. -*/ - +BEGIN_VISP_NAMESPACE /*! \class vpLinearKalmanFilterInstantiation \ingroup group_core_kalman @@ -156,5 +157,5 @@ void vpLinearKalmanFilterInstantiation::setStateModel(vpStateModel mdl) break; } } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpList.h b/modules/core/include/visp3/core/vpList.h index ac5ce23642..854f5ce6dc 100644 --- a/modules/core/include/visp3/core/vpList.h +++ b/modules/core/include/visp3/core/vpList.h @@ -31,14 +31,14 @@ * List data structure. */ -#ifndef VP_LIST_H -#define VP_LIST_H - /*! * \file vpList.h * \brief Definition of the list management class */ +#ifndef _VP_LIST_H_ +#define _VP_LIST_H_ + #include #include #include @@ -47,6 +47,7 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE /*! \class vpListElement \brief Each element of a list @@ -704,7 +705,7 @@ template void vpList::display() } std::cout << std::endl << std::endl; } - +END_VISP_NAMESPACE #endif /* #ifndef VP_LIST_H */ /* diff --git a/modules/core/include/visp3/core/vpMath.h b/modules/core/include/visp3/core/vpMath.h index 02359de94a..5bee7e898d 100644 --- a/modules/core/include/visp3/core/vpMath.h +++ b/modules/core/include/visp3/core/vpMath.h @@ -37,8 +37,8 @@ * the C mathematics library (math.h) */ -#ifndef vpMATH_HH -#define vpMATH_HH +#ifndef _vpMATH_H_ +#define _vpMATH_H_ #include @@ -92,6 +92,8 @@ #include #include +BEGIN_VISP_NAMESPACE + class vpPoint; class vpHomogeneousMatrix; class vpColVector; @@ -104,7 +106,7 @@ class vpTranslationVector; * \ingroup group_core_math_tools * \brief Provides simple mathematics computation tools that are not * available in the C mathematics library (math.h) - */ +*/ class VISP_EXPORT vpMath { public: @@ -662,5 +664,5 @@ template <> inline unsigned int vpMath::saturate(double v) { return static_cast(vpMath::round(v)); } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMatrix.h b/modules/core/include/visp3/core/vpMatrix.h index 00d2d8c080..4c985d1c5e 100644 --- a/modules/core/include/visp3/core/vpMatrix.h +++ b/modules/core/include/visp3/core/vpMatrix.h @@ -31,11 +31,28 @@ * Matrix manipulation. */ -#ifndef vpMatrix_H -#define vpMatrix_H +/*! + \file vpMatrix.h + + \brief Definition of matrix class as well as a set of operations on + these matrices. +*/ + +#ifndef _vpMatrix_H_ +#define _vpMatrix_H_ -#include #include +BEGIN_VISP_NAMESPACE + +class vpRowVector; +class vpColVector; +class vpTranslationVector; +class vpHomogeneousMatrix; +class vpVelocityTwistMatrix; +class vpForceTwistMatrix; +END_VISP_NAMESPACE + +#include #include #include #include @@ -46,19 +63,7 @@ #include #include -class vpRowVector; -class vpColVector; -class vpTranslationVector; -class vpHomogeneousMatrix; -class vpVelocityTwistMatrix; -class vpForceTwistMatrix; - -/*! - \file vpMatrix.h - - \brief Definition of matrix class as well as a set of operations on - these matrices. -*/ +BEGIN_VISP_NAMESPACE /*! \class vpMatrix @@ -1200,4 +1205,6 @@ __declspec(selectany) unsigned int vpMatrix::m_lapack_min_size = vpMatrix::m_lap VISP_EXPORT #endif vpMatrix operator*(const double &x, const vpMatrix &A); + +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMatrixException.h b/modules/core/include/visp3/core/vpMatrixException.h index edc9e136a1..c8d084b7f9 100644 --- a/modules/core/include/visp3/core/vpMatrixException.h +++ b/modules/core/include/visp3/core/vpMatrixException.h @@ -40,11 +40,12 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpMatrixException * \ingroup group_core_debug * \brief error that can be emitted by the vpMatrix class and its derivatives - */ +*/ class VISP_EXPORT vpMatrixException : public vpException { public: @@ -99,5 +100,5 @@ class VISP_EXPORT vpMatrixException : public vpException */ explicit vpMatrixException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMeterPixelConversion.h b/modules/core/include/visp3/core/vpMeterPixelConversion.h index be918b527f..5aae2c2fc4 100644 --- a/modules/core/include/visp3/core/vpMeterPixelConversion.h +++ b/modules/core/include/visp3/core/vpMeterPixelConversion.h @@ -31,15 +31,14 @@ * Meter to pixel conversion. */ -#ifndef _vpMeterPixelConversion_h_ -#define _vpMeterPixelConversion_h_ - /*! \file vpMeterPixelConversion.h \brief Meter to pixel conversion. - */ +#ifndef _vpMeterPixelConversion_h_ +#define _vpMeterPixelConversion_h_ + #include #include #include @@ -51,6 +50,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! \class vpMeterPixelConversion @@ -353,5 +353,5 @@ class VISP_EXPORT vpMeterPixelConversion //@} #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMoment.h b/modules/core/include/visp3/core/vpMoment.h index 60ccc96ed4..1adcadac59 100644 --- a/modules/core/include/visp3/core/vpMoment.h +++ b/modules/core/include/visp3/core/vpMoment.h @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE class vpMomentDatabase; class vpMomentObject; @@ -100,7 +101,7 @@ class vpMomentObject; * - vpMomentCInvariant * - vpMomentGravityCenter * - vpMomentGravityCenterNormalized - */ +*/ class VISP_EXPORT vpMoment { private: @@ -154,4 +155,5 @@ class VISP_EXPORT vpMoment //@} friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMoment &m); }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentAlpha.h b/modules/core/include/visp3/core/vpMomentAlpha.h index 1e0a991482..cf1352963b 100644 --- a/modules/core/include/visp3/core/vpMomentAlpha.h +++ b/modules/core/include/visp3/core/vpMomentAlpha.h @@ -39,8 +39,11 @@ #ifndef _vpMomentAlpha_h_ #define _vpMomentAlpha_h_ +#include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpMomentAlpha * @@ -198,7 +201,7 @@ * Shortcuts for quickly getting those references exist in vpMomentCommon. * * This moment depends on vpMomentCentered. - */ +*/ class VISP_EXPORT vpMomentAlpha : public vpMoment { private: @@ -249,5 +252,5 @@ class VISP_EXPORT vpMomentAlpha : public vpMoment friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAlpha &v); void printDependencies(std::ostream &os) const; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentArea.h b/modules/core/include/visp3/core/vpMomentArea.h index ccef048ad6..556d65d419 100644 --- a/modules/core/include/visp3/core/vpMomentArea.h +++ b/modules/core/include/visp3/core/vpMomentArea.h @@ -33,8 +33,10 @@ #ifndef _vpMomentArea_h_ #define _vpMomentArea_h_ +#include #include +BEGIN_VISP_NAMESPACE class vpMomentObject; class vpMomentCentered; // Required for discrete case of vpMomentObject @@ -52,7 +54,7 @@ class vpMomentCentered; // Required for discrete case of vpMomentObject * corresponds to the number of points. Since this is of no use in a servoing * scheme, this class uses in this case \f$ a = \mu_{20} + \mu_{02} \f$, which is * invariant to planar translation and rotation. - */ +*/ class VISP_EXPORT vpMomentArea : public vpMoment { public: @@ -67,5 +69,5 @@ class VISP_EXPORT vpMomentArea : public vpMoment //@} friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentArea &m); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentAreaNormalized.h b/modules/core/include/visp3/core/vpMomentAreaNormalized.h index 212ad34ffe..6e5ae0e920 100644 --- a/modules/core/include/visp3/core/vpMomentAreaNormalized.h +++ b/modules/core/include/visp3/core/vpMomentAreaNormalized.h @@ -37,8 +37,10 @@ #ifndef _vpMomentAreaNormalized_h_ #define _vpMomentAreaNormalized_h_ +#include #include +BEGIN_VISP_NAMESPACE class vpMomentObject; class vpMomentCentered; @@ -128,7 +130,7 @@ class vpMomentCentered; * \code * An:1.41421 * \endcode - */ +*/ class VISP_EXPORT vpMomentAreaNormalized : public vpMoment { private: @@ -181,5 +183,5 @@ class VISP_EXPORT vpMomentAreaNormalized : public vpMoment friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAreaNormalized &v); void printDependencies(std::ostream &os) const; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentBasic.h b/modules/core/include/visp3/core/vpMomentBasic.h index e0bc51abb2..ffa7488ac4 100644 --- a/modules/core/include/visp3/core/vpMomentBasic.h +++ b/modules/core/include/visp3/core/vpMomentBasic.h @@ -39,8 +39,11 @@ #ifndef _vpMomentBasic_h_ #define _vpMomentBasic_h_ +#include #include +BEGIN_VISP_NAMESPACE + /*! \class vpMomentBasic @@ -81,4 +84,5 @@ class VISP_EXPORT vpMomentBasic : public vpMoment friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentBasic &v); void printDependencies(std::ostream &os) const; }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentCInvariant.h b/modules/core/include/visp3/core/vpMomentCInvariant.h index 58290fd9e4..7dd2cdf2b4 100644 --- a/modules/core/include/visp3/core/vpMomentCInvariant.h +++ b/modules/core/include/visp3/core/vpMomentCInvariant.h @@ -39,9 +39,11 @@ #ifndef _vpMomentCInvariant_h_ #define _vpMomentCInvariant_h_ +#include #include #include +BEGIN_VISP_NAMESPACE class vpMomentCentered; class vpMomentBasic; @@ -278,4 +280,5 @@ class VISP_EXPORT vpMomentCInvariant : public vpMoment friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentCInvariant &v); }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentCentered.h b/modules/core/include/visp3/core/vpMomentCentered.h index 0f6afae38c..579799dafb 100644 --- a/modules/core/include/visp3/core/vpMomentCentered.h +++ b/modules/core/include/visp3/core/vpMomentCentered.h @@ -31,16 +31,18 @@ * Centered moment descriptor */ -#ifndef _vpMomentCentered_h_ -#define _vpMomentCentered_h_ - -#include /*! \file vpMomentCentered.h \brief Centered moment descriptor (also referred as \f$\mu_{ij}\f$). - */ +#ifndef _vpMomentCentered_h_ +#define _vpMomentCentered_h_ + +#include +#include + +BEGIN_VISP_NAMESPACE class vpMomentObject; /*! @@ -127,5 +129,5 @@ mu12 = mc.get(1,2); // the same \endcode */ inline const std::vector &vpMomentCentered::get() const { return vpMoment::get(); } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentCommon.h b/modules/core/include/visp3/core/vpMomentCommon.h index a6b112ebb3..a5a2322002 100644 --- a/modules/core/include/visp3/core/vpMomentCommon.h +++ b/modules/core/include/visp3/core/vpMomentCommon.h @@ -49,6 +49,7 @@ #include +BEGIN_VISP_NAMESPACE class vpMomentObject; /*! @@ -137,4 +138,5 @@ class VISP_EXPORT vpMomentCommon : public vpMomentDatabase void updateAll(vpMomentObject &object) vp_override; }; +END_VISP_NAMESPACE #endif // VPCOMMONMOMENTS_H diff --git a/modules/core/include/visp3/core/vpMomentDatabase.h b/modules/core/include/visp3/core/vpMomentDatabase.h index 0cd4d7cee1..66d0070bf5 100644 --- a/modules/core/include/visp3/core/vpMomentDatabase.h +++ b/modules/core/include/visp3/core/vpMomentDatabase.h @@ -44,6 +44,7 @@ #include #include +BEGIN_VISP_NAMESPACE class vpMoment; class vpMomentObject; @@ -123,7 +124,7 @@ class vpMomentObject; * Consequently, a database can contain at most one moment of each type. Often it * is useful to update all moments with the same object. Shortcuts * (vpMomentDatabase::updateAll) are provided for that matter. - */ +*/ class VISP_EXPORT vpMomentDatabase { private: @@ -158,5 +159,5 @@ class VISP_EXPORT vpMomentDatabase friend class vpMoment; friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentDatabase &v); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentGravityCenter.h b/modules/core/include/visp3/core/vpMomentGravityCenter.h index 83e61ecfb2..37506a7c5d 100644 --- a/modules/core/include/visp3/core/vpMomentGravityCenter.h +++ b/modules/core/include/visp3/core/vpMomentGravityCenter.h @@ -38,8 +38,11 @@ #ifndef _vpMomentGravityCenter_h_ #define _vpMomentGravityCenter_h_ +#include #include #include + +BEGIN_VISP_NAMESPACE class vpMomentObject; /*! @@ -103,7 +106,7 @@ class vpMomentObject; * Yg=-0.00833333 * Xg=0.0166667, Yg=-0.00833333 * \endcode - */ +*/ class VISP_EXPORT vpMomentGravityCenter : public vpMoment { @@ -132,5 +135,5 @@ class VISP_EXPORT vpMomentGravityCenter : public vpMoment //@} friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenter &v); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentGravityCenterNormalized.h b/modules/core/include/visp3/core/vpMomentGravityCenterNormalized.h index 6523a74a17..b745ac8930 100644 --- a/modules/core/include/visp3/core/vpMomentGravityCenterNormalized.h +++ b/modules/core/include/visp3/core/vpMomentGravityCenterNormalized.h @@ -41,6 +41,8 @@ #include #include + +BEGIN_VISP_NAMESPACE class vpMomentObject; /*! @@ -56,7 +58,7 @@ class vpMomentObject; * vpMomentGravityCenterNormalized depends on vpMomentAreaNormalized to get * access to \f$a_n\f$ and on vpMomentGravityCenter to get access to * \f$(x_g,y_g)\f$ . - */ +*/ class VISP_EXPORT vpMomentGravityCenterNormalized : public vpMomentGravityCenter { public: @@ -67,5 +69,6 @@ class VISP_EXPORT vpMomentGravityCenterNormalized : public vpMomentGravityCenter void printDependencies(std::ostream &os) const; friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenterNormalized &v); }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMomentObject.h b/modules/core/include/visp3/core/vpMomentObject.h index fb8e1af6ff..3892b8133b 100644 --- a/modules/core/include/visp3/core/vpMomentObject.h +++ b/modules/core/include/visp3/core/vpMomentObject.h @@ -39,11 +39,13 @@ #include #include +#include #include #include #include #include +BEGIN_VISP_NAMESPACE class vpCameraParameters; /*! @@ -310,5 +312,6 @@ class VISP_EXPORT vpMomentObject void cacheValues(std::vector &cache, double x, double y, double IntensityNormalized); double calc_mom_polygon(unsigned int p, unsigned int q, const std::vector &points); }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMouseButton.h b/modules/core/include/visp3/core/vpMouseButton.h index 3d68601f20..5c72ba5841 100644 --- a/modules/core/include/visp3/core/vpMouseButton.h +++ b/modules/core/include/visp3/core/vpMouseButton.h @@ -31,11 +31,12 @@ * Color definition. */ -#ifndef vpMouseButton_h -#define vpMouseButton_h +#ifndef _vpMouseButton_h_ +#define _vpMouseButton_h_ #include +BEGIN_VISP_NAMESPACE /*! \class vpMouseButton \ingroup group_gui_display @@ -44,12 +45,13 @@ class VISP_EXPORT vpMouseButton { public: - typedef enum { + typedef enum + { button1 = 1, /*!< Mouse left button. */ button2 = 2, /*!< Mouse middle button, or roll. */ button3 = 3, /*!< Mouse right button. */ none = 0 /*!< No button. */ } vpMouseButtonType; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMunkres.h b/modules/core/include/visp3/core/vpMunkres.h index 27d9c0c2a7..d89857e0f7 100644 --- a/modules/core/include/visp3/core/vpMunkres.h +++ b/modules/core/include/visp3/core/vpMunkres.h @@ -46,6 +46,7 @@ // Internal #include "vpMath.h" +BEGIN_VISP_NAMESPACE /*! \class vpMunkres \ingroup group_core_munkres @@ -53,7 +54,7 @@ Implements the Munkres Assignment Algorithm described [here](https://en.wikipedia.org/wiki/Hungarian_algorithm). \note This class is only available with c++17 enabled. - */ +*/ class VISP_EXPORT vpMunkres { public: @@ -369,5 +370,5 @@ inline std::vector > vpMunkres::run(std::v return ret; } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpMutex.h b/modules/core/include/visp3/core/vpMutex.h index 9c05b9d067..950f4f5547 100644 --- a/modules/core/include/visp3/core/vpMutex.h +++ b/modules/core/include/visp3/core/vpMutex.h @@ -48,6 +48,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +namespace VISP_NAMESPACE_NAME +{ +#endif /*! \class vpMutex @@ -184,6 +188,8 @@ class vp_deprecated vpMutex HANDLE m_mutex; #endif }; - +#ifdef ENABLE_VISP_NAMESPACE +} +#endif #endif #endif diff --git a/modules/core/include/visp3/core/vpNetwork.h b/modules/core/include/visp3/core/vpNetwork.h index 45da39ad9f..26ef8e8936 100644 --- a/modules/core/include/visp3/core/vpNetwork.h +++ b/modules/core/include/visp3/core/vpNetwork.h @@ -65,6 +65,7 @@ #include // To detect OSX or IOS using TARGET_OS_IPHONE or TARGET_OS_IOS macro #endif +BEGIN_VISP_NAMESPACE /*! \class vpNetwork @@ -501,6 +502,6 @@ template int vpNetwork::sendTo(T *object, const unsigned int &dest, flags, (sockaddr *)&receptor_list[dest].receptorAddress, receptor_list[dest].receptorAddressSize); #endif } - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpPixelMeterConversion.h b/modules/core/include/visp3/core/vpPixelMeterConversion.h index 5531eb231e..c3cacbc985 100644 --- a/modules/core/include/visp3/core/vpPixelMeterConversion.h +++ b/modules/core/include/visp3/core/vpPixelMeterConversion.h @@ -31,14 +31,14 @@ * Pixel to meter conversion. */ -#ifndef _vpPixelMeterConversion_h_ -#define _vpPixelMeterConversion_h_ - /*! \file vpPixelMeterConversion.h \brief pixel to meter conversion - */ + +#ifndef _vpPixelMeterConversion_h_ +#define _vpPixelMeterConversion_h_ + #include #include #include @@ -50,6 +50,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! \class vpPixelMeterConversion @@ -384,5 +385,5 @@ class VISP_EXPORT vpPixelMeterConversion //@} #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpPlane.h b/modules/core/include/visp3/core/vpPlane.h index 7c150a641f..9741cd713c 100644 --- a/modules/core/include/visp3/core/vpPlane.h +++ b/modules/core/include/visp3/core/vpPlane.h @@ -31,13 +31,16 @@ * Plane geometrical structure. */ -#ifndef vpPlane_hh -#define vpPlane_hh +#ifndef _vpPlane_h_ +#define _vpPlane_h_ +#include #include #include #include +BEGIN_VISP_NAMESPACE + /*! \class vpPlane @@ -145,7 +148,7 @@ class VISP_EXPORT vpPlane vpColVector getNormal() const; void getNormal(vpColVector &n) const; - friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpPlane &p); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpPlane &p); // Operation with Plane void projectionPointOnPlan(const vpPoint &P, vpPoint &Pproj) const; @@ -155,5 +158,5 @@ class VISP_EXPORT vpPlane double getIntersection(const vpColVector &M1, vpColVector &H) const; void changeFrame(const vpHomogeneousMatrix &cMo); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpPoint.h b/modules/core/include/visp3/core/vpPoint.h index b2f4f069b3..2232816dec 100644 --- a/modules/core/include/visp3/core/vpPoint.h +++ b/modules/core/include/visp3/core/vpPoint.h @@ -31,20 +31,22 @@ * Point feature. */ -#ifndef vpPoint_H -#define vpPoint_H - /*! \file vpPoint.h \brief class that defines what is a point */ -class vpHomogeneousMatrix; +#ifndef _vpPoint_H_ +#define _vpPoint_H_ +#include #include #include #include +BEGIN_VISP_NAMESPACE +class vpHomogeneousMatrix; + /*! \class vpPoint \ingroup group_core_geometry @@ -148,5 +150,5 @@ class VISP_EXPORT vpPoint : public vpForwardProjection //! Basic construction. void init() vp_override; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpPolygon.h b/modules/core/include/visp3/core/vpPolygon.h index 55386999c2..d0dfa15be2 100644 --- a/modules/core/include/visp3/core/vpPolygon.h +++ b/modules/core/include/visp3/core/vpPolygon.h @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpPolygon \ingroup group_core_geometry @@ -202,5 +203,5 @@ class VISP_EXPORT vpPolygon static bool isInside(const std::vector &roi, const double &i, const double &j, const PointInPolygonMethod &method = PnPolyRayCasting); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpPolygon3D.h b/modules/core/include/visp3/core/vpPolygon3D.h index cb3e5b3bb2..4c9f5899bb 100644 --- a/modules/core/include/visp3/core/vpPolygon3D.h +++ b/modules/core/include/visp3/core/vpPolygon3D.h @@ -41,10 +41,12 @@ #include +#include #include #include #include +BEGIN_VISP_NAMESPACE /*! \class vpPolygon3D \ingroup group_core_geometry @@ -54,7 +56,8 @@ class VISP_EXPORT vpPolygon3D { public: - typedef enum { + typedef enum + { NO_CLIPPING = 0, NEAR_CLIPPING = 1, FAR_CLIPPING = 2, @@ -213,31 +216,35 @@ class VISP_EXPORT vpPolygon3D static void getMinMaxRoi(const std::vector &roi, int &i_min, int &i_max, int &j_min, int &j_max); static bool roiInsideImage(const vpImage &I, const std::vector &corners); }; - +END_VISP_NAMESPACE #ifdef VISP_HAVE_NLOHMANN_JSON #include #include -NLOHMANN_JSON_SERIALIZE_ENUM( vpPolygon3D::vpPolygon3DClippingType, { - {vpPolygon3D::NO_CLIPPING, "none"}, - {vpPolygon3D::NEAR_CLIPPING, "near"}, - {vpPolygon3D::FAR_CLIPPING, "far"}, - {vpPolygon3D::LEFT_CLIPPING, "left"}, - {vpPolygon3D::RIGHT_CLIPPING, "right"}, - {vpPolygon3D::UP_CLIPPING, "up"}, - {vpPolygon3D::DOWN_CLIPPING, "down"}, - {vpPolygon3D::FOV_CLIPPING, "fov"}, - {vpPolygon3D::ALL_CLIPPING, "all"} +NLOHMANN_JSON_SERIALIZE_ENUM(VISP_NAMESPACE_ADDRESSING vpPolygon3D::vpPolygon3DClippingType, { + {VISP_NAMESPACE_ADDRESSING vpPolygon3D::NO_CLIPPING, "none"}, + {VISP_NAMESPACE_ADDRESSING vpPolygon3D::NEAR_CLIPPING, "near"}, + {VISP_NAMESPACE_ADDRESSING vpPolygon3D::FAR_CLIPPING, "far"}, + {VISP_NAMESPACE_ADDRESSING vpPolygon3D::LEFT_CLIPPING, "left"}, + {VISP_NAMESPACE_ADDRESSING vpPolygon3D::RIGHT_CLIPPING, "right"}, + {VISP_NAMESPACE_ADDRESSING vpPolygon3D::UP_CLIPPING, "up"}, + {VISP_NAMESPACE_ADDRESSING vpPolygon3D::DOWN_CLIPPING, "down"}, + {VISP_NAMESPACE_ADDRESSING vpPolygon3D::FOV_CLIPPING, "fov"}, + {VISP_NAMESPACE_ADDRESSING vpPolygon3D::ALL_CLIPPING, "all"} }); -inline nlohmann::json clippingFlagsToJSON(const int flags) { +inline nlohmann::json clippingFlagsToJSON(const int flags) +{ +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif constexpr std::array specificFlags = { vpPolygon3D::ALL_CLIPPING, vpPolygon3D::FOV_CLIPPING, vpPolygon3D::NO_CLIPPING }; - for(const auto f: specificFlags) { - if(flags == f) { + for (const auto f: specificFlags) { + if (flags == f) { return nlohmann::json::array({ f }); } } @@ -252,5 +259,4 @@ inline nlohmann::json clippingFlagsToJSON(const int flags) { } #endif - #endif diff --git a/modules/core/include/visp3/core/vpPoseVector.h b/modules/core/include/visp3/core/vpPoseVector.h index 170b81459d..35fca304c7 100644 --- a/modules/core/include/visp3/core/vpPoseVector.h +++ b/modules/core/include/visp3/core/vpPoseVector.h @@ -32,9 +32,6 @@ * a rotation vector (theta u representation) and t is a translation vector. */ -#ifndef vpPOSEVECTOR_H -#define vpPOSEVECTOR_H - /*! \file vpPoseVector.h @@ -43,11 +40,8 @@ translation vector. */ -class vpRotationMatrix; -class vpHomogeneousMatrix; -class vpTranslationVector; -class vpThetaUVector; -class vpRowVector; +#ifndef _vpPOSEVECTOR_H_ +#define _vpPOSEVECTOR_H_ #include #include @@ -55,9 +49,12 @@ class vpRowVector; #include #include -#ifdef VISP_HAVE_NLOHMANN_JSON -#include -#endif +BEGIN_VISP_NAMESPACE +class vpRotationMatrix; +class vpHomogeneousMatrix; +class vpTranslationVector; +class vpThetaUVector; +class vpRowVector; /*! \class vpPoseVector @@ -200,6 +197,8 @@ class VISP_EXPORT vpPoseVector : public vpArray2D // constructor convert a translation and a rotation matrix into a pose vpPoseVector(const vpTranslationVector &tv, const vpRotationMatrix &R); + virtual ~vpPoseVector() { } + #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS vp_deprecated vpPoseVector buildFrom(double tx, double ty, double tz, double tux, double tuy, double tuz); // convert an homogeneous matrix in a pose @@ -331,10 +330,11 @@ inline void to_json(nlohmann::json &j, const vpPoseVector &r) { r.convert_to_json(j); } + inline void from_json(const nlohmann::json &j, vpPoseVector &r) { r.parse_json(j); } #endif - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpQuadProg.h b/modules/core/include/visp3/core/vpQuadProg.h index 052dcbd1d0..1064d2430a 100644 --- a/modules/core/include/visp3/core/vpQuadProg.h +++ b/modules/core/include/visp3/core/vpQuadProg.h @@ -31,6 +31,11 @@ * Quadratic Programming */ +/*! + * \file vpQuadProg.h + * \brief Implementation of Quadratic Program with Active Sets. + */ + #ifndef _vpQuadProg_h_ #define _vpQuadProg_h_ @@ -41,11 +46,7 @@ #include #include -/*! - * \file vpQuadProg.h - * \brief Implementation of Quadratic Program with Active Sets. - */ - +BEGIN_VISP_NAMESPACE /*! * \class vpQuadProg * \ingroup group_core_optim @@ -65,7 +66,7 @@ * * \warning The solvers are only available if c++11 or higher is activated during build. * Configure ViSP using cmake -DUSE_CXX_STANDARD=11. - */ +*/ class VISP_EXPORT vpQuadProg { public: @@ -159,4 +160,5 @@ class VISP_EXPORT vpQuadProg } #endif }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpQuaternionVector.h b/modules/core/include/visp3/core/vpQuaternionVector.h index b9b4af1470..b27d824f80 100644 --- a/modules/core/include/visp3/core/vpQuaternionVector.h +++ b/modules/core/include/visp3/core/vpQuaternionVector.h @@ -31,9 +31,6 @@ * Quaternion definition. */ -#ifndef _vpQuaternionVector_h_ -#define _vpQuaternionVector_h_ - /*! * \file vpQuaternionVector.h * @@ -41,11 +38,15 @@ * operations on it. */ +#ifndef _vpQuaternionVector_h_ +#define _vpQuaternionVector_h_ + #include #include #include #include +BEGIN_VISP_NAMESPACE /*! \class vpQuaternionVector @@ -100,7 +101,7 @@ double z = q.z(); double w = q.w(); \endcode - */ +*/ class VISP_EXPORT vpQuaternionVector : public vpRotationVector { public: @@ -164,5 +165,5 @@ class VISP_EXPORT vpQuaternionVector : public vpRotationVector static const double minimum; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRGBa.h b/modules/core/include/visp3/core/vpRGBa.h index 772ba97f3a..9157ff2a26 100644 --- a/modules/core/include/visp3/core/vpRGBa.h +++ b/modules/core/include/visp3/core/vpRGBa.h @@ -31,17 +31,19 @@ * RGBA pixel. */ -#ifndef vpRGBa_h -#define vpRGBa_h - /*! \file vpRGBa.h \brief Define the object vpRGBa that is used to build color images (it defines a RGB 32 bits structure, fourth byte is not used) */ +#ifndef _vpRGBa_h_ +#define _vpRGBa_h_ + +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpRGBa @@ -141,5 +143,5 @@ class VISP_EXPORT vpRGBa friend VISP_EXPORT vpRGBa operator*(const double &x, const vpRGBa &rgb); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRGBf.h b/modules/core/include/visp3/core/vpRGBf.h index 828a59b087..1bccac9ac4 100644 --- a/modules/core/include/visp3/core/vpRGBf.h +++ b/modules/core/include/visp3/core/vpRGBf.h @@ -31,17 +31,20 @@ * 32-bit floating point RGB pixel. */ -#ifndef vpRGBf_h -#define vpRGBf_h - /*! \file vpRGBf.h \brief Define the object vpRGBf that is used to build color images (it defines a RGB 32-bit floating point structure) */ +#ifndef _vpRGBf_h_ +#define _vpRGBf_h_ + +#include #include +BEGIN_VISP_NAMESPACE + /*! \class vpRGBf @@ -127,5 +130,5 @@ class VISP_EXPORT vpRGBf friend VISP_EXPORT vpRGBf operator*(double x, const vpRGBf &rgb); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRansac.h b/modules/core/include/visp3/core/vpRansac.h index 2be17d461c..f795ed7987 100644 --- a/modules/core/include/visp3/core/vpRansac.h +++ b/modules/core/include/visp3/core/vpRansac.h @@ -35,15 +35,17 @@ \file vpRansac.h */ -#ifndef vpRANSAC_HH -#define vpRANSAC_HH +#ifndef _vpRANSAC_H_ +#define _vpRANSAC_H_ #include +#include #include #include // debug and trace #include #include // random number generation +BEGIN_VISP_NAMESPACE /*! \class vpRansac \ingroup group_core_robust @@ -61,7 +63,7 @@ http://www.csse.uwa.edu.au/~pk \sa vpHomography - */ +*/ template class vpRansac { public: @@ -241,5 +243,5 @@ bool vpRansac::ransac(unsigned int npts, const vpColVector &x, return true; } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRect.h b/modules/core/include/visp3/core/vpRect.h index 3b93213427..797c535a6b 100644 --- a/modules/core/include/visp3/core/vpRect.h +++ b/modules/core/include/visp3/core/vpRect.h @@ -31,8 +31,18 @@ * Defines a rectangle in the plane. */ -#ifndef vpRect_h -#define vpRect_h +#ifndef _vpRect_h_ +#define _vpRect_h_ + +#include +#include +#include // numeric_limits +#include +#include +#include +#include + +BEGIN_VISP_NAMESPACE /*! \class vpRect @@ -65,13 +75,6 @@ setting sizes, e.g. setWidth(), setHeight() */ - -#include -#include -#include -#include -#include - class VISP_EXPORT vpRect { public: @@ -408,5 +411,5 @@ class VISP_EXPORT vpRect double width; // Rectangle width double height; // Rectangle height }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRectOriented.h b/modules/core/include/visp3/core/vpRectOriented.h index afe8667a66..26397a196e 100644 --- a/modules/core/include/visp3/core/vpRectOriented.h +++ b/modules/core/include/visp3/core/vpRectOriented.h @@ -31,18 +31,19 @@ * Defines a (possibly oriented) rectangle in the plane. */ -#ifndef vpRectOriented_h -#define vpRectOriented_h +#ifndef _vpRectOriented_h_ +#define _vpRectOriented_h_ +#include +#include +#include + +BEGIN_VISP_NAMESPACE /*! * \class vpRectOriented * \ingroup group_core_geometry * \brief Defines an oriented rectangle in the plane. - */ - -#include -#include - +*/ class VISP_EXPORT vpRectOriented { public: @@ -105,4 +106,5 @@ class VISP_EXPORT vpRectOriented vpImagePoint m_bottomRight; bool isLeft(const vpImagePoint &pointToTest, const vpImagePoint &point1, const vpImagePoint &point2) const; }; -#endif // vpRectOriented_h +END_VISP_NAMESPACE +#endif // _vpRectOriented_h_ diff --git a/modules/core/include/visp3/core/vpRequest.h b/modules/core/include/visp3/core/vpRequest.h index 20939485e7..9836a10b85 100644 --- a/modules/core/include/visp3/core/vpRequest.h +++ b/modules/core/include/visp3/core/vpRequest.h @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpRequest @@ -225,5 +226,5 @@ template void vpRequest::addParameterObject(T *params, const int &s delete[] tempS; } } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRobust.h b/modules/core/include/visp3/core/vpRobust.h index 5738838e87..23e3b42b66 100644 --- a/modules/core/include/visp3/core/vpRobust.h +++ b/modules/core/include/visp3/core/vpRobust.h @@ -38,10 +38,11 @@ #ifndef vpRobust_h #define vpRobust_h -#include #include +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpRobust \ingroup group_core_robust @@ -244,5 +245,5 @@ class VISP_EXPORT vpRobust double select(vpColVector &a, int l, int r, int k); //@} }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRotationMatrix.h b/modules/core/include/visp3/core/vpRotationMatrix.h index 81fa71b15a..9a740665ce 100644 --- a/modules/core/include/visp3/core/vpRotationMatrix.h +++ b/modules/core/include/visp3/core/vpRotationMatrix.h @@ -31,14 +31,14 @@ * Rotation matrix. */ -#ifndef _vpRotationMatrix_h_ -#define _vpRotationMatrix_h_ - /*! \file vpRotationMatrix.h \brief Class that consider the particular case of rotation matrix */ +#ifndef _vpRotationMatrix_h_ +#define _vpRotationMatrix_h_ + #include #include #include @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpRotationMatrix @@ -230,6 +231,6 @@ class VISP_EXPORT vpRotationMatrix : public vpArray2D #ifndef DOXYGEN_SHOULD_SKIP_THIS VISP_EXPORT #endif -vpRotationMatrix operator*(const double &x, const vpRotationMatrix &R); - +VISP_NAMESPACE_ADDRESSING vpRotationMatrix operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRotationMatrix &R); +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRotationVector.h b/modules/core/include/visp3/core/vpRotationVector.h index ac49de5431..c6bd3c47b6 100644 --- a/modules/core/include/visp3/core/vpRotationVector.h +++ b/modules/core/include/visp3/core/vpRotationVector.h @@ -31,21 +31,24 @@ * Generic rotation vector (cannot be used as is !). */ -#ifndef _vpRotationVector_h_ -#define _vpRotationVector_h_ - /*! \file vpRotationVector.h \brief class that consider the case of a generic rotation vector (cannot be used as is !) */ +#ifndef _vpRotationVector_h_ +#define _vpRotationVector_h_ + #include #include #include +#include #include +BEGIN_VISP_NAMESPACE + class vpRowVector; class vpColVector; @@ -155,6 +158,6 @@ class VISP_EXPORT vpRotationVector : public vpArray2D #ifndef DOXYGEN_SHOULD_SKIP_THIS VISP_EXPORT #endif -vpColVector operator*(const double &x, const vpRotationVector &v); - +VISP_NAMESPACE_ADDRESSING vpColVector operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRotationVector &v); +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRowVector.h b/modules/core/include/visp3/core/vpRowVector.h index 3119f303da..8154ab01e0 100644 --- a/modules/core/include/visp3/core/vpRowVector.h +++ b/modules/core/include/visp3/core/vpRowVector.h @@ -31,16 +31,19 @@ * Operation on row vectors. */ -#ifndef vpRowVector_H -#define vpRowVector_H +#ifndef _vpRowVector_H_ +#define _vpRowVector_H_ #include +#include #include #include #include #include +BEGIN_VISP_NAMESPACE + class vpMatrix; class vpColVector; @@ -336,4 +339,5 @@ class VISP_EXPORT vpRowVector : public vpArray2D VISP_EXPORT vpRowVector operator*(const double &x, const vpRowVector &v); +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRxyzVector.h b/modules/core/include/visp3/core/vpRxyzVector.h index 64a957b833..111bf8172a 100644 --- a/modules/core/include/visp3/core/vpRxyzVector.h +++ b/modules/core/include/visp3/core/vpRxyzVector.h @@ -32,9 +32,6 @@ * Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi). */ -#ifndef _vpRxyzVector_h_ -#define _vpRxyzVector_h_ - /*! \file vpRxyzVector.h @@ -44,10 +41,15 @@ Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi) */ +#ifndef _vpRxyzVector_h_ +#define _vpRxyzVector_h_ + #include #include #include +BEGIN_VISP_NAMESPACE + class vpRotationVector; class vpRotationMatrix; class vpThetaUVector; @@ -216,5 +218,5 @@ class VISP_EXPORT vpRxyzVector : public vpRotationVector vpRxyzVector &operator=(const std::initializer_list &list); #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRzyxVector.h b/modules/core/include/visp3/core/vpRzyxVector.h index 0ed07dc55b..87c39fcfa8 100644 --- a/modules/core/include/visp3/core/vpRzyxVector.h +++ b/modules/core/include/visp3/core/vpRzyxVector.h @@ -32,9 +32,6 @@ * Rzyx(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(x,psi) */ -#ifndef _vpRzyxVector_h_ -#define _vpRzyxVector_h_ - /*! \file vpRzyxVector.h @@ -44,13 +41,18 @@ Rzyx(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(x,psi) */ -class vpRotationMatrix; -class vpThetaUVector; +#ifndef _vpRzyxVector_h_ +#define _vpRzyxVector_h_ #include #include #include +BEGIN_VISP_NAMESPACE + +class vpRotationMatrix; +class vpThetaUVector; + /*! \class vpRzyxVector @@ -217,5 +219,5 @@ class VISP_EXPORT vpRzyxVector : public vpRotationVector vpRzyxVector &operator=(const std::initializer_list &list); #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpRzyzVector.h b/modules/core/include/visp3/core/vpRzyzVector.h index ae50e1f228..b5f7164614 100644 --- a/modules/core/include/visp3/core/vpRzyzVector.h +++ b/modules/core/include/visp3/core/vpRzyzVector.h @@ -32,9 +32,6 @@ * Rzyz(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(z,psi) */ -#ifndef _vpRzyzVector_h_ -#define _vpRzyzVector_h_ - /*! \file vpRzyzVector.h \brief class that consider the case of the Rzyz angles parameterization @@ -43,13 +40,18 @@ Rzyz(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(z,psi) */ -class vpRotationMatrix; -class vpThetaUVector; +#ifndef _vpRzyzVector_h_ +#define _vpRzyzVector_h_ #include #include #include +BEGIN_VISP_NAMESPACE + +class vpRotationMatrix; +class vpThetaUVector; + /*! \class vpRzyzVector @@ -216,4 +218,5 @@ class VISP_EXPORT vpRzyzVector : public vpRotationVector vpRzyzVector &operator=(const std::initializer_list &list); #endif }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpScale.h b/modules/core/include/visp3/core/vpScale.h index 98da42ad49..28d51f32eb 100644 --- a/modules/core/include/visp3/core/vpScale.h +++ b/modules/core/include/visp3/core/vpScale.h @@ -51,6 +51,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpScale \ingroup group_core_robust @@ -63,7 +64,7 @@ \author Andrew Comport \date 24/10/03 - */ +*/ class VISP_EXPORT vpScale { @@ -85,5 +86,5 @@ class VISP_EXPORT vpScale double KernelDensity_EPANECHNIKOV(vpColVector &X); double KernelDensityGradient_EPANECHNIKOV(double X, unsigned int n); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpSerial.h b/modules/core/include/visp3/core/vpSerial.h index 1707e9c619..c961e49ca5 100644 --- a/modules/core/include/visp3/core/vpSerial.h +++ b/modules/core/include/visp3/core/vpSerial.h @@ -41,6 +41,7 @@ #include +BEGIN_VISP_NAMESPACE /*! \class vpSerial \ingroup group_core_com_serial @@ -68,7 +69,8 @@ class VISP_EXPORT vpSerial /*! * Defines the possible byte sizes for the serial port. */ - typedef enum { + typedef enum + { fivebits = 5, //!< Data is encoded with 5 bits sixbits = 6, //!< Data is encoded with 6 bits sevenbits = 7, //!< Data is encoded with 7 bits @@ -78,7 +80,8 @@ class VISP_EXPORT vpSerial /*! * Defines the possible parity types for the serial port. */ - typedef enum { + typedef enum + { parity_none = 0, //!< No parity check parity_odd = 1, //!< Check for odd parity parity_even = 2 //!< Check for even parity @@ -87,7 +90,8 @@ class VISP_EXPORT vpSerial /*! * Defines the possible stopbit types for the serial port. */ - typedef enum { + typedef enum + { stopbits_one = 1, //!< 1 stop bit is used stopbits_two = 2, //!< 2 stop bits are used } stopbits_t; @@ -95,7 +99,8 @@ class VISP_EXPORT vpSerial /*! * Defines the possible flowcontrol types for the serial port. */ - typedef enum { + typedef enum + { flowcontrol_none = 0, //!< No flow control flowcontrol_software, //!< Software flow control flowcontrol_hardware //!< Hardware flow control @@ -173,6 +178,6 @@ class VISP_EXPORT vpSerial stopbits_t m_stopbits; flowcontrol_t m_flowcontrol; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpServer.h b/modules/core/include/visp3/core/vpServer.h index 2ab89b9ded..9a5d19a0e1 100644 --- a/modules/core/include/visp3/core/vpServer.h +++ b/modules/core/include/visp3/core/vpServer.h @@ -42,6 +42,7 @@ // inet_ntop() not supported on win XP #ifdef VISP_HAVE_FUNC_INET_NTOP +BEGIN_VISP_NAMESPACE /*! \class vpServer @@ -216,6 +217,6 @@ class VISP_EXPORT vpServer : public vpNetwork */ void setMaxNumberOfClients(const unsigned int &l) { max_clients = l; } }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpSphere.h b/modules/core/include/visp3/core/vpSphere.h index 706d6c29b3..ebcdd14427 100644 --- a/modules/core/include/visp3/core/vpSphere.h +++ b/modules/core/include/visp3/core/vpSphere.h @@ -36,15 +36,18 @@ * \brief forward projection of a sphere */ -#ifndef vpSphere_hh -#define vpSphere_hh +#ifndef _vpSphere_h_ +#define _vpSphere_h_ +#include #include #include #include #include #include + +BEGIN_VISP_NAMESPACE /*! * \class vpSphere * \ingroup group_core_geometry @@ -73,7 +76,7 @@ * projection(const vpColVector &cP, vpColVector &p) const. They could be retrieved using get_x(), get_y(), get_n20(), * get_n11() and get_n02(). They correspond to 2D normalized sphere parameters with values expressed in meters. * To get theses parameters use get_p(). - */ +*/ class VISP_EXPORT vpSphere : public vpForwardProjection { public: @@ -148,5 +151,5 @@ class VISP_EXPORT vpSphere : public vpForwardProjection void init() vp_override; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h index cd7e0454e9..00e4617f27 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h +++ b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h @@ -44,6 +44,7 @@ #include +BEGIN_VISP_NAMESPACE /** * \ingroup group_core_math_tools * \brief Base class for methods detecting the drift of the mean of a process. @@ -52,7 +53,7 @@ * testDownwardMeanDrift().To detect only upward drifts in \f$ s(t) \f$ use * testUpwardMeanDrift(). To detect both, downward and upward drifts use * testDownUpwardMeanDrift(). - */ +*/ class VISP_EXPORT vpStatisticalTestAbstract { public: @@ -262,5 +263,5 @@ class VISP_EXPORT vpStatisticalTestAbstract */ vpMeanDriftType testUpwardMeanDrift(const float &signal); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h index 63893668c9..f2cc7cddcc 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h +++ b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h @@ -41,6 +41,7 @@ #include +BEGIN_VISP_NAMESPACE /** * \ingroup group_core_math_tools * \brief Class that permits to perform Exponentially Weighted Moving Average mean drft tests. @@ -66,7 +67,7 @@ * testDownwardMeanDrift().To detect only upward drifts in \f$ s(t) \f$ use * testUpwardMeanDrift(). To detect both, downward and upward drifts use * testDownUpwardMeanDrift(). - */ +*/ class VISP_EXPORT vpStatisticalTestEWMA : public vpStatisticalTestAbstract { protected: @@ -179,4 +180,5 @@ class VISP_EXPORT vpStatisticalTestEWMA : public vpStatisticalTestAbstract */ void setAlpha(const float &alpha); }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestHinkley.h b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h index 9a8dcc2724..58203015a7 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestHinkley.h +++ b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h @@ -41,6 +41,7 @@ #include +BEGIN_VISP_NAMESPACE /** * \ingroup group_core_math_tools * \brief This class implements the Hinkley's cumulative sum test. @@ -83,7 +84,7 @@ If a drift is detected, the drift location is given by the last instant \f$k^{'}\f$ when \f$ M_{k^{'}} - S_{k^{'}} = 0 \f$, or \f$ T_{k^{'}} - N_{k^{'}} = 0 \f$. - */ +*/ class VISP_EXPORT vpStatisticalTestHinkley : public vpStatisticalTestAbstract { protected: @@ -329,5 +330,5 @@ class VISP_EXPORT vpStatisticalTestHinkley : public vpStatisticalTestAbstract */ void setAlpha(const float &alpha); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h index 8a39d7d8f0..6bad84f5f9 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h +++ b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h @@ -41,6 +41,7 @@ #include +BEGIN_VISP_NAMESPACE /** * \ingroup group_core_math_tools * \brief Class that permits to perform a mean adjusted Cumulative Sum test. @@ -76,7 +77,7 @@ * testDownwardMeanDrift().To detect only upward drifts in \f$ s(t) \f$ use * testUpwardMeanDrift(). To detect both, downward and upward drifts use * testDownUpwardMeanDrift(). - */ +*/ class VISP_EXPORT vpStatisticalTestMeanAdjustedCUSUM : public vpStatisticalTestAbstract { protected: @@ -271,4 +272,5 @@ class VISP_EXPORT vpStatisticalTestMeanAdjustedCUSUM : public vpStatisticalTestA m_limitUp = limitUp; } }; +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h index 9954831496..ed12e3aee1 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h +++ b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /** * \ingroup group_core_math_tools * \brief Class that permits a Shewhart's test. @@ -68,7 +69,7 @@ * testDownwardMeanDrift().To detect only upward drifts in \f$ s(t) \f$ use * testUpwardMeanDrift(). To detect both, downward and upward drifts use * testDownUpwardMeanDrift(). - */ +*/ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma { @@ -238,5 +239,5 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma */ void init(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1], const float &mean, const float &stdev); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestSigma.h b/modules/core/include/visp3/core/vpStatisticalTestSigma.h index 210da6eba0..b5dd794fca 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestSigma.h +++ b/modules/core/include/visp3/core/vpStatisticalTestSigma.h @@ -41,6 +41,7 @@ #include +BEGIN_VISP_NAMESPACE /** * \ingroup group_core_math_tools * \brief Class that permits a simple test comparing the current value to the @@ -63,7 +64,7 @@ * testDownwardMeanDrift().To detect only upward drifts in \f$ s(t) \f$ use * testUpwardMeanDrift(). To detect both, downward and upward drifts use * testDownUpwardMeanDrift(). - */ +*/ class VISP_EXPORT vpStatisticalTestSigma : public vpStatisticalTestAbstract { @@ -169,5 +170,5 @@ class VISP_EXPORT vpStatisticalTestSigma : public vpStatisticalTestAbstract */ void init(const float &h, const float &mean, const float &stdev); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpSubColVector.h b/modules/core/include/visp3/core/vpSubColVector.h index 8d339f0795..668aa200e1 100644 --- a/modules/core/include/visp3/core/vpSubColVector.h +++ b/modules/core/include/visp3/core/vpSubColVector.h @@ -31,17 +31,19 @@ * Mask on a vpColVector. */ -#ifndef _vpSubColVector_h_ -#define _vpSubColVector_h_ - -#include - /*! * \file vpSubColVector.h * * \brief Definition of the vpSubColVector class */ +#ifndef _vpSubColVector_h_ +#define _vpSubColVector_h_ + +#include +#include + +BEGIN_VISP_NAMESPACE /*! * \class vpSubColVector * \ingroup group_core_matrices @@ -51,7 +53,7 @@ * a vpSubColVector. * * \sa vpMatrix vpColVector vpRowVector - */ +*/ class VISP_EXPORT vpSubColVector : public vpColVector { public: @@ -85,5 +87,5 @@ class VISP_EXPORT vpSubColVector : public vpColVector }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpSubMatrix.h b/modules/core/include/visp3/core/vpSubMatrix.h index 7f23ce2c44..8177146d1a 100644 --- a/modules/core/include/visp3/core/vpSubMatrix.h +++ b/modules/core/include/visp3/core/vpSubMatrix.h @@ -31,17 +31,19 @@ * Mask on a vpMatrix. */ -#ifndef _vpSubMatrix_h_ -#define _vpSubMatrix_h_ - -#include - /*! * \file vpSubMatrix.h * * \brief Definition of the vpSubMatrix class */ +#ifndef _vpSubMatrix_h_ +#define _vpSubMatrix_h_ + +#include +#include + +BEGIN_VISP_NAMESPACE /*! * \class vpSubMatrix * \ingroup group_core_matrices @@ -50,7 +52,7 @@ * * * \sa vpMatrix vpColVector vpRowVector - */ +*/ class VISP_EXPORT vpSubMatrix : public vpMatrix { @@ -90,5 +92,5 @@ class VISP_EXPORT vpSubMatrix : public vpMatrix //! Copy constructor unavailable vpSubMatrix(const vpSubMatrix &m /* m */); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpSubRowVector.h b/modules/core/include/visp3/core/vpSubRowVector.h index 4ed0bc0b0e..f90d5afd5c 100644 --- a/modules/core/include/visp3/core/vpSubRowVector.h +++ b/modules/core/include/visp3/core/vpSubRowVector.h @@ -31,17 +31,19 @@ * Mask on a vpRowVector. */ -#ifndef _vpSubRowVector_h_ -#define _vpSubRowVector_h_ - -#include - /*! * \file vpSubRowVector.h * * \brief Definition of the vpSubRowVector class */ +#ifndef _vpSubRowVector_h_ +#define _vpSubRowVector_h_ + +#include +#include + +BEGIN_VISP_NAMESPACE /*! * \class vpSubRowVector * \ingroup group_core_matrices @@ -51,7 +53,7 @@ * a vpSubRowVector. * * \sa vpMatrix vpColVector vpRowVector - */ +*/ class VISP_EXPORT vpSubRowVector : public vpRowVector { @@ -79,5 +81,5 @@ class VISP_EXPORT vpSubRowVector : public vpRowVector //! Copy constructor unavailable vpSubRowVector(const vpSubRowVector &m /* m */); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpThetaUVector.h b/modules/core/include/visp3/core/vpThetaUVector.h index 5c4c3bb5cc..998dca9bf3 100644 --- a/modules/core/include/visp3/core/vpThetaUVector.h +++ b/modules/core/include/visp3/core/vpThetaUVector.h @@ -31,15 +31,25 @@ * Theta U parameterization for the rotation. */ -#ifndef _vpThetaUVector_h_ -#define _vpThetaUVector_h_ - /*! \file vpThetaUVector.h \brief class that consider the case of the Theta U parameterization for the rotation */ +#ifndef _vpThetaUVector_h_ +#define _vpThetaUVector_h_ + +#include +#include +#include +#include +#include +#include +#include + +BEGIN_VISP_NAMESPACE + class vpHomogeneousMatrix; class vpRotationMatrix; class vpPoseVector; @@ -50,15 +60,6 @@ class vpColVector; class vpRotationVector; class vpQuaternionVector; -#include -#include -#include -#include -#include -#include -#include -#include - /*! \class vpThetaUVector @@ -241,5 +242,5 @@ class VISP_EXPORT vpThetaUVector : public vpRotationVector static const double minimum; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpThread.h b/modules/core/include/visp3/core/vpThread.h index be654680a1..b710683a68 100644 --- a/modules/core/include/visp3/core/vpThread.h +++ b/modules/core/include/visp3/core/vpThread.h @@ -48,6 +48,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +namespace VISP_NAMESPACE_NAME +{ +#endif /*! \class vpThread @@ -59,7 +63,7 @@ This class implements native pthread functionalities if available, or native Windows threading capabilities if pthread is not available under Windows. - */ +*/ class vp_deprecated vpThread { public: @@ -179,6 +183,8 @@ class vp_deprecated vpThread bool m_isCreated; //!< Indicates if the thread is created bool m_isJoinable; //!< Indicates if the thread is joinable }; - +#ifdef ENABLE_VISP_NAMESPACE +} +#endif #endif #endif diff --git a/modules/core/include/visp3/core/vpTime.h b/modules/core/include/visp3/core/vpTime.h index 78a3649b7f..e43e832264 100644 --- a/modules/core/include/visp3/core/vpTime.h +++ b/modules/core/include/visp3/core/vpTime.h @@ -31,13 +31,14 @@ * Time management and measurement. */ -#ifndef vpTime_h -#define vpTime_h - /*! \file vpTime.h \brief Time management and measurement */ + +#ifndef _vpTime_h_ +#define _vpTime_h_ + #include #include #include @@ -47,6 +48,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * \ingroup group_core_time * \brief Time management and measurement. @@ -66,7 +68,7 @@ * } * } * \endcode - */ +*/ namespace vpTime { @@ -99,5 +101,5 @@ class VISP_EXPORT vpChrono double m_lastTimePoint; #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpTracker.h b/modules/core/include/visp3/core/vpTracker.h index bbf40cc4b1..693f2727b2 100644 --- a/modules/core/include/visp3/core/vpTracker.h +++ b/modules/core/include/visp3/core/vpTracker.h @@ -31,18 +31,20 @@ * Generic tracker. */ -#ifndef vpTracker_H -#define vpTracker_H - /*! * \file vpTracker.h * \brief Class that defines what is a generic tracker. */ +#ifndef _vpTracker_H_ +#define _vpTracker_H_ + +#include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpTracker * \ingroup group_core_trackers @@ -54,7 +56,7 @@ * - in the image plane \e p. These parameters are located in the public * attribute vpTracker::p. They correspond to normalized coordinates * of the feature expressed in meters. - */ +*/ class VISP_EXPORT vpTracker { public: @@ -103,5 +105,5 @@ class VISP_EXPORT vpTracker void init(); //@} }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpTrackingException.h b/modules/core/include/visp3/core/vpTrackingException.h index c17e6bcd9a..0c4f37cda9 100644 --- a/modules/core/include/visp3/core/vpTrackingException.h +++ b/modules/core/include/visp3/core/vpTrackingException.h @@ -31,23 +31,26 @@ * Exceptions that can be emitted by the vpTracking class and its derivatives. */ -#ifndef _vpTrackingException_H -#define _vpTrackingException_H - /*! * \file vpTrackingException.h * \brief error that can be emitted by the vpTracker class and its derivatives */ +#ifndef _vpTrackingException_H_ +#define _vpTrackingException_H_ + #include #include +#include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpTrackingException * \ingroup group_core_debug * \brief Error that can be emitted by the vpTracker class and its derivatives. - */ +*/ class VISP_EXPORT vpTrackingException : public vpException { public: @@ -87,5 +90,5 @@ class VISP_EXPORT vpTrackingException : public vpException */ explicit vpTrackingException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpTranslationVector.h b/modules/core/include/visp3/core/vpTranslationVector.h index 48e1a3b440..48ee1c194f 100644 --- a/modules/core/include/visp3/core/vpTranslationVector.h +++ b/modules/core/include/visp3/core/vpTranslationVector.h @@ -31,20 +31,22 @@ * Translation vector. */ -#ifndef vpTRANSLATIONVECTOR_H -#define vpTRANSLATIONVECTOR_H - /*! * \file vpTranslationVector.h * \brief Class that consider the case of a translation vector. */ +#ifndef _vpTRANSLATIONVECTOR_H_ +#define _vpTRANSLATIONVECTOR_H_ + #include #include #include -#include #include +BEGIN_VISP_NAMESPACE +class vpMatrix; + /*! \class vpTranslationVector @@ -207,5 +209,5 @@ class VISP_EXPORT vpTranslationVector : public vpArray2D protected: unsigned int m_index; // index used for operator<< and operator, to fill a vector }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpTriangle.h b/modules/core/include/visp3/core/vpTriangle.h index de27604290..f6048d8710 100644 --- a/modules/core/include/visp3/core/vpTriangle.h +++ b/modules/core/include/visp3/core/vpTriangle.h @@ -34,6 +34,11 @@ #ifndef vpTriangle_h #define vpTriangle_h +#include +#include +#include + +BEGIN_VISP_NAMESPACE /*! \class vpTriangle \ingroup group_core_geometry @@ -45,11 +50,6 @@ vpImagePoint class documentation for more details about the frame.) are \f$ (0,0) \f$, \f$ (1,0) \f$ and \f$ (0,1) \f$. */ - -#include -#include -#include - class VISP_EXPORT vpTriangle { private: @@ -107,5 +107,5 @@ class VISP_EXPORT vpTriangle private: void init(const vpImagePoint &iP1, const vpImagePoint &iP2, const vpImagePoint &iP3); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpUDPClient.h b/modules/core/include/visp3/core/vpUDPClient.h index 75d36acd44..3e4131cdda 100644 --- a/modules/core/include/visp3/core/vpUDPClient.h +++ b/modules/core/include/visp3/core/vpUDPClient.h @@ -51,6 +51,7 @@ #define VP_MAX_UDP_PAYLOAD 508 +BEGIN_VISP_NAMESPACE /*! * \class vpUDPClient * @@ -160,7 +161,7 @@ * \endcode * * \sa vpUDPServer - */ +*/ class VISP_EXPORT vpUDPClient { public: @@ -194,6 +195,6 @@ class VISP_EXPORT vpUDPClient void close(); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpUDPServer.h b/modules/core/include/visp3/core/vpUDPServer.h index 351f20a2f7..76e30eae08 100644 --- a/modules/core/include/visp3/core/vpUDPServer.h +++ b/modules/core/include/visp3/core/vpUDPServer.h @@ -51,6 +51,7 @@ #define VP_MAX_UDP_PAYLOAD 508 +BEGIN_VISP_NAMESPACE /*! \class vpUDPServer @@ -217,6 +218,6 @@ class VISP_EXPORT vpUDPServer void init(const std::string &hostname, int port); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpUKSigmaDrawerAbstract.h b/modules/core/include/visp3/core/vpUKSigmaDrawerAbstract.h index 24e51c8259..f43dadbb69 100644 --- a/modules/core/include/visp3/core/vpUKSigmaDrawerAbstract.h +++ b/modules/core/include/visp3/core/vpUKSigmaDrawerAbstract.h @@ -41,6 +41,7 @@ #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include +BEGIN_VISP_NAMESPACE /*! \class vpUKSigmaDrawerAbstract \ingroup group_core_kalman @@ -79,5 +80,6 @@ class VISP_EXPORT vpUKSigmaDrawerAbstract protected: unsigned int m_n; /*!< The size of the state of the UKF.*/ }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpUKSigmaDrawerMerwe.h b/modules/core/include/visp3/core/vpUKSigmaDrawerMerwe.h index cd0039da9d..ca154cceda 100644 --- a/modules/core/include/visp3/core/vpUKSigmaDrawerMerwe.h +++ b/modules/core/include/visp3/core/vpUKSigmaDrawerMerwe.h @@ -42,6 +42,7 @@ #include #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +BEGIN_VISP_NAMESPACE /*! \class vpUKSigmaDrawerMerwe \ingroup group_core_kalman @@ -146,5 +147,6 @@ class VISP_EXPORT vpUKSigmaDrawerMerwe : public vpUKSigmaDrawerAbstract vpAddSubFunction m_resFunc; /*!< Residual function expressed in the state space.*/ vpAddSubFunction m_addFunc; /*!< Addition function expressed in the state space.*/ }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpUniRand.h b/modules/core/include/visp3/core/vpUniRand.h index 50b30457b5..df7030aa98 100644 --- a/modules/core/include/visp3/core/vpUniRand.h +++ b/modules/core/include/visp3/core/vpUniRand.h @@ -82,6 +82,8 @@ typedef unsigned __int32 uint32_t; #endif #include + +BEGIN_VISP_NAMESPACE /*! \class vpUniRand @@ -172,5 +174,5 @@ class VISP_EXPORT vpUniRand float m_maxInvFlt; pcg32_random_t m_rng; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpUnscentedKalman.h b/modules/core/include/visp3/core/vpUnscentedKalman.h index 60c3eba162..fe074dbd58 100644 --- a/modules/core/include/visp3/core/vpUnscentedKalman.h +++ b/modules/core/include/visp3/core/vpUnscentedKalman.h @@ -44,6 +44,7 @@ #include // std::function #include // std::shared_ptr +BEGIN_VISP_NAMESPACE /*! \class vpUnscentedKalman \ingroup group_core_kalman @@ -426,6 +427,6 @@ class VISP_EXPORT vpUnscentedKalman static vpUnscentedTransformResult unscentedTransform(const std::vector &sigmaPoints, const std::vector &wm, const std::vector &wc, const vpMatrix &cov, const vpAddSubFunction &resFunc, const vpMeanFunction &meanFunc); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpVelocityTwistMatrix.h b/modules/core/include/visp3/core/vpVelocityTwistMatrix.h index 8e954cf2fa..d7044aeb4a 100644 --- a/modules/core/include/visp3/core/vpVelocityTwistMatrix.h +++ b/modules/core/include/visp3/core/vpVelocityTwistMatrix.h @@ -31,18 +31,19 @@ * Velocity twist transformation matrix. */ -#ifndef vpVelocityTwistMatrix_h -#define vpVelocityTwistMatrix_h +#ifndef _vpVelocityTwistMatrix_h_ +#define _vpVelocityTwistMatrix_h_ #include #include #include #include -#include #include -class vpHomogeneousMatrix; +BEGIN_VISP_NAMESPACE class vpColVector; +class vpHomogeneousMatrix; +class vpMatrix; /*! \class vpVelocityTwistMatrix @@ -239,5 +240,5 @@ class VISP_EXPORT vpVelocityTwistMatrix : public vpArray2D //@} #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/core/include/visp3/core/vpXmlParser.h b/modules/core/include/visp3/core/vpXmlParser.h index e069a59c9e..adce5cad4f 100644 --- a/modules/core/include/visp3/core/vpXmlParser.h +++ b/modules/core/include/visp3/core/vpXmlParser.h @@ -31,14 +31,14 @@ * Tools to automatize the creation of xml parser based on the libXML2 */ -#ifndef vpXmlParser_HH -#define vpXmlParser_HH - /*! \file vpXmlParser.h \brief Tools to simplify the creation of xml parser based on the libXML2 */ +#ifndef vpXmlParser_HH +#define vpXmlParser_HH + #include #ifdef VISP_HAVE_XML2 @@ -54,6 +54,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpXmlParser @@ -309,7 +310,7 @@ class VISP_EXPORT vpXmlParser static void cleanup() { xmlCleanupParser(); } //@} }; - +END_VISP_NAMESPACE #endif /* VISP_HAVE_XML2 */ #endif diff --git a/modules/core/include/visp3/core/vpXmlParserCamera.h b/modules/core/include/visp3/core/vpXmlParserCamera.h index ebfb896dca..c36ae99d5b 100644 --- a/modules/core/include/visp3/core/vpXmlParserCamera.h +++ b/modules/core/include/visp3/core/vpXmlParserCamera.h @@ -38,14 +38,15 @@ */ -#ifndef vpXMLPARSERCAMERA_H -#define vpXMLPARSERCAMERA_H +#ifndef _vpXMLPARSERCAMERA_H_ +#define _vpXMLPARSERCAMERA_H_ #include #if defined(VISP_HAVE_PUGIXML) #include +BEGIN_VISP_NAMESPACE /*! \class vpXmlParserCamera @@ -198,5 +199,6 @@ class VISP_EXPORT vpXmlParserCamera class Impl; Impl *m_impl; }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpXmlParserHomogeneousMatrix.h b/modules/core/include/visp3/core/vpXmlParserHomogeneousMatrix.h index b99d65609b..62fae4ac1e 100644 --- a/modules/core/include/visp3/core/vpXmlParserHomogeneousMatrix.h +++ b/modules/core/include/visp3/core/vpXmlParserHomogeneousMatrix.h @@ -39,14 +39,15 @@ */ -#ifndef VP_XMLPARSERHOMOGENEOUSMATRIX_H -#define VP_XMLPARSERHOMOGENEOUSMATRIX_H +#ifndef _VP_XMLPARSERHOMOGENEOUSMATRIX_H_ +#define _VP_XMLPARSERHOMOGENEOUSMATRIX_H_ #include #if defined(VISP_HAVE_PUGIXML) #include +BEGIN_VISP_NAMESPACE /*! \class vpXmlParserHomogeneousMatrix @@ -171,5 +172,6 @@ class VISP_EXPORT vpXmlParserHomogeneousMatrix class Impl; Impl *m_impl; }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/core/include/visp3/core/vpXmlParserRectOriented.h b/modules/core/include/visp3/core/vpXmlParserRectOriented.h index 861546c013..adb5a6d191 100644 --- a/modules/core/include/visp3/core/vpXmlParserRectOriented.h +++ b/modules/core/include/visp3/core/vpXmlParserRectOriented.h @@ -37,14 +37,15 @@ Class vpXmlParserRectOriented allows to load and save oriented rectangles in a file XML */ -#ifndef vpXmlParserRectOriented_h -#define vpXmlParserRectOriented_h +#ifndef _vpXmlParserRectOriented_h_ +#define _vpXmlParserRectOriented_h_ #include #if defined(VISP_HAVE_PUGIXML) #include +BEGIN_VISP_NAMESPACE /*! \class vpXmlParserRectOriented @@ -108,5 +109,6 @@ class VISP_EXPORT vpXmlParserRectOriented class Impl; Impl *m_impl; }; +END_VISP_NAMESPACE #endif #endif // vpXmlParserRectOriented_h diff --git a/modules/core/src/camera/vpCameraParameters.cpp b/modules/core/src/camera/vpCameraParameters.cpp index 4b5d19b817..db79745b47 100644 --- a/modules/core/src/camera/vpCameraParameters.cpp +++ b/modules/core/src/camera/vpCameraParameters.cpp @@ -48,6 +48,8 @@ #include #include +BEGIN_VISP_NAMESPACE + const double vpCameraParameters::DEFAULT_PX_PARAMETER = 600.0; const double vpCameraParameters::DEFAULT_PY_PARAMETER = 600.0; const double vpCameraParameters::DEFAULT_U0_PARAMETER = 192.0; @@ -683,3 +685,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpCameraParameters } return os; } +END_VISP_NAMESPACE diff --git a/modules/core/src/camera/vpColorDepthConversion.cpp b/modules/core/src/camera/vpColorDepthConversion.cpp index f45bb1ed6c..b57edb5ef0 100644 --- a/modules/core/src/camera/vpColorDepthConversion.cpp +++ b/modules/core/src/camera/vpColorDepthConversion.cpp @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE namespace { @@ -252,3 +253,4 @@ vpImagePoint vpColorDepthConversion::projectColorToDepth( #endif return depth_pixel; } +END_VISP_NAMESPACE diff --git a/modules/core/src/camera/vpMeterPixelConversion.cpp b/modules/core/src/camera/vpMeterPixelConversion.cpp index 05a3b8386d..38aaf8f2d4 100644 --- a/modules/core/src/camera/vpMeterPixelConversion.cpp +++ b/modules/core/src/camera/vpMeterPixelConversion.cpp @@ -44,6 +44,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Line parameters conversion from normalized coordinates \f$(\rho_m,\theta_m)\f$ expressed in the image plane to pixel coordinates \f$(\rho_p,\theta_p)\f$ using ViSP camera parameters. This function doesn't use distortion @@ -402,3 +403,4 @@ void vpMeterPixelConversion::convertPoint(const cv::Mat &cameraMatrix, const cv: iP.set_v(imagePoints_vec[0].y); } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/camera/vpPixelMeterConversion.cpp b/modules/core/src/camera/vpPixelMeterConversion.cpp index a116ca6651..4e0474e05a 100644 --- a/modules/core/src/camera/vpPixelMeterConversion.cpp +++ b/modules/core/src/camera/vpPixelMeterConversion.cpp @@ -43,6 +43,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Convert ellipse parameters (ie ellipse center and normalized centered moments) * from pixels \f$(u_c, v_c, n_{{20}_p}, n_{{11}_p}, n_{{02}_p})\f$ @@ -336,3 +337,4 @@ void vpPixelMeterConversion::convertPoint(const cv::Mat &cameraMatrix, const cv: } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/camera/vpXmlParserCamera.cpp b/modules/core/src/camera/vpXmlParserCamera.cpp index 42200c9530..f36f126c97 100644 --- a/modules/core/src/camera/vpXmlParserCamera.cpp +++ b/modules/core/src/camera/vpXmlParserCamera.cpp @@ -81,6 +81,7 @@ #define LABEL_XML_ADDITIONAL_INFO "additional_information" +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpXmlParserCamera::Impl { @@ -301,18 +302,18 @@ class vpXmlParserCamera::Impl bool test_subsampling_height = true; if (subsampling_width) { - test_subsampling_width = (abs((int)subsampl_width - (int)subsampling_width_tmp) < - (allowedPixelDiffOnImageSize * (int)(subsampling_width_tmp / subsampling_width))); + test_subsampling_width = (abs(static_cast(subsampl_width) - static_cast(subsampling_width_tmp)) < + (allowedPixelDiffOnImageSize * static_cast(subsampling_width_tmp / subsampling_width))); } if (subsampling_height) { - test_subsampling_height = (abs((int)subsampl_height - (int)subsampling_height_tmp) < - (allowedPixelDiffOnImageSize * (int)(subsampling_height_tmp / subsampling_height))); + test_subsampling_height = (abs(static_cast(subsampl_height) - static_cast(subsampling_height_tmp)) < + (allowedPixelDiffOnImageSize * static_cast(subsampling_height_tmp / subsampling_height))); } // if same name && same projection model && same image size camera already exists, we return SEQUENCE_OK // otherwise it is a new camera that need to be updated and we return SEQUENCE_OK bool same_name = (cam_name.empty() || (cam_name == camera_name_tmp)); - bool same_img_size = (abs((int)im_width - (int)image_width_tmp) < allowedPixelDiffOnImageSize || im_width == 0) && - (abs((int)im_height - (int)image_height_tmp) < allowedPixelDiffOnImageSize || im_height == 0) && + bool same_img_size = (abs(static_cast(im_width) - static_cast(image_width_tmp)) < allowedPixelDiffOnImageSize || im_width == 0) && + (abs(static_cast(im_height) - static_cast(image_height_tmp)) < allowedPixelDiffOnImageSize || im_height == 0) && (test_subsampling_width) && (test_subsampling_height); if (same_name && same_img_size && same_proj_model) { back = SEQUENCE_OK; // Camera exists @@ -331,8 +332,8 @@ class vpXmlParserCamera::Impl } #if 0 if (!((projModelFound == true) && - (abs((int)im_width - (int)image_width_tmp) < allowedPixelDiffOnImageSize || im_width == 0) && - (abs((int)im_height - (int)image_height_tmp) < allowedPixelDiffOnImageSize || im_height == 0) && + (abs(static_cast(im_width) - static_cast(image_width_tmp)) < allowedPixelDiffOnImageSize || im_width == 0) && + (abs(static_cast(im_height) - static_cast(image_height_tmp)) < allowedPixelDiffOnImageSize || im_height == 0) && (test_subsampling_width) && (test_subsampling_height))) { // Same images size, we need to check if the camera have the same name if (!cam_name.empty() && (cam_name != camera_name_tmp)) { @@ -500,8 +501,8 @@ class vpXmlParserCamera::Impl std::vector fixed_distortion_coeffs; - // In case disortion coefficients are missing, we should complete them with 0 values - // Since 0x3FF is 0011|1111|1111 and we are interrested in the most significant 1s shown below + // In case distortion coefficients are missing, we should complete them with 0 values + // Since 0x3FF is 0011|1111|1111 and we are interested in the most significant 1s shown below // -- --- // If we divide by 32 (>> 2^5 : 5 remaining least significant bits), we will have to check 5 bits only int check = validation / 32; @@ -660,21 +661,25 @@ class vpXmlParserCamera::Impl unsigned int im_height, unsigned int subsampl_width = 0, unsigned int subsampl_height = 0) { vpXmlCodeType prop; - - for (pugi::xml_node node = node_.first_child(); node; node = node.next_sibling()) { - if (node.type() != pugi::node_element) - continue; - - if (SEQUENCE_OK != str2xmlcode(node.name(), prop)) { - prop = CODE_XML_OTHER; - } - if (prop == CODE_XML_CAMERA) { - if (SEQUENCE_OK == read_camera_header(node, cam_name, im_width, im_height, subsampl_width, subsampl_height)) { - return node; + pugi::xml_node resNode = pugi::xml_node(); + + pugi::xml_node node = node_.first_child(); + bool hasNotFoundCam = true; + while (node && hasNotFoundCam) { + if (node.type() == pugi::node_element) { + if (SEQUENCE_OK != str2xmlcode(node.name(), prop)) { + prop = CODE_XML_OTHER; + } + if (prop == CODE_XML_CAMERA) { + if (SEQUENCE_OK == read_camera_header(node, cam_name, im_width, im_height, subsampl_width, subsampl_height)) { + resNode = node; + hasNotFoundCam = false; + } } } + node = node.next_sibling(); } - return pugi::xml_node(); + return resNode; } /*! @@ -997,23 +1002,27 @@ class vpXmlParserCamera::Impl pugi::xml_node find_additional_info(const pugi::xml_node &node_) { vpXmlCodeType prop; + pugi::xml_node resNode = pugi::xml_node(); + + pugi::xml_node node = node_.first_child(); + bool hasNotFoundInfo = true; + while (node && hasNotFoundInfo) { + if (node.type() == pugi::node_element) { + if (SEQUENCE_OK != str2xmlcode(node.name(), prop)) { + prop = CODE_XML_OTHER; + } - for (pugi::xml_node node = node_.first_child(); node; node = node.next_sibling()) { - if (node.type() != pugi::node_element) { - continue; - } - - if (SEQUENCE_OK != str2xmlcode(node.name(), prop)) { - prop = CODE_XML_OTHER; + if (prop == CODE_XML_ADDITIONAL_INFO) { + // We found the node + resNode = node; + hasNotFoundInfo = false; + } } - if (prop == CODE_XML_ADDITIONAL_INFO) { - // We found the node - return node; - } + node = node.next_sibling(); } - return pugi::xml_node(); + return resNode; } /*! @@ -1227,7 +1236,7 @@ void vpXmlParserCamera::setSubsampling_width(unsigned int subsampling) { m_impl- void vpXmlParserCamera::setSubsampling_height(unsigned int subsampling) { m_impl->setSubsampling_height(subsampling); } void vpXmlParserCamera::setWidth(unsigned int width) { m_impl->setWidth(width); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpXmlParserCamera.cpp.o) has no symbols void dummy_vpXmlParserCamera() { }; diff --git a/modules/core/src/display/vpColor.cpp b/modules/core/src/display/vpColor.cpp index 0af91b46ff..fb2bbe45dd 100644 --- a/modules/core/src/display/vpColor.cpp +++ b/modules/core/src/display/vpColor.cpp @@ -35,6 +35,7 @@ #include +BEGIN_VISP_NAMESPACE // FS: Sould be improved to avoid the #if preprocessor line. Not a good idea // to define colors in static. // See also vpColor.h where things need to be improved. @@ -98,7 +99,7 @@ vpColor const vpColor::none = vpColor(0, 0, 0, id_unknown); const unsigned int vpColor::nbColors = 18; /*!< Array of available colors. */ -vpColor const vpColor::allColors[vpColor::nbColors] = {vpColor::blue, // 12 +vpColor const vpColor::allColors[vpColor::nbColors] = { vpColor::blue, // 12 vpColor::green, // 9 vpColor::red, // 6 vpColor::cyan, // 15 @@ -115,10 +116,10 @@ vpColor const vpColor::allColors[vpColor::nbColors] = {vpColor::blue, // 1 vpColor::gray, // 3 vpColor::darkGray, // 4 vpColor::black, // 0 - vpColor::white}; // 17 + vpColor::white }; // 17 #endif -vpColor colors[6] = {vpColor::blue, vpColor::green, vpColor::red, vpColor::cyan, vpColor::orange, vpColor::purple}; +vpColor colors[6] = { vpColor::blue, vpColor::green, vpColor::red, vpColor::cyan, vpColor::orange, vpColor::purple }; /*! Compare two colors. @@ -144,3 +145,5 @@ VISP_EXPORT bool operator!=(const vpColor &c1, const vpColor &c2) { return ((c1.R != c2.R) || (c1.G != c2.G) || (c1.B == c2.B)); } + +END_VISP_NAMESPACE diff --git a/modules/core/src/display/vpDisplay.cpp b/modules/core/src/display/vpDisplay.cpp index 7b430151a3..a15b635f6d 100644 --- a/modules/core/src/display/vpDisplay.cpp +++ b/modules/core/src/display/vpDisplay.cpp @@ -33,7 +33,10 @@ * *****************************************************************************/ -#include +/*! + \file vpDisplay.cpp + \brief Generic class for image display. +*/ #include #include @@ -43,11 +46,7 @@ #include #include -/*! - \file vpDisplay.cpp - \brief Generic class for image display. -*/ - +BEGIN_VISP_NAMESPACE /*! Default constructor. */ @@ -328,3 +327,4 @@ void vpDisplay::setDownScalingFactor(vpScaleType scaleType) m_scaleType = scaleType; } } +END_VISP_NAMESPACE diff --git a/modules/core/src/display/vpDisplay_impl.h b/modules/core/src/display/vpDisplay_impl.h index 253027b7ac..a9c202fdf3 100644 --- a/modules/core/src/display/vpDisplay_impl.h +++ b/modules/core/src/display/vpDisplay_impl.h @@ -37,6 +37,7 @@ #include #include +BEGIN_VISP_NAMESPACE template void vp_display_close(vpImage &I) { if (I.display != nullptr) { @@ -241,7 +242,7 @@ void vp_display_display_ellipse(const vpImage &I, const vpImagePoint ¢ double t = (a - b) / (a + b); t *= t; // t^2 double circumference = (angle / 2.0) * (a + b) * (1.0 + 3.0 * t / (10.0 + sqrt(4.0 - 3.0 * t))); - unsigned int nbpoints = (unsigned int)(floor(circumference / 20)); + unsigned int nbpoints = static_cast(floor(circumference / 20)); if (nbpoints < 10) { nbpoints = 10; } @@ -562,15 +563,15 @@ template void vp_display_display_roi(const vpImage &I, const double left = floor(roi.getLeft()); double roiheight = floor(roi.getHeight()); double roiwidth = floor(roi.getWidth()); - double iheight = (double)(I.getHeight()); - double iwidth = (double)(I.getWidth()); + double iheight = static_cast(I.getHeight()); + double iwidth = static_cast(I.getWidth()); if (top < 0 || top > iheight || left < 0 || left > iwidth || top + roiheight > iheight || left + roiwidth > iwidth) { throw(vpException(vpException::dimensionError, "Region of interest outside of the image")); } if (I.display != nullptr) { - (I.display)->displayImageROI(I, vpImagePoint(top, left), (unsigned int)roiwidth, (unsigned int)roiheight); + (I.display)->displayImageROI(I, vpImagePoint(top, left), static_cast(roiwidth), static_cast(roiheight)); } } @@ -584,7 +585,7 @@ template void vp_display_flush(const vpImage &I) template void vp_display_flush_roi(const vpImage &I, const vpRect &roi) { if (I.display != nullptr) { - (I.display)->flushDisplayROI(roi.getTopLeft(), (unsigned int)roi.getWidth(), (unsigned int)roi.getHeight()); + (I.display)->flushDisplayROI(roi.getTopLeft(), static_cast(roi.getWidth()), static_cast(roi.getHeight())); } } @@ -724,3 +725,4 @@ template unsigned int vp_display_get_down_scaling_factor(const vpIm return 1; } } +END_VISP_NAMESPACE diff --git a/modules/core/src/display/vpDisplay_rgba.cpp b/modules/core/src/display/vpDisplay_rgba.cpp index 2a3a069823..9737ea386d 100644 --- a/modules/core/src/display/vpDisplay_rgba.cpp +++ b/modules/core/src/display/vpDisplay_rgba.cpp @@ -41,7 +41,7 @@ // Modifications done in this file should be reported in all vpDisplay_*.cpp // files that implement other types (unsigned char, vpRGB, vpRGBa) //************************************************************************ - +BEGIN_VISP_NAMESPACE /*! Close the display attached to I. */ @@ -1326,3 +1326,4 @@ void vpDisplay::setWindowPosition(const vpImage &I, int winx, int winy) \param I : Image associated to the display window. */ unsigned int vpDisplay::getDownScalingFactor(const vpImage &I) { return vp_display_get_down_scaling_factor(I); } +END_VISP_NAMESPACE diff --git a/modules/core/src/display/vpDisplay_uchar.cpp b/modules/core/src/display/vpDisplay_uchar.cpp index 6080fa4025..3e887ec109 100644 --- a/modules/core/src/display/vpDisplay_uchar.cpp +++ b/modules/core/src/display/vpDisplay_uchar.cpp @@ -41,7 +41,7 @@ // Modifications done in this file should be reported in all vpDisplay_*.cpp // files that implement other types (unsigned char, vpRGB, vpRGBa) //************************************************************************ - +BEGIN_VISP_NAMESPACE /*! Close the display attached to I. */ @@ -1336,3 +1336,4 @@ unsigned int vpDisplay::getDownScalingFactor(const vpImage &I) { return vp_display_get_down_scaling_factor(I); } +END_VISP_NAMESPACE diff --git a/modules/core/src/display/vpFeatureDisplay.cpp b/modules/core/src/display/vpFeatureDisplay.cpp index a764d6c8bb..818e4ce2f1 100644 --- a/modules/core/src/display/vpFeatureDisplay.cpp +++ b/modules/core/src/display/vpFeatureDisplay.cpp @@ -49,6 +49,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Display a 2D point with coordinates (x, y) expressed in the image plane. These coordinates are obtained after perspective projection of the point. @@ -273,3 +274,4 @@ void vpFeatureDisplay::displayEllipse(double x, double y, double n20, double n11 vpMeterPixelConversion::convertEllipse(cam, circle, center, n20_p, n11_p, n02_p); vpDisplay::displayEllipse(I, center, n20_p, n11_p, n02_p, true, color, thickness); } +END_VISP_NAMESPACE diff --git a/modules/core/src/framegrabber/vpFrameGrabber.cpp b/modules/core/src/framegrabber/vpFrameGrabber.cpp index 2514ea5648..1c03c736ce 100644 --- a/modules/core/src/framegrabber/vpFrameGrabber.cpp +++ b/modules/core/src/framegrabber/vpFrameGrabber.cpp @@ -34,6 +34,7 @@ #include +BEGIN_VISP_NAMESPACE unsigned int vpFrameGrabber::getHeight() const { return height; @@ -43,3 +44,4 @@ unsigned int vpFrameGrabber::getWidth() const { return width; } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/private/vpBayerConversion.h b/modules/core/src/image/private/vpBayerConversion.h index 1167be1466..ae494262ab 100644 --- a/modules/core/src/image/private/vpBayerConversion.h +++ b/modules/core/src/image/private/vpBayerConversion.h @@ -79,7 +79,7 @@ template T demosaicCrossBilinear(const T *bayer, unsigned int width // Malvar template T demosaicPhiMalvar(const T *bayer, unsigned int width, unsigned int i, unsigned int j) { - return vpMath::saturate( + return VISP_NAMESPACE_ADDRESSING vpMath::saturate( (-bayer[(i - 2) * width + j] - bayer[(i - 1) * width + j - 1] + 4 * bayer[(i - 1) * width + j] - bayer[(i - 1) * width + j + 1] + 0.5f * bayer[i * width + j - 2] + 5 * bayer[i * width + j] + 0.5f * bayer[i * width + j + 2] - bayer[(i + 1) * width + j - 1] + 4 * bayer[(i + 1) * width + j] - @@ -89,17 +89,17 @@ template T demosaicPhiMalvar(const T *bayer, unsigned int width, un template T demosaicThetaMalvar(const T *bayer, unsigned int width, unsigned int i, unsigned int j) { - return vpMath::saturate((0.5f * bayer[(i - 2) * width + j] - bayer[(i - 1) * width + j - 1] - - bayer[(i - 1) * width + j + 1] - bayer[i * width + j - 2] + 4 * bayer[i * width + j - 1] + - 5 * bayer[i * width + j] + 4 * bayer[i * width + j + 1] - bayer[i * width + j + 2] - - bayer[(i + 1) * width + j - 1] - bayer[(i + 1) * width + j + 1] + - 0.5f * bayer[(i + 2) * width + j]) * + return VISP_NAMESPACE_ADDRESSING vpMath::saturate((0.5f * bayer[(i - 2) * width + j] - bayer[(i - 1) * width + j - 1] - + bayer[(i - 1) * width + j + 1] - bayer[i * width + j - 2] + 4 * bayer[i * width + j - 1] + + 5 * bayer[i * width + j] + 4 * bayer[i * width + j + 1] - bayer[i * width + j + 2] - + bayer[(i + 1) * width + j - 1] - bayer[(i + 1) * width + j + 1] + + 0.5f * bayer[(i + 2) * width + j]) * 0.125f); } template T demosaicCheckerMalvar(const T *bayer, unsigned int width, unsigned int i, unsigned int j) { - return vpMath::saturate( + return VISP_NAMESPACE_ADDRESSING vpMath::saturate( (-1.5f * bayer[(i - 2) * width + j] + 2 * bayer[(i - 1) * width + j - 1] + 2 * bayer[(i - 1) * width + j + 1] - 1.5f * bayer[i * width + j - 2] + 6 * bayer[i * width + j] - 1.5f * bayer[i * width + j + 2] + 2 * bayer[(i + 1) * width + j - 1] + 2 * bayer[(i + 1) * width + j + 1] - 1.5f * bayer[(i + 2) * width + j]) * @@ -108,9 +108,9 @@ template T demosaicCheckerMalvar(const T *bayer, unsigned int width template T demosaicCrossMalvar(const T *bayer, unsigned int width, unsigned int i, unsigned int j) { - return vpMath::saturate((-bayer[(i - 2) * width + j] + 2 * bayer[(i - 1) * width + j] - bayer[i * width + j - 2] + - 2 * bayer[i * width + j - 1] + 4 * bayer[i * width + j] + 2 * bayer[i * width + j + 1] - - bayer[i * width + j + 2] + 2 * bayer[(i + 1) * width + j] - bayer[(i + 2) * width + j]) * + return VISP_NAMESPACE_ADDRESSING vpMath::saturate((-bayer[(i - 2) * width + j] + 2 * bayer[(i - 1) * width + j] - bayer[i * width + j - 2] + + 2 * bayer[i * width + j - 1] + 4 * bayer[i * width + j] + 2 * bayer[i * width + j + 1] - + bayer[i * width + j + 2] + 2 * bayer[(i + 1) * width + j] - bayer[(i + 2) * width + j]) * 0.125f); } diff --git a/modules/core/src/image/private/vpImageConvert_impl.h b/modules/core/src/image/private/vpImageConvert_impl.h index 9e0bd97d57..8258f50b84 100644 --- a/modules/core/src/image/private/vpImageConvert_impl.h +++ b/modules/core/src/image/private/vpImageConvert_impl.h @@ -38,17 +38,19 @@ \brief Image conversion tools */ -#ifndef vpIMAGECONVERT_impl_H -#define vpIMAGECONVERT_impl_H +#ifndef _vpIMAGECONVERT_impl_H_ +#define _vpIMAGECONVERT_impl_H_ #if defined(VISP_HAVE_OPENMP) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include #endif +#include #include #include +BEGIN_VISP_NAMESPACE /*! Convert the input float depth image to a 8-bits depth image. The input depth value is assigned a value proportional to its frequency. @@ -262,5 +264,5 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage } } } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/src/image/vpCannyEdgeDetection.cpp b/modules/core/src/image/vpCannyEdgeDetection.cpp index c1f55dcec6..78c26922fa 100644 --- a/modules/core/src/image/vpCannyEdgeDetection.cpp +++ b/modules/core/src/image/vpCannyEdgeDetection.cpp @@ -39,7 +39,11 @@ namespace { // Helper to apply the scale to the raw values of the filters template -static void scaleFilter(vpArray2D &filter, const float &scale) +static void scaleFilter( +#ifdef ENABLE_VISP_NAMESPACE + visp:: +#endif + vpArray2D &filter, const float &scale) { const unsigned int nbRows = filter.getRows(); const unsigned int nbCols = filter.getCols(); @@ -52,6 +56,38 @@ static void scaleFilter(vpArray2D &filter, const float &scale) }; #endif +BEGIN_VISP_NAMESPACE +#ifdef VISP_HAVE_NLOHMANN_JSON +void from_json(const nlohmann::json &j, vpCannyEdgeDetection &detector) +{ + std::string filteringAndGradientName = vpImageFilter::vpCannyFiltAndGradTypeToStr(detector.m_filteringAndGradientType); + filteringAndGradientName = j.value("filteringAndGradientType", filteringAndGradientName); + detector.m_filteringAndGradientType = vpImageFilter::vpCannyFiltAndGradTypeFromStr(filteringAndGradientName); + detector.m_gaussianKernelSize = j.value("gaussianSize", detector.m_gaussianKernelSize); + detector.m_gaussianStdev = j.value("gaussianStdev", detector.m_gaussianStdev); + detector.m_lowerThreshold = j.value("lowerThreshold", detector.m_lowerThreshold); + detector.m_lowerThresholdRatio = j.value("lowerThresholdRatio", detector.m_lowerThresholdRatio); + detector.m_gradientFilterKernelSize = j.value("gradientFilterKernelSize", detector.m_gradientFilterKernelSize); + detector.m_upperThreshold = j.value("upperThreshold", detector.m_upperThreshold); + detector.m_upperThresholdRatio = j.value("upperThresholdRatio", detector.m_upperThresholdRatio); +} + +void to_json(nlohmann::json &j, const vpCannyEdgeDetection &detector) +{ + std::string filteringAndGradientName = vpImageFilter::vpCannyFiltAndGradTypeToStr(detector.m_filteringAndGradientType); + j = nlohmann::json { + {"filteringAndGradientType", filteringAndGradientName}, + {"gaussianSize", detector.m_gaussianKernelSize}, + {"gaussianStdev", detector.m_gaussianStdev}, + {"lowerThreshold", detector.m_lowerThreshold}, + {"lowerThresholdRatio", detector.m_lowerThresholdRatio}, + {"gradientFilterKernelSize", detector.m_gradientFilterKernelSize}, + {"upperThreshold", detector.m_upperThreshold}, + {"upperThresholdRatio", detector.m_upperThresholdRatio} + }; +} +#endif + // // Initialization methods vpCannyEdgeDetection::vpCannyEdgeDetection() @@ -478,8 +514,9 @@ vpCannyEdgeDetection::recursiveSearchForStrongEdge(const std::pair &I, vpImage &Icolor) } convert(I_float, Icolor); } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpFont.cpp b/modules/core/src/image/vpFont.cpp index fd706e8afb..ed611a8bae 100644 --- a/modules/core/src/image/vpFont.cpp +++ b/modules/core/src/image/vpFont.cpp @@ -67,6 +67,7 @@ #define STB_TRUETYPE_IMPLEMENTATION #include "private/stb_truetype.h" +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpFont::Impl { @@ -2692,3 +2693,4 @@ vpImagePoint vpFont::getMeasure(const std::string &text) const { return m_impl-> \return A result of the operation. */ bool vpFont::setHeight(unsigned int height) { return m_impl->Resize(height); } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpGaussianFilter.cpp b/modules/core/src/image/vpGaussianFilter.cpp index 8bafec5514..9ca88acfdb 100644 --- a/modules/core/src/image/vpGaussianFilter.cpp +++ b/modules/core/src/image/vpGaussianFilter.cpp @@ -38,6 +38,7 @@ #include #include +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpGaussianFilter::Impl { @@ -147,7 +148,7 @@ void vpGaussianFilter::apply(const vpImage &I, vpImage &I, vpImage &I_blur) { m_impl->apply(I, I_blur); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpGaussianFilter.cpp.o) has no symbols void dummy_vpGaussianFilter() { }; diff --git a/modules/core/src/image/vpImageCircle.cpp b/modules/core/src/image/vpImageCircle.cpp index d21fbe1a00..afb49a7816 100644 --- a/modules/core/src/image/vpImageCircle.cpp +++ b/modules/core/src/image/vpImageCircle.cpp @@ -34,6 +34,7 @@ #include #include +BEGIN_VISP_NAMESPACE vpImageCircle::vpImageCircle() : m_center() , m_radius(0.) @@ -1164,3 +1165,4 @@ float vpImageCircle::get_n11() const { return 0.; } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpImageConvert.cpp b/modules/core/src/image/vpImageConvert.cpp index a047b7d9bf..0ee31c2c16 100644 --- a/modules/core/src/image/vpImageConvert.cpp +++ b/modules/core/src/image/vpImageConvert.cpp @@ -56,7 +56,7 @@ #endif #include - +BEGIN_VISP_NAMESPACE bool vpImageConvert::YCbCrLUTcomputed = false; int vpImageConvert::vpCrr[256]; int vpImageConvert::vpCgb[256]; @@ -2424,5 +2424,6 @@ void vpImageConvert::demosaicRGGBToRGBaMalvar(const uint16_t *rggb, uint16_t *rg { demosaicRGGBToRGBaMalvarTpl(rggb, rgba, width, height, nThreads); } - #endif // VISP_SKIP_BAYER_CONVERSION + +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpImageConvert_hsv.cpp b/modules/core/src/image/vpImageConvert_hsv.cpp index 187cba2c64..3d8ef91c9b 100644 --- a/modules/core/src/image/vpImageConvert_hsv.cpp +++ b/modules/core/src/image/vpImageConvert_hsv.cpp @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Convert an HSV image to a RGB or RGBa image depending on the value of \e step. * \param[in] hue_ : Image hue channel in range [0,1]. @@ -555,3 +556,4 @@ void vpImageConvert::RGBToHSV(const unsigned char *rgb, unsigned char *hue, unsi { vpImageConvert::RGB2HSV(rgb, hue, saturation, value, size, 3, h_full); } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpImageConvert_pcl.cpp b/modules/core/src/image/vpImageConvert_pcl.cpp index 072ec4814e..da5b771f12 100644 --- a/modules/core/src/image/vpImageConvert_pcl.cpp +++ b/modules/core/src/image/vpImageConvert_pcl.cpp @@ -48,6 +48,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! * Create a point cloud from a depth image. * @@ -281,4 +282,5 @@ int vpImageConvert::depthToPointCloud(const vpImage &color, const vpImag return pcl_size; } +END_VISP_NAMESPACE #endif diff --git a/modules/core/src/image/vpImageConvert_yuv.cpp b/modules/core/src/image/vpImageConvert_yuv.cpp index bec8f5a03a..799f61ff3b 100644 --- a/modules/core/src/image/vpImageConvert_yuv.cpp +++ b/modules/core/src/image/vpImageConvert_yuv.cpp @@ -54,6 +54,7 @@ void vpSAT(int &c) } }; +BEGIN_VISP_NAMESPACE /*! Convert an image from YUYV 4:2:2 (y0 u01 y1 v01 y2 u23 y3 v23 ...) to RGB32. Destination rgba memory area has to be allocated before. @@ -1662,3 +1663,4 @@ void vpImageConvert::YVU9ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned rgb += 9 * width; } } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpImageDraw.cpp b/modules/core/src/image/vpImageDraw.cpp index ce28d0e698..ef37be6dee 100644 --- a/modules/core/src/image/vpImageDraw.cpp +++ b/modules/core/src/image/vpImageDraw.cpp @@ -63,6 +63,9 @@ namespace { +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif template void DrawLine(vpImage &canvas, int x1, int y1, int x2, int y2, const Type &color, unsigned int width = 1) { @@ -234,6 +237,7 @@ void DrawRectangle(vpImage &canvas, const vpRect &rect, const Type &color, } } // namespace +BEGIN_VISP_NAMESPACE /*! Draw an arrow from image point \e ip1 to image point \e ip2. \param[in,out] I : Image where to draw the arrow. @@ -976,3 +980,4 @@ void vpImageDraw::drawRectangle(vpImage &I, const vpRect &rectangle, con DrawRectangle(I, rectangle, vpRGBa(color.R, color.G, color.B), thickness); } } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpImageFilter.cpp b/modules/core/src/image/vpImageFilter.cpp index 6658d1f44c..54d6b177ad 100644 --- a/modules/core/src/image/vpImageFilter.cpp +++ b/modules/core/src/image/vpImageFilter.cpp @@ -36,6 +36,7 @@ #include #include +BEGIN_VISP_NAMESPACE /** * \brief Get the list of available vpCannyBackendType. * @@ -1128,3 +1129,4 @@ void vpImageFilter::canny(const vpImage &Isrc, vpImage #include +#include // numeric_limits + +BEGIN_VISP_NAMESPACE /*! Check if an image point belongs to a rectangle. @@ -126,7 +129,7 @@ vpImagePoint &vpImagePoint::operator/=(double scale) */ VISP_EXPORT bool operator==(const vpImagePoint &ip1, const vpImagePoint &ip2) { - // --comment: return ip1 dot get_i() eq ip2 dot get_i() and ip1 dot get_j() eq ip2 dot get_j() +// --comment: return ip1 dot get_i() eq ip2 dot get_i() and ip1 dot get_j() eq ip2 dot get_j() double i1 = ip1.get_i(); double j1 = ip1.get_j(); @@ -144,7 +147,7 @@ VISP_EXPORT bool operator==(const vpImagePoint &ip1, const vpImagePoint &ip2) */ VISP_EXPORT bool operator!=(const vpImagePoint &ip1, const vpImagePoint &ip2) { - // --comment: return ip1 dot get_i() diff ip2 dot get_i() or ip1 dot get_j() diff ip2 dot get_j() +// --comment: return ip1 dot get_i() diff ip2 dot get_i() or ip1 dot get_j() diff ip2 dot get_j() double i1 = ip1.get_i(); double j1 = ip1.get_j(); double i2 = ip2.get_i(); @@ -451,3 +454,4 @@ double vpImagePoint::sqrDistance(const vpImagePoint &iP1, const vpImagePoint &iP { return vpMath::sqr(iP1.get_i() - iP2.get_i()) + vpMath::sqr(iP1.get_j() - iP2.get_j()); } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpImageTools.cpp b/modules/core/src/image/vpImageTools.cpp index b196cd7dcb..5049092e0d 100644 --- a/modules/core/src/image/vpImageTools.cpp +++ b/modules/core/src/image/vpImageTools.cpp @@ -42,6 +42,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! Change the look up table (LUT) of an image. Considering pixel gray level values \f$ l \f$ in the range \f$[A, B]\f$, this method allows @@ -1191,3 +1192,4 @@ int vpImageTools::inRange(const unsigned char *hue, const unsigned char *saturat } return cpt_in_range; } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpRGBa.cpp b/modules/core/src/image/vpRGBa.cpp index 3e8ec6a227..26ebd5d72b 100644 --- a/modules/core/src/image/vpRGBa.cpp +++ b/modules/core/src/image/vpRGBa.cpp @@ -44,6 +44,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Copy operator (from an unsigned char value) @@ -229,7 +230,7 @@ bool vpRGBa::operator>(const vpRGBa &v) const return (gray1 > gray2); } -vpRGBa operator*(const double &x, const vpRGBa &rgb) { return rgb * x; } +vpRGBa operator*(const double &x, const vpRGBa &rgb) { return rgb * x; } /*! @@ -258,3 +259,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRGBa &rgba) os << "(" << static_cast(rgba.R) << "," << static_cast(rgba.G) << "," << static_cast(rgba.B) << "," << static_cast(rgba.A) << ")"; return os; } +END_VISP_NAMESPACE diff --git a/modules/core/src/image/vpRGBf.cpp b/modules/core/src/image/vpRGBf.cpp index 2979de6f81..1213ffe49c 100644 --- a/modules/core/src/image/vpRGBf.cpp +++ b/modules/core/src/image/vpRGBf.cpp @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Copy operator (from a floating-point value) @@ -234,7 +235,7 @@ bool vpRGBf::operator>(const vpRGBf &v) const return (gray1 > gray2); } -vpRGBf operator*(double x, const vpRGBf &rgb) { return rgb * x; } +VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpRGBf operator*(double x, const vpRGBf &rgb) { return rgb * x; } /*! \relates vpRGBf @@ -262,3 +263,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRGBf &rgb) os << "(" << rgb.R << "," << rgb.G << "," << rgb.B << ")"; return os; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/kalman/vpKalmanFilter.cpp b/modules/core/src/math/kalman/vpKalmanFilter.cpp index 9112f4038e..d1503eff44 100644 --- a/modules/core/src/math/kalman/vpKalmanFilter.cpp +++ b/modules/core/src/math/kalman/vpKalmanFilter.cpp @@ -43,6 +43,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Initialize the Kalman filter. @@ -87,9 +88,8 @@ void vpKalmanFilter::init(unsigned int size_state_vector, unsigned int size_meas */ vpKalmanFilter::vpKalmanFilter() : iter(0), size_state(0), size_measure(0), nsignal(0), verbose_mode(false), Xest(), Xpre(), F(), H(), R(), Q(), - dt(-1), Ppre(), Pest(), W(), I() -{ -} + dt(-1), Ppre(), Pest(), W(), I() +{ } /*! Construct a default Kalman filter by setting the number of signal to filter. @@ -100,9 +100,8 @@ vpKalmanFilter::vpKalmanFilter() */ vpKalmanFilter::vpKalmanFilter(unsigned int n_signal) : iter(0), size_state(0), size_measure(0), nsignal(n_signal), verbose_mode(false), Xest(), Xpre(), F(), H(), R(), Q(), - dt(-1), Ppre(), Pest(), W(), I() -{ -} + dt(-1), Ppre(), Pest(), W(), I() +{ } /*! Construct a Kalman filter. @@ -119,7 +118,7 @@ vpKalmanFilter::vpKalmanFilter(unsigned int n_signal) */ vpKalmanFilter::vpKalmanFilter(unsigned int size_state_vector, unsigned int size_measure_vector, unsigned int n_signal) : iter(0), size_state(0), size_measure(0), nsignal(0), verbose_mode(false), Xest(), Xpre(), F(), H(), R(), Q(), - dt(-1), Ppre(), Pest(), W(), I() + dt(-1), Ppre(), Pest(), W(), I() { init(size_state_vector, size_measure_vector, n_signal); } @@ -285,81 +284,80 @@ vpKalmanFilter::initFilterCteAcceleration(double dt, vpColVector &Z0, vpColVector &Z1, vpColVector &Z2, - vpColVector &sigma_noise, - vpColVector &sigma_state ) + vpColVector &sigma_noise, + vpColVector &sigma_state) { - this->dt = dt ; + this->dt = dt; - double dt2 = dt*dt ; - double dt3 = dt2*dt ; - double dt4 = dt3*dt ; - double dt5 = dt4*dt ; + double dt2 = dt*dt; + double dt3 = dt2*dt; + double dt4 = dt3*dt; + double dt5 = dt4*dt; //init_done = true ; - Pest =0 ; + Pest = 0; // initialise les matrices decrivant les modeles - for (int i=0; i < size_measure ; i++ ) - { + for (int i = 0; i < size_measure; i++) { // modele sur l'etat // | 1 dt dt2/2 | // F = | 0 1 dt | // | 0 0 1 | - F[3*i][3*i] = 1 ; - F[3*i][3*i+1] = dt ; - F[3*i][3*i+2] = dt*dt/2 ; - F[3*i+1][3*i+1] = 1 ; - F[3*i+1][3*i+2] = dt ; - F[3*i+2][3*i+2] = 1 ; + F[3*i][3*i] = 1; + F[3*i][3*i+1] = dt; + F[3*i][3*i+2] = dt*dt/2; + F[3*i+1][3*i+1] = 1; + F[3*i+1][3*i+2] = dt; + F[3*i+2][3*i+2] = 1; // modele sur la mesure - H[i][3*i] = 1 ; - H[i][3*i+1] = 0 ; - H[i][3*i+2] = 0 ; + H[i][3*i] = 1; + H[i][3*i+1] = 0; + H[i][3*i+2] = 0; - double sR = sigma_noise[i] ; - double sQ = sigma_state[i] ; + double sR = sigma_noise[i]; + double sQ = sigma_state[i]; // bruit de mesure - R[i][i] = (sR) ; + R[i][i] = (sR); // bruit d'etat 6.2.3.9 - Q[3*i ][3*i ] = sQ * dt5/20; - Q[3*i ][3*i+1] = sQ * dt4/8; - Q[3*i ][3*i+2] = sQ * dt3/6 ; + Q[3*i][3*i] = sQ * dt5/20; + Q[3*i][3*i+1] = sQ * dt4/8; + Q[3*i][3*i+2] = sQ * dt3/6; - Q[3*i+1][3*i ] = sQ * dt4/8 ; - Q[3*i+1][3*i+1] = sQ * dt3/3 ; - Q[3*i+1][3*i+2] = sQ * dt2/2 ; + Q[3*i+1][3*i] = sQ * dt4/8; + Q[3*i+1][3*i+1] = sQ * dt3/3; + Q[3*i+1][3*i+2] = sQ * dt2/2; - Q[3*i+2][3*i ] = sQ * dt3/6 ; - Q[3*i+2][3*i+1] = sQ * dt2/2.0 ; - Q[3*i+2][3*i+2] = sQ * dt ; + Q[3*i+2][3*i] = sQ * dt3/6; + Q[3*i+2][3*i+1] = sQ * dt2/2.0; + Q[3*i+2][3*i+2] = sQ * dt; // Initialisation pour la matrice de covariance sur l'etat - Pest[3*i ][3*i ] = sR ; - Pest[3*i ][3*i+1] = 1.5/dt*sR ; - Pest[3*i ][3*i+2] = sR/(dt2) ; + Pest[3*i][3*i] = sR; + Pest[3*i][3*i+1] = 1.5/dt*sR; + Pest[3*i][3*i+2] = sR/(dt2); - Pest[3*i+1][3*i ] = 1.5/dt*sR ; - Pest[3*i+1][3*i+1] = dt3/3*sQ + 13/(2*dt2)*sR ; - Pest[3*i+1][3*i+2] = 9*dt2*sQ/40.0 +6/dt3*sR ; + Pest[3*i+1][3*i] = 1.5/dt*sR; + Pest[3*i+1][3*i+1] = dt3/3*sQ + 13/(2*dt2)*sR; + Pest[3*i+1][3*i+2] = 9*dt2*sQ/40.0 +6/dt3*sR; - Pest[3*i+2][3*i ] = sR/(dt2) ; - Pest[3*i+2][3*i+1] = 9*dt2*sQ/40.0 +6/dt3*sR ; - Pest[3*i+2][3*i+2] = 23*dt/30.0*sQ+6.0/dt4*sR ; + Pest[3*i+2][3*i] = sR/(dt2); + Pest[3*i+2][3*i+1] = 9*dt2*sQ/40.0 +6/dt3*sR; + Pest[3*i+2][3*i+2] = 23*dt/30.0*sQ+6.0/dt4*sR; // Initialisation pour l'etat - Xest[3*i] = Z2[i] ; - Xest[3*i+1] = ( 1.5 *Z2[i] - Z1[i] -0.5*Z0[i] ) /( 2*dt ) ; - Xest[3*i+2] = ( Z2[i] - 2*Z1[i] + Z0[i] ) /( dt*dt ) ; + Xest[3*i] = Z2[i]; + Xest[3*i+1] = (1.5 *Z2[i] - Z1[i] -0.5*Z0[i]) /(2*dt); + Xest[3*i+2] = (Z2[i] - 2*Z1[i] + Z0[i]) /(dt*dt); } } @@ -369,82 +367,82 @@ vpKalmanFilter::initFilterSinger(double dt, double a, vpColVector &Z0, vpColVector &Z1, - vpColVector &sigma_noise, - vpColVector &sigma_state ) + vpColVector &sigma_noise, + vpColVector &sigma_state) { - this->dt = dt ; + this->dt = dt; - double dt2 = dt*dt ; - double dt3 = dt2*dt ; + double dt2 = dt*dt; + double dt3 = dt2*dt; - double a2 = a*a ; - double a3 = a2*a ; - double a4 = a3*a ; + double a2 = a*a; + double a3 = a2*a; + double a4 = a3*a; //init_done = true ; - Pest =0 ; + Pest = 0; // initialise les matrices decrivant les modeles - for (int i=0; i < size_measure ; i++ ) - { + for (int i = 0; i < size_measure; i++) { // modele sur l'etat // | 1 dt dt2/2 | // F = | 0 1 dt | // | 0 0 1 | - F[3*i][3*i] = 1 ; - F[3*i][3*i+1] = dt ; - F[3*i][3*i+2] = 1/a2*(1+a*dt+exp(-a*dt)) ; - F[3*i+1][3*i+1] = 1 ; - F[3*i+1][3*i+2] = 1/a*(1-exp(-a*dt)) ; - F[3*i+2][3*i+2] = exp(-a*dt) ; + F[3*i][3*i] = 1; + F[3*i][3*i+1] = dt; + F[3*i][3*i+2] = 1/a2*(1+a*dt+exp(-a*dt)); + F[3*i+1][3*i+1] = 1; + F[3*i+1][3*i+2] = 1/a*(1-exp(-a*dt)); + F[3*i+2][3*i+2] = exp(-a*dt); // modele sur la mesure - H[i][3*i] = 1 ; - H[i][3*i+1] = 0 ; - H[i][3*i+2] = 0 ; + H[i][3*i] = 1; + H[i][3*i+1] = 0; + H[i][3*i+2] = 0; - double sR = sigma_noise[i] ; - double sQ = sigma_state[i] ; + double sR = sigma_noise[i]; + double sQ = sigma_state[i]; - R[i][i] = (sR) ; // bruit de mesure 1.5mm + R[i][i] = (sR); // bruit de mesure 1.5mm - Q[3*i ][3*i ] = sQ/a4*(1-exp(-2*a*dt)+2*a*dt+2*a3/3*dt3-2*a2*dt2-4*a*dt*exp(-a*dt) ) ; - Q[3*i ][3*i+1] = sQ/a3*(1+exp(-2*a*dt)-2*exp(-a*dt)+2*a*dt*exp(-a*dt)-2*a*dt+a2*dt2 ) ; - Q[3*i ][3*i+2] = sQ/a2*(1-exp(-2*a*dt)-2*a*dt*exp(-a*dt) ) ; + Q[3*i][3*i] = sQ/a4*(1-exp(-2*a*dt)+2*a*dt+2*a3/3*dt3-2*a2*dt2-4*a*dt*exp(-a*dt)); + Q[3*i][3*i+1] = sQ/a3*(1+exp(-2*a*dt)-2*exp(-a*dt)+2*a*dt*exp(-a*dt)-2*a*dt+a2*dt2); + Q[3*i][3*i+2] = sQ/a2*(1-exp(-2*a*dt)-2*a*dt*exp(-a*dt)); - Q[3*i+1][3*i ] = Q[3*i ][3*i+1] ; - Q[3*i+1][3*i+1] = sQ/a2*(4*exp(-a*dt)-3-exp(-2*a*dt)+2*a*dt ) ; - Q[3*i+1][3*i+2] = sQ/a*(exp(-2*a*dt)+1- 2*exp(-a*dt)) ; + Q[3*i+1][3*i] = Q[3*i][3*i+1]; + Q[3*i+1][3*i+1] = sQ/a2*(4*exp(-a*dt)-3-exp(-2*a*dt)+2*a*dt); + Q[3*i+1][3*i+2] = sQ/a*(exp(-2*a*dt)+1- 2*exp(-a*dt)); - Q[3*i+2][3*i ] = Q[3*i ][3*i+2] ; - Q[3*i+2][3*i+1] = Q[3*i+1][3*i+2] ; - Q[3*i+2][3*i+2] = sQ*(1-exp(-2*a*dt) ) ; + Q[3*i+2][3*i] = Q[3*i][3*i+2]; + Q[3*i+2][3*i+1] = Q[3*i+1][3*i+2]; + Q[3*i+2][3*i+2] = sQ*(1-exp(-2*a*dt)); // Initialisation pour la matrice de covariance sur l'etat - Pest[3*i ][3*i ] = sR ; - Pest[3*i ][3*i+1] = 1/dt*sR ; - Pest[3*i ][3*i+2] = 0 ; + Pest[3*i][3*i] = sR; + Pest[3*i][3*i+1] = 1/dt*sR; + Pest[3*i][3*i+2] = 0; - Pest[3*i+1][3*i ] = 1/dt*sR ; + Pest[3*i+1][3*i] = 1/dt*sR; Pest[3*i+1][3*i+1] = 2*sR/dt2 + sQ/(a4*dt2)*(2-a2*dt2+2*a3*dt3/3.0 -2*exp(-a*dt)-2*a*dt*exp(-a*dt)); - Pest[3*i+1][3*i+2] = sQ/(a2*dt)*(exp(-a*dt)+a*dt-1) ; + Pest[3*i+1][3*i+2] = sQ/(a2*dt)*(exp(-a*dt)+a*dt-1); - Pest[3*i+2][3*i ] = 0 ; - Pest[3*i+2][3*i+1] = Pest[3*i+1][3*i+2] ; - Pest[3*i+2][3*i+2] = 0 ; + Pest[3*i+2][3*i] = 0; + Pest[3*i+2][3*i+1] = Pest[3*i+1][3*i+2]; + Pest[3*i+2][3*i+2] = 0; // Initialisation pour l'etat - Xest[3*i] = Z1[i] ; - Xest[3*i+1] = ( Z1[i] - Z0[i] ) /(dt ) ; - Xest[3*i+2] = 0 ; + Xest[3*i] = Z1[i]; + Xest[3*i+1] = (Z1[i] - Z0[i]) /(dt); + Xest[3*i+2] = 0; } } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/kalman/vpLinearKalmanFilterInstantiation.cpp b/modules/core/src/math/kalman/vpLinearKalmanFilterInstantiation.cpp index ad4179240d..e78d58ccf8 100644 --- a/modules/core/src/math/kalman/vpLinearKalmanFilterInstantiation.cpp +++ b/modules/core/src/math/kalman/vpLinearKalmanFilterInstantiation.cpp @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Initialize the Kalman filter material depending on the selected @@ -810,7 +811,8 @@ void vpLinearKalmanFilterInstantiation::filter(vpColVector &z) iter++; return; - } else if (iter == 1) { + } + else if (iter == 1) { if (model == stateConstVel_MeasurePos) { for (unsigned int i = 0; i < size_measure * nsignal; i++) { double z_prev = Xest[size_state * i]; // Previous mesured position @@ -827,3 +829,4 @@ void vpLinearKalmanFilterInstantiation::filter(vpColVector &z) filtering(z); prediction(); } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/kalman/vpUKSigmaDrawerMerwe.cpp b/modules/core/src/math/kalman/vpUKSigmaDrawerMerwe.cpp index 56d64fb2dd..10c6da6ad6 100644 --- a/modules/core/src/math/kalman/vpUKSigmaDrawerMerwe.cpp +++ b/modules/core/src/math/kalman/vpUKSigmaDrawerMerwe.cpp @@ -41,6 +41,7 @@ #include #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +BEGIN_VISP_NAMESPACE vpUKSigmaDrawerMerwe::vpUKSigmaDrawerMerwe(const int &n, const double &alpha, const double &beta, const double &kappa, const vpAddSubFunction &resFunc, const vpAddSubFunction &addFunc) : vpUKSigmaDrawerAbstract(n) @@ -84,6 +85,7 @@ vpUKSigmaDrawerMerwe::vpSigmaPointsWeights vpUKSigmaDrawerMerwe::computeWeights( } return weights; } +END_VISP_NAMESPACE #else void vpUKSigmaDrawerMerwe_dummy() { diff --git a/modules/core/src/math/kalman/vpUnscentedKalman.cpp b/modules/core/src/math/kalman/vpUnscentedKalman.cpp index c873e3b2b7..9ce2c18876 100644 --- a/modules/core/src/math/kalman/vpUnscentedKalman.cpp +++ b/modules/core/src/math/kalman/vpUnscentedKalman.cpp @@ -39,6 +39,7 @@ #include #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +BEGIN_VISP_NAMESPACE vpUnscentedKalman::vpUnscentedKalman(const vpMatrix &Q, const vpMatrix &R, std::shared_ptr &drawer, const vpProcessFunction &f, const vpMeasurementFunction &h) : m_Q(Q) , m_R(R) @@ -145,6 +146,7 @@ vpUnscentedKalman::vpUnscentedTransformResult vpUnscentedKalman::unscentedTransf } return result; } +END_VISP_NAMESPACE #else void vpUnscentedKalman_dummy() { diff --git a/modules/core/src/math/matrix/vpColVector.cpp b/modules/core/src/math/matrix/vpColVector.cpp index 35157bb1ae..564a502d20 100644 --- a/modules/core/src/math/matrix/vpColVector.cpp +++ b/modules/core/src/math/matrix/vpColVector.cpp @@ -57,6 +57,7 @@ #include #endif +BEGIN_VISP_NAMESPACE vpColVector vpColVector::operator+(const vpColVector &v) const { if (getRows() != v.getRows()) { @@ -517,13 +518,6 @@ vpRowVector vpColVector::transpose() const { return t(); } void vpColVector::transpose(vpRowVector &v) const { v = t(); } -vpColVector operator*(const double &x, const vpColVector &v) -{ - vpColVector vout; - vout = v * x; - return vout; -} - double vpColVector::dotProd(const vpColVector &a, const vpColVector &b) { if (a.data == nullptr) { @@ -1012,3 +1006,11 @@ void vpColVector::insert(const vpColVector &v, unsigned int r, unsigned int c) double vpColVector::euclideanNorm() const { return frobeniusNorm(); } #endif // defined(VISP_BUILD_DEPRECATED_FUNCTIONS) + +vpColVector operator*(const double &x, const vpColVector &v) +{ + vpColVector vout; + vout = v * x; + return vout; +} +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpEigenConversion.cpp b/modules/core/src/math/matrix/vpEigenConversion.cpp index 075b99bd74..87e63b3736 100644 --- a/modules/core/src/math/matrix/vpEigenConversion.cpp +++ b/modules/core/src/math/matrix/vpEigenConversion.cpp @@ -35,28 +35,28 @@ #include -namespace vp +namespace VISP_NAMESPACE_NAME { #ifdef VISP_HAVE_EIGEN3 /* Eigen to ViSP */ -void eigen2visp(const Eigen::MatrixXd &src, vpMatrix &dst) +void eigen2visp(const Eigen::MatrixXd &src, VISP_NAMESPACE_ADDRESSING vpMatrix &dst) { dst.resize(static_cast(src.rows()), static_cast(src.cols()), false, false); Eigen::Map >(&dst.data[0], src.rows(), src.cols()) = src; } -void eigen2visp(const Eigen::MatrixXd &src, vpHomogeneousMatrix &dst) +void eigen2visp(const Eigen::MatrixXd &src, VISP_NAMESPACE_ADDRESSING vpHomogeneousMatrix &dst) { if ((src.rows() != 4) || (src.cols() != 4)) { - throw vpException(vpException::dimensionError, "Input Eigen Matrix must be of size (4,4)!"); + throw VISP_NAMESPACE_ADDRESSING vpException(VISP_NAMESPACE_ADDRESSING vpException::dimensionError, "Input Eigen Matrix must be of size (4,4)!"); } Eigen::Map >(&dst.data[0], src.rows(), src.cols()) = src; } -void eigen2visp(const Eigen::VectorXd &src, vpColVector &dst) +void eigen2visp(const Eigen::VectorXd &src, VISP_NAMESPACE_ADDRESSING vpColVector &dst) { dst.resize(static_cast(src.rows())); #if (VP_VERSION_INT(EIGEN_WORLD_VERSION, EIGEN_MAJOR_VERSION, EIGEN_MINOR_VERSION) < 0x030300) @@ -70,7 +70,7 @@ void eigen2visp(const Eigen::VectorXd &src, vpColVector &dst) } } -void eigen2visp(const Eigen::RowVectorXd &src, vpRowVector &dst) +void eigen2visp(const Eigen::RowVectorXd &src, VISP_NAMESPACE_ADDRESSING vpRowVector &dst) { dst.resize(static_cast(src.cols())); #if (VP_VERSION_INT(EIGEN_WORLD_VERSION, EIGEN_MAJOR_VERSION, EIGEN_MINOR_VERSION) < 0x030300) @@ -84,11 +84,11 @@ void eigen2visp(const Eigen::RowVectorXd &src, vpRowVector &dst) } } -void visp2eigen(const vpColVector &src, Eigen::VectorXd &dst) { dst = Eigen::VectorXd::Map(src.data, src.size()); } +void visp2eigen(const VISP_NAMESPACE_ADDRESSING vpColVector &src, Eigen::VectorXd &dst) { dst = Eigen::VectorXd::Map(src.data, src.size()); } -void visp2eigen(const vpRowVector &src, Eigen::RowVectorXd &dst) +void visp2eigen(const VISP_NAMESPACE_ADDRESSING vpRowVector &src, Eigen::RowVectorXd &dst) { dst = Eigen::RowVectorXd::Map(src.data, src.size()); } #endif -} // namespace vp +} // namespace VISP_NAMESPACE_NAME diff --git a/modules/core/src/math/matrix/vpMatrix.cpp b/modules/core/src/math/matrix/vpMatrix.cpp index 051f6b64ed..fbdeaf14cf 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -69,6 +69,14 @@ #include #elif defined(VISP_HAVE_MKL) #include +#endif +#endif + +BEGIN_VISP_NAMESPACE + +#ifdef VISP_HAVE_LAPACK +#ifdef VISP_HAVE_GSL +#elif defined(VISP_HAVE_MKL) typedef MKL_INT integer; void vpMatrix::blas_dsyev(char jobz, char uplo, unsigned int n_, double *a_data, unsigned int lda_, double *w_data, @@ -1661,31 +1669,6 @@ double vpMatrix::sum() const // Matrix/real operations. //--------------------------------- -/*! - \relates vpMatrix - Allow to multiply a scalar by a matrix. -*/ -vpMatrix operator*(const double &x, const vpMatrix &B) -{ - if (std::fabs(x - 1.) < std::numeric_limits::epsilon()) { - return B; - } - - unsigned int Brow = B.getRows(); - unsigned int Bcol = B.getCols(); - - vpMatrix C; - C.resize(Brow, Bcol, false, false); - - for (unsigned int i = 0; i < Brow; ++i) { - for (unsigned int j = 0; j < Bcol; ++j) { - C[i][j] = B[i][j] * x; - } - } - - return C; -} - /*! Operator that allows to multiply all the elements of a matrix by a scalar. @@ -4995,10 +4978,10 @@ vpColVector vpMatrix::getCol(unsigned int j) const { return getCol(j, 0, rowNum) A.print(std::cout, 4); - vpRowVector rv = A.getRow(1); - std::cout << "Row vector: \n" << rv << std::endl; +vpRowVector rv = A.getRow(1); +std::cout << "Row vector: \n" << rv << std::endl; } - \endcode +\endcode It produces the following output : \code [4, 4] = @@ -5013,43 +4996,43 @@ Row vector : vpRowVector vpMatrix::getRow(unsigned int i) const { return getRow(i, 0, colNum); } /*! - Extract a row vector from a matrix. - \warning All the indexes start from 0 in this function. - \param i : Index of the row to extract. If i=0, the first row is extracted. - \param j_begin : Index of the column that gives the location of the first - element of the row vector to extract. - \param row_size : Size of the row vector to extract. - \return The extracted row vector. +Extract a row vector from a matrix. +\warning All the indexes start from 0 in this function. +\param i : Index of the row to extract.If i = 0, the first row is extracted. +\param j_begin : Index of the column that gives the location of the first +element of the row vector to extract. +\param row_size : Size of the row vector to extract. +\return The extracted row vector. - The following example shows how to use this function: - \code - #include - #include +The following example shows how to use this function: +\code +#include +#include - int main() - { - vpMatrix A(4,4); +int main() +{ + vpMatrix A(4, 4); - for(unsigned int i=0; i < A.getRows(); i++) - for(unsigned int j=0; j < A.getCols(); j++) - A[i][j] = i*A.getCols()+j; + for (unsigned int i = 0; i < A.getRows(); i++) + for (unsigned int j = 0; j < A.getCols(); j++) + A[i][j] = i*A.getCols()+j; - A.print(std::cout, 4); + A.print(std::cout, 4); - vpRowVector rv = A.getRow(1, 1, 3); - std::cout << "Row vector: \n" << rv << std::endl; - } - \endcode - It produces the following output : - \code - [4, 4] = - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 - 12 13 14 15 - Row vector : - 5 6 7 - \endcode + vpRowVector rv = A.getRow(1, 1, 3); + std::cout << "Row vector: \n" << rv << std::endl; +} +\endcode +It produces the following output : +\code +[4, 4] = +0 1 2 3 +4 5 6 7 +8 9 10 11 +12 13 14 15 +Row vector : +5 6 7 +\endcode */ vpRowVector vpMatrix::getRow(unsigned int i, unsigned int j_begin, unsigned int row_size) const { @@ -6722,3 +6705,29 @@ void vpMatrix::setIdentity(const double &val) } #endif //#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) + +/*! + \relates vpMatrix + Allow to multiply a scalar by a matrix. +*/ +vpMatrix operator*(const double &x, const vpMatrix &B) +{ + if (std::fabs(x - 1.) < std::numeric_limits::epsilon()) { + return B; + } + + unsigned int Brow = B.getRows(); + unsigned int Bcol = B.getCols(); + + VISP_NAMESPACE_ADDRESSING vpMatrix C; + C.resize(Brow, Bcol, false, false); + + for (unsigned int i = 0; i < Brow; ++i) { + for (unsigned int j = 0; j < Bcol; ++j) { + C[i][j] = B[i][j] * x; + } + } + + return C; +} +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpMatrix_cholesky.cpp b/modules/core/src/math/matrix/vpMatrix_cholesky.cpp index 30ae5de122..d8334d9e40 100644 --- a/modules/core/src/math/matrix/vpMatrix_cholesky.cpp +++ b/modules/core/src/math/matrix/vpMatrix_cholesky.cpp @@ -30,11 +30,7 @@ * * Description: * Matrix Cholesky decomposition. - * - * Authors: - * Filip Novotny - * -*****************************************************************************/ + */ #include @@ -71,6 +67,11 @@ extern "C" int dpotri_(char *uplo, integer *n, double *a, integer *lda, integer #endif #endif +#if defined(VISP_HAVE_EIGEN3) +#include +#endif + +BEGIN_VISP_NAMESPACE /*! Compute the inverse of a n-by-n matrix using the Cholesky decomposition. The matrix must be real symmetric positive defined. @@ -85,30 +86,29 @@ extern "C" int dpotri_(char *uplo, integer *n, double *a, integer *lda, integer Here an example: \code -#include + #include -int main() -{ - vpMatrix A(4,4); + int main() + { + vpMatrix A(4,4); - // Symmetric matrix - A[0][0] = 1/1.; A[0][1] = 1/5.; A[0][2] = 1/6.; A[0][3] = 1/7.; - A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; - A[2][0] = 1/6.; A[2][1] = 1/3.; A[2][2] = 1/2.; A[2][3] = 1/6.; - A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; + // Symmetric matrix + A[0][0] = 1/1.; A[0][1] = 1/5.; A[0][2] = 1/6.; A[0][3] = 1/7.; + A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; + A[2][0] = 1/6.; A[2][1] = 1/3.; A[2][2] = 1/2.; A[2][3] = 1/6.; + A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; - // Compute the inverse - vpMatrix A_1; // A^-1 - A_1 = A.inverseByCholesky(); - std::cout << "Inverse by Cholesky: \n" << A_1 << std::endl; + // Compute the inverse + vpMatrix A_1; // A^-1 + A_1 = A.inverseByCholesky(); + std::cout << "Inverse by Cholesky: \n" << A_1 << std::endl; - std::cout << "A*A^-1: \n" << A * A_1 << std::endl; -} + std::cout << "A*A^-1: \n" << A * A_1 << std::endl; + } \endcode \sa pseudoInverse() */ - vpMatrix vpMatrix::inverseByCholesky() const { #if defined(VISP_HAVE_LAPACK) @@ -123,36 +123,36 @@ vpMatrix vpMatrix::inverseByCholesky() const #if defined(VISP_HAVE_LAPACK) /*! Compute the inverse of a n-by-n matrix using the Cholesky decomposition with -Lapack 3rd party. The matrix must be real symmetric positive defined. + Lapack 3rd party. The matrix must be real symmetric positive defined. \return The inverse matrix. Here an example: \code -#include + #include -int main() -{ - unsigned int n = 4; - vpMatrix A(n, n); - vpMatrix I; - I.eye(4); + int main() + { + unsigned int n = 4; + vpMatrix A(n, n); + vpMatrix I; + I.eye(4); - A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; - A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; - A[2][0] = 1/6.; A[2][1] = 1/4.; A[2][2] = 1/2.; A[2][3] = 1/6.; - A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; + A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; + A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; + A[2][0] = 1/6.; A[2][1] = 1/4.; A[2][2] = 1/2.; A[2][3] = 1/6.; + A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; - // Make matrix symmetric positive - A = 0.5*(A+A.t()); - A = A + n*I; + // Make matrix symmetric positive + A = 0.5*(A+A.t()); + A = A + n*I; - // Compute the inverse - vpMatrix A_1 = A.inverseByCholeskyLapack(); - std::cout << "Inverse by Cholesky (Lapack): \n" << A_1 << std::endl; + // Compute the inverse + vpMatrix A_1 = A.inverseByCholeskyLapack(); + std::cout << "Inverse by Cholesky (Lapack): \n" << A_1 << std::endl; - std::cout << "A*A^-1: \n" << A * A_1 << std::endl; -} + std::cout << "A*A^-1: \n" << A * A_1 << std::endl; + } \endcode \sa inverseByCholesky(), inverseByCholeskyOpenCV() @@ -267,7 +267,7 @@ vpMatrix vpMatrix::choleskyByLapack()const } return L; } -#endif +#endif // VISP_HAVE_LAPACK #if defined(VISP_HAVE_OPENCV) /*! @@ -278,30 +278,30 @@ vpMatrix vpMatrix::choleskyByLapack()const Here an example: \code -#include + #include -int main() -{ - unsigned int n = 4; - vpMatrix A(n, n); - vpMatrix I; - I.eye(4); + int main() + { + unsigned int n = 4; + vpMatrix A(n, n); + vpMatrix I; + I.eye(4); - A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; - A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; - A[2][0] = 1/6.; A[2][1] = 1/4.; A[2][2] = 1/2.; A[2][3] = 1/6.; - A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; + A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; + A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; + A[2][0] = 1/6.; A[2][1] = 1/4.; A[2][2] = 1/2.; A[2][3] = 1/6.; + A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; - // Make matrix symmetric positive - A = 0.5*(A+A.t()); - A = A + n*I; + // Make matrix symmetric positive + A = 0.5*(A+A.t()); + A = A + n*I; - // Compute the inverse - vpMatrix A_1 = A.inverseByCholeskyOpenCV(); - std::cout << "Inverse by Cholesky (OpenCV): \n" << A_1 << std::endl; + // Compute the inverse + vpMatrix A_1 = A.inverseByCholeskyOpenCV(); + std::cout << "Inverse by Cholesky (OpenCV): \n" << A_1 << std::endl; - std::cout << "A*A^-1: \n" << A * A_1 << std::endl; -} + std::cout << "A*A^-1: \n" << A * A_1 << std::endl; + } \endcode \sa inverseByCholesky(), inverseByCholeskyLapack() @@ -349,10 +349,9 @@ vpMatrix vpMatrix::choleskyByOpenCV() const } return L; } -#endif +#endif // VISP_HAVE_OPENCV #if defined(VISP_HAVE_EIGEN3) -#include /*! * \brief Compute the Cholesky decomposition of a Hermitian positive-definite matrix * using Eigen3 library. @@ -378,4 +377,6 @@ vpMatrix vpMatrix::choleskyByEigen3() const } return Lvisp; } -#endif +#endif // VISP_HAVE_EIGEN3 + +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpMatrix_covariance.cpp b/modules/core/src/math/matrix/vpMatrix_covariance.cpp index 1caa73ec38..aed1ad5ad7 100644 --- a/modules/core/src/math/matrix/vpMatrix_covariance.cpp +++ b/modules/core/src/math/matrix/vpMatrix_covariance.cpp @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Compute the covariance matrix of the parameters x from a least squares minimization defined as: Ax = b @@ -231,3 +232,4 @@ void vpMatrix::computeCovarianceMatrixVVS(const vpHomogeneousMatrix &cMo, const // building deltaP deltaP = Js.pseudoInverse(Js.getRows() * std::numeric_limits::epsilon()) * deltaS; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpMatrix_lu.cpp b/modules/core/src/math/matrix/vpMatrix_lu.cpp index 6b265f1f9f..7730ee975e 100644 --- a/modules/core/src/math/matrix/vpMatrix_lu.cpp +++ b/modules/core/src/math/matrix/vpMatrix_lu.cpp @@ -74,6 +74,7 @@ extern "C" void dgetri_(integer *n, double *a, integer *lda, integer *ipiv, doub #include // std::fabs #include // numeric_limits +BEGIN_VISP_NAMESPACE /*-------------------------------------------------------------------- LU Decomposition related functions -------------------------------------------------------------------- */ @@ -625,3 +626,4 @@ double vpMatrix::detByLUEigen3() const return M.determinant(); } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpMatrix_mul.cpp b/modules/core/src/math/matrix/vpMatrix_mul.cpp index 15a61f61f1..69aae24f45 100644 --- a/modules/core/src/math/matrix/vpMatrix_mul.cpp +++ b/modules/core/src/math/matrix/vpMatrix_mul.cpp @@ -44,6 +44,7 @@ // or vector content in a gsl_matrix or gsl_vector. This is not acceptable here. // that's why we prefer use naive code when VISP_HAVE_GSL is defined. #if defined(VISP_HAVE_LAPACK) +BEGIN_VISP_NAMESPACE #ifdef VISP_HAVE_MKL #include typedef MKL_INT integer; @@ -112,10 +113,11 @@ void vpMatrix::blas_dgemv(char trans, unsigned int M_, unsigned int N_, double a dgemv_(&trans, &M, &N, &alpha, a_data, &lda, x_data, &incx, &beta, y_data, &incy); } #endif +END_VISP_NAMESPACE #else // Work around to avoid warning LNK4221: This object file does not define any // previously undefined public symbols -void dummy_vpMatrix_blas(){}; +void dummy_vpMatrix_blas() { }; #endif #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/modules/core/src/math/matrix/vpMatrix_qr.cpp b/modules/core/src/math/matrix/vpMatrix_qr.cpp index b770626cd3..53b60a202c 100644 --- a/modules/core/src/math/matrix/vpMatrix_qr.cpp +++ b/modules/core/src/math/matrix/vpMatrix_qr.cpp @@ -52,6 +52,7 @@ // Debug trace #include +BEGIN_VISP_NAMESPACE #ifdef VISP_HAVE_LAPACK #ifdef VISP_HAVE_GSL #if !(GSL_MAJOR_VERSION >= 2 && GSL_MINOR_VERSION >= 2) @@ -1208,3 +1209,4 @@ vpColVector vpMatrix::solveByQR(const vpColVector &b) const solveByQR(b, x); return x; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpMatrix_svd.cpp b/modules/core/src/math/matrix/vpMatrix_svd.cpp index f45551e674..70c9121778 100644 --- a/modules/core/src/math/matrix/vpMatrix_svd.cpp +++ b/modules/core/src/math/matrix/vpMatrix_svd.cpp @@ -43,7 +43,6 @@ #include // std::fabs #include -#include // numeric_limits #ifdef VISP_HAVE_EIGEN3 #include @@ -73,6 +72,8 @@ extern "C" int dgesdd_(char *jobz, integer *m, integer *n, double *a, integer *l #include #endif #endif + +BEGIN_VISP_NAMESPACE /*--------------------------------------------------------------------- SVD related functions @@ -466,3 +467,4 @@ void vpMatrix::svdEigen3(vpColVector &w, vpMatrix &V) U_ = svd.matrixU(); } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpRowVector.cpp b/modules/core/src/math/matrix/vpRowVector.cpp index 464ff165c8..3ea3b992dd 100644 --- a/modules/core/src/math/matrix/vpRowVector.cpp +++ b/modules/core/src/math/matrix/vpRowVector.cpp @@ -51,6 +51,7 @@ #include #include +BEGIN_VISP_NAMESPACE //! Copy operator. Allow operation such as A = v vpRowVector &vpRowVector::operator=(const vpRowVector &v) { @@ -769,7 +770,7 @@ v: 0 10 11 3 */ void vpRowVector::insert(unsigned int i, const vpRowVector &v) { - if ( (i + v.size()) > this->size()) { + if ((i + v.size()) > this->size()) { throw(vpException(vpException::dimensionError, "Unable to insert (1x%d) row vector in (1x%d) row " "vector at position (%d)", @@ -1067,7 +1068,7 @@ int vpRowVector::print(std::ostream &s, unsigned int length, char const *intro) } else { assert(maxAfter > 1); - s.width( static_cast (maxAfter)); + s.width(static_cast (maxAfter)); s << ".0"; } } @@ -1081,16 +1082,6 @@ int vpRowVector::print(std::ostream &s, unsigned int length, char const *intro) return static_cast(maxBefore + maxAfter); } -/*! - Allows to multiply a scalar by row vector. -*/ -vpRowVector operator*(const double &x, const vpRowVector &v) -{ - vpRowVector vout; - vout = v * x; - return vout; -} - /*! Return the sum of all the elements \f$v_{i}\f$ of the row vector v(n). @@ -1366,3 +1357,14 @@ std::ostream &vpRowVector::matlabPrint(std::ostream &os) const os << "]" << std::endl; return os; } + +/*! + Allows to multiply a scalar by row vector. +*/ +vpRowVector operator*(const double &x, const vpRowVector &v) +{ + vpRowVector vout; + vout = v * x; + return vout; +} +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpSubColVector.cpp b/modules/core/src/math/matrix/vpSubColVector.cpp index bdebd53e90..1281b901eb 100644 --- a/modules/core/src/math/matrix/vpSubColVector.cpp +++ b/modules/core/src/math/matrix/vpSubColVector.cpp @@ -41,6 +41,7 @@ #include #include +BEGIN_VISP_NAMESPACE //! Default constructor that creates an empty vector. vpSubColVector::vpSubColVector() : vpColVector(), m_pRowNum(0), m_parent(nullptr) { } @@ -247,3 +248,4 @@ vpSubColVector &vpSubColVector::operator=(const vpPoseVector &p) memcpy(data, p.data, rowNum * sizeof(double)); return *this; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpSubMatrix.cpp b/modules/core/src/math/matrix/vpSubMatrix.cpp index 763980f7f4..c906c316f7 100644 --- a/modules/core/src/math/matrix/vpSubMatrix.cpp +++ b/modules/core/src/math/matrix/vpSubMatrix.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE vpSubMatrix::vpSubMatrix() : pRowNum(0), pColNum(0), parent(nullptr) { } /*! @@ -180,3 +181,4 @@ vpSubMatrix &vpSubMatrix::operator=(const double &x) } vpSubMatrix::~vpSubMatrix() { data = nullptr; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/matrix/vpSubRowVector.cpp b/modules/core/src/math/matrix/vpSubRowVector.cpp index f826982e6d..875b02cec4 100644 --- a/modules/core/src/math/matrix/vpSubRowVector.cpp +++ b/modules/core/src/math/matrix/vpSubRowVector.cpp @@ -36,6 +36,7 @@ #include #include +BEGIN_VISP_NAMESPACE //! Default constructor that creates an empty vector. vpSubRowVector::vpSubRowVector() : vpRowVector(), m_pColNum(0), m_parent(nullptr) { } @@ -181,3 +182,4 @@ vpSubRowVector &vpSubRowVector::operator=(const double &x) } return *this; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/misc/vpHinkley.cpp b/modules/core/src/math/misc/vpHinkley.cpp index fc534c3e7e..5e1c34617b 100644 --- a/modules/core/src/math/misc/vpHinkley.cpp +++ b/modules/core/src/math/misc/vpHinkley.cpp @@ -53,6 +53,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* VP_DEBUG_MODE fixed by configure: 1: 2: @@ -432,6 +433,7 @@ void vpHinkley::print(vpHinkley::vpHinkleyJumpType jump) break; } } +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpHinkley.cpp.o) has no symbols void dummy_vpRHinkley() { }; diff --git a/modules/core/src/math/misc/vpMath.cpp b/modules/core/src/math/misc/vpMath.cpp index 2e6683d478..cba531ab04 100644 --- a/modules/core/src/math/misc/vpMath.cpp +++ b/modules/core/src/math/misc/vpMath.cpp @@ -54,6 +54,7 @@ #include #endif +BEGIN_VISP_NAMESPACE #if !(defined(VISP_HAVE_FUNC_ISNAN) || defined(VISP_HAVE_FUNC_STD_ISNAN)) || \ !(defined(VISP_HAVE_FUNC_ISINF) || defined(VISP_HAVE_FUNC_STD_ISINF)) || \ !(defined(VISP_HAVE_FUNC_ISFINITE) || defined(VISP_HAVE_FUNC_STD_ISFINITE) || defined(VISP_HAVE_FUNC__FINITE)) @@ -762,3 +763,4 @@ vpHomogeneousMatrix vpMath::enu2ned(const vpHomogeneousMatrix &enu_M) vpHomogeneousMatrix ned_M = ned_M_enu * enu_M; return ned_M; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp index 3f1cb6e76a..3034fcd812 100644 --- a/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp @@ -38,6 +38,7 @@ #include +BEGIN_VISP_NAMESPACE std::string vpStatisticalTestAbstract::vpMeanDriftTypeToString(const vpStatisticalTestAbstract::vpMeanDriftType &type) { std::string name; @@ -244,3 +245,4 @@ vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testUpward return MEAN_DRIFT_NONE; } } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp b/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp index 6e1d925f82..78be0ed89f 100644 --- a/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp @@ -39,6 +39,7 @@ #include +BEGIN_VISP_NAMESPACE void vpStatisticalTestEWMA::computeDeltaAndLimits() { float delta = 3.f * m_stdev * std::sqrt(m_alpha / (2.f - m_alpha)); @@ -126,3 +127,4 @@ void vpStatisticalTestEWMA::setAlpha(const float &alpha) { init(alpha); } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp b/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp index ab07c8e1dd..73c9dd186c 100644 --- a/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE vpStatisticalTestHinkley::vpStatisticalTestHinkley() : vpStatisticalTestAbstract() , m_dmin2(0.1f) @@ -248,3 +249,4 @@ void vpStatisticalTestHinkley::updateTestSignals(const float &signal) ++m_count; computeMean(signal); } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp b/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp index c5fbb5fbdb..ca113164d5 100644 --- a/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp @@ -39,6 +39,7 @@ #include +BEGIN_VISP_NAMESPACE void vpStatisticalTestMeanAdjustedCUSUM::computeDeltaAndLimits() { setDelta(m_k * m_stdev); @@ -153,3 +154,4 @@ void vpStatisticalTestMeanAdjustedCUSUM::init(const float &delta, const float &l m_sumForMean = 0.f; m_areStatisticsComputed = true; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp index 811d6a9d8e..74460225da 100644 --- a/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp @@ -43,6 +43,7 @@ #include +BEGIN_VISP_NAMESPACE const int vpStatisticalTestShewhart::NB_DATA_SIGNAL; const bool vpStatisticalTestShewhart::CONST_ALL_WECO_ACTIVATED[vpStatisticalTestShewhart::COUNT_WECO - 1] = { true, true, true, true }; @@ -306,3 +307,4 @@ void vpStatisticalTestShewhart::init(const bool &activateWECOrules, const bool a computeLimits(); m_areStatisticsComputed = true; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/misc/vpStatisticalTestSigma.cpp b/modules/core/src/math/misc/vpStatisticalTestSigma.cpp index 6180460386..cfb0d3cfbe 100644 --- a/modules/core/src/math/misc/vpStatisticalTestSigma.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestSigma.cpp @@ -39,6 +39,7 @@ #include +BEGIN_VISP_NAMESPACE void vpStatisticalTestSigma::computeLimits() { float delta = m_h * m_stdev; @@ -112,3 +113,4 @@ void vpStatisticalTestSigma::init(const float &h, const float &mean, const float computeLimits(); m_areStatisticsComputed = true; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/random-generator/vpGaussRand.cpp b/modules/core/src/math/random-generator/vpGaussRand.cpp index 0682f07217..255947965d 100644 --- a/modules/core/src/math/random-generator/vpGaussRand.cpp +++ b/modules/core/src/math/random-generator/vpGaussRand.cpp @@ -36,6 +36,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Generate a normal random variable using the Box-Muller generator. @@ -64,3 +65,4 @@ double vpGaussRand::gaussianDraw() return v1 * fac; } } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/random-generator/vpUniRand.cpp b/modules/core/src/math/random-generator/vpUniRand.cpp index 10335a504a..bc091ae5e4 100644 --- a/modules/core/src/math/random-generator/vpUniRand.cpp +++ b/modules/core/src/math/random-generator/vpUniRand.cpp @@ -69,6 +69,7 @@ #include #include +BEGIN_VISP_NAMESPACE vpUniRand::vpUniRand() : m_maxInvDbl(1.0 / static_cast(UINT32_MAX)), m_maxInvFlt(1.0f / static_cast(UINT32_MAX)), m_rng() { } @@ -207,3 +208,4 @@ void vpUniRand::setSeed(uint64_t initstate, uint64_t initseq) m_rng.state += initstate; next(); } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/robust/vpRobust.cpp b/modules/core/src/math/robust/vpRobust.cpp index c781df403b..c420c103cc 100644 --- a/modules/core/src/math/robust/vpRobust.cpp +++ b/modules/core/src/math/robust/vpRobust.cpp @@ -53,6 +53,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Default constructor. */ @@ -705,3 +706,4 @@ double vpRobust::gammln(double xx) #undef vpEPS #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/robust/vpScale.cpp b/modules/core/src/math/robust/vpScale.cpp index 4af25912f2..fd7130251f 100644 --- a/modules/core/src/math/robust/vpScale.cpp +++ b/modules/core/src/math/robust/vpScale.cpp @@ -47,6 +47,7 @@ #define DEBUG_LEVEL2 0 +BEGIN_VISP_NAMESPACE //! Constructor vpScale::vpScale() : bandwidth(0.02), dimension(1) { @@ -71,7 +72,7 @@ vpScale::vpScale(double kernel_bandwidth, unsigned int dim) : bandwidth(kernel_b } //! Destructor -vpScale::~vpScale() {} +vpScale::~vpScale() { } // Calculate the modes of the density for the distribution // and their associated errors @@ -181,7 +182,8 @@ double vpScale::KernelDensityGradient(vpColVector &error, unsigned int position) inside_kernel = 1; sum_delta += error[j] - error[position]; j++; - } else { + } + else { inside_kernel = 0; } } @@ -196,7 +198,8 @@ double vpScale::KernelDensityGradient(vpColVector &error, unsigned int position) inside_kernel = 1; sum_delta += error[j] - error[position]; j--; - } else { + } + else { inside_kernel = 0; } } @@ -259,3 +262,4 @@ double vpScale::KernelDensityGradient_EPANECHNIKOV(double sumX, unsigned int n) // (double)dimension)*c*vpMath::sqr(bandwidth)); return sumX * (dimension + 2) / (n * bandwidth * c * vpMath::sqr(bandwidth)); } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/spline/vpBSpline.cpp b/modules/core/src/math/spline/vpBSpline.cpp index 4f4b16cfb1..da5d524e3d 100644 --- a/modules/core/src/math/spline/vpBSpline.cpp +++ b/modules/core/src/math/spline/vpBSpline.cpp @@ -36,6 +36,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Basic constructor. @@ -517,3 +518,4 @@ vpImagePoint *vpBSpline::computeCurveDers(double u, unsigned int der) const return derivate; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpExponentialMap.cpp b/modules/core/src/math/transformation/vpExponentialMap.cpp index 0fe64c478d..2bbe6611fd 100644 --- a/modules/core/src/math/transformation/vpExponentialMap.cpp +++ b/modules/core/src/math/transformation/vpExponentialMap.cpp @@ -38,6 +38,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Compute the exponential map. The inverse function is inverse(). The @@ -285,3 +286,4 @@ vpColVector vpExponentialMap::inverse(const vpHomogeneousMatrix &M, const double return v; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpForceTwistMatrix.cpp b/modules/core/src/math/transformation/vpForceTwistMatrix.cpp index 351d127eec..5f4820af21 100644 --- a/modules/core/src/math/transformation/vpForceTwistMatrix.cpp +++ b/modules/core/src/math/transformation/vpForceTwistMatrix.cpp @@ -34,13 +34,6 @@ * *****************************************************************************/ -#include -#include - -#include -#include -#include - /*! \file vpForceTwistMatrix.cpp @@ -49,6 +42,15 @@ transform a force/torque skew from one frame to an other. */ +#include +#include + +#include +#include +#include + +BEGIN_VISP_NAMESPACE + /*! Copy operator. @@ -788,3 +790,6 @@ int vpForceTwistMatrix::print(std::ostream &s, unsigned int length, char const * void vpForceTwistMatrix::setIdentity() { eye(); } #endif //#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +#ifdef ENABLE_VISP_NAMESPACE + } +#endif diff --git a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp index 206919ad22..d2c9f21daf 100644 --- a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Construct an homogeneous matrix from a translation vector and quaternion rotation vector. @@ -1379,6 +1380,9 @@ void vpHomogeneousMatrix::convert_to_json(nlohmann::json &j) const void vpHomogeneousMatrix::parse_json(const nlohmann::json &j) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpArray2D *asArray = (vpArray2D*) this; if (j.is_object() && j.contains("type")) { // Specific conversions const bool converted = convertFromTypeAndBuildFrom(j, *this); @@ -1398,3 +1402,4 @@ void vpHomogeneousMatrix::parse_json(const nlohmann::json &j) } } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpPoseVector.cpp b/modules/core/src/math/transformation/vpPoseVector.cpp index e2e517ce95..5c73b4c935 100644 --- a/modules/core/src/math/transformation/vpPoseVector.cpp +++ b/modules/core/src/math/transformation/vpPoseVector.cpp @@ -49,6 +49,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! Default constructor that construct a 6 dimension pose vector \f$ [\bf t, @@ -610,6 +612,9 @@ void vpPoseVector::convert_to_json(nlohmann::json &j) const } void vpPoseVector::parse_json(const nlohmann::json &j) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpArray2D *asArray = (vpArray2D*) this; if (j.is_object() && j.contains("type")) { // Specific conversions const bool converted = convertFromTypeAndBuildFrom(j, *this); @@ -626,3 +631,4 @@ void vpPoseVector::parse_json(const nlohmann::json &j) } } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpQuaternionVector.cpp b/modules/core/src/math/transformation/vpQuaternionVector.cpp index 53a9731800..8d845db705 100644 --- a/modules/core/src/math/transformation/vpQuaternionVector.cpp +++ b/modules/core/src/math/transformation/vpQuaternionVector.cpp @@ -43,6 +43,7 @@ #include #include +BEGIN_VISP_NAMESPACE // minimum value of sine const double vpQuaternionVector::minimum = 0.0001; @@ -549,3 +550,4 @@ vpQuaternionVector vpQuaternionVector::slerp(const vpQuaternionVector &q0, const return qSlerp; } +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpRotationMatrix.cpp b/modules/core/src/math/transformation/vpRotationMatrix.cpp index a0ca634dff..6f5927d890 100644 --- a/modules/core/src/math/transformation/vpRotationMatrix.cpp +++ b/modules/core/src/math/transformation/vpRotationMatrix.cpp @@ -52,6 +52,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Initialize the rotation matrix as identity. @@ -944,25 +945,6 @@ vpRotationMatrix &vpRotationMatrix::build(const vpQuaternionVector &q) return *this; } -/*! - Allow to multiply a scalar by a rotation matrix. -*/ -vpRotationMatrix operator*(const double &x, const vpRotationMatrix &R) -{ - vpRotationMatrix C; - - unsigned int Rrow = R.getRows(); - unsigned int Rcol = R.getCols(); - - for (unsigned int i = 0; i < Rrow; ++i) { - for (unsigned int j = 0; j < Rcol; ++j) { - C[i][j] = R[i][j] * x; - } - } - - return C; -} - /*! Return the \f$\theta {\bf u}\f$ vector that corresponds to the rotation matrix. @@ -1138,3 +1120,23 @@ void vpRotationMatrix::orthogonalize() void vpRotationMatrix::setIdentity() { eye(); } #endif //#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) + +/*! + Allow to multiply a scalar by a rotation matrix. +*/ +vpRotationMatrix operator*(const double &x, const vpRotationMatrix &R) +{ + vpRotationMatrix C; + + unsigned int Rrow = R.getRows(); + unsigned int Rcol = R.getCols(); + + for (unsigned int i = 0; i < Rrow; ++i) { + for (unsigned int j = 0; j < Rcol; ++j) { + C[i][j] = R[i][j] * x; + } + } + + return C; +} +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpRotationVector.cpp b/modules/core/src/math/transformation/vpRotationVector.cpp index 12540837d7..752a9e5e6c 100644 --- a/modules/core/src/math/transformation/vpRotationVector.cpp +++ b/modules/core/src/math/transformation/vpRotationVector.cpp @@ -33,6 +33,12 @@ * *****************************************************************************/ +/*! + \file vpRotationVector.cpp + \brief Class that consider the case of a generic rotation vector + (cannot be used as is !). +*/ + #include #include @@ -40,12 +46,7 @@ #include #include -/*! - \file vpRotationVector.cpp - \brief Class that consider the case of a generic rotation vector - (cannot be used as is !). -*/ - +BEGIN_VISP_NAMESPACE /*! Return the transpose of the rotation vector. @@ -96,17 +97,6 @@ vpColVector vpRotationVector::operator*(double x) const return v; } -/*! - \relates vpRotationVector - Allows to multiply a scalar by rotaion vector. -*/ -vpColVector operator*(const double &x, const vpRotationVector &v) -{ - vpColVector vout; - vout = v * x; - return vout; -} - /*! Set vector first element value. \param val : Value of the vector first element [rad]. @@ -190,3 +180,15 @@ double vpRotationVector::sumSquare() const return sum_square; } + +/*! + \relates vpRotationVector + Allows to multiply a scalar by rotaion vector. +*/ +vpColVector operator*(const double &x, const vpRotationVector &v) +{ + vpColVector vout; + vout = v * x; + return vout; +} +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpRxyzVector.cpp b/modules/core/src/math/transformation/vpRxyzVector.cpp index 144b236ea9..1d8ffc3d82 100644 --- a/modules/core/src/math/transformation/vpRxyzVector.cpp +++ b/modules/core/src/math/transformation/vpRxyzVector.cpp @@ -33,16 +33,17 @@ * Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi). */ -#include - -#include - /*! \file vpRxyzVector.cpp \brief class that consider the case of the Rxyz angle parameterization for the rotation : Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi) */ +#include + +#include + +BEGIN_VISP_NAMESPACE /*! Default constructor that initialize all the 3 angles to zero. */ vpRxyzVector::vpRxyzVector() : vpRotationVector(3) { } @@ -322,3 +323,4 @@ vpRxyzVector &vpRxyzVector::operator=(const std::initializer_list &list) return *this; } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpRzyxVector.cpp b/modules/core/src/math/transformation/vpRzyxVector.cpp index 4dfc849933..47732cb5e6 100644 --- a/modules/core/src/math/transformation/vpRzyxVector.cpp +++ b/modules/core/src/math/transformation/vpRzyxVector.cpp @@ -34,8 +34,6 @@ * *****************************************************************************/ -#include -#include /*! \file vpRzyxVector.cpp \brief class that consider the case of the Rzyx angle parameterization for @@ -43,6 +41,10 @@ */ +#include +#include + +BEGIN_VISP_NAMESPACE /*! Default constructor that initialize all the 3 angles to zero. */ vpRzyxVector::vpRzyxVector() : vpRotationVector(3) { } @@ -338,3 +340,4 @@ vpRzyxVector &vpRzyxVector::operator=(const std::initializer_list &list) return *this; } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpRzyzVector.cpp b/modules/core/src/math/transformation/vpRzyzVector.cpp index 4de914d006..154ca166c1 100644 --- a/modules/core/src/math/transformation/vpRzyzVector.cpp +++ b/modules/core/src/math/transformation/vpRzyzVector.cpp @@ -33,15 +33,16 @@ * Rzyz(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(z,psi) */ -#include -#include - /*! \file vpRzyzVector.cpp \brief class that consider the case of the Rzyz angle parameterization for the rotation : Rzyz(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(z,psi) */ +#include +#include + +BEGIN_VISP_NAMESPACE /*! Default constructor that initialize all the 3 angles to zero. */ vpRzyzVector::vpRzyzVector() : vpRotationVector(3) { } /*! Copy constructor. */ @@ -319,3 +320,4 @@ vpRzyzVector &vpRzyzVector::operator=(const std::initializer_list &list) return *this; } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpThetaUVector.cpp b/modules/core/src/math/transformation/vpThetaUVector.cpp index 7a6758ebcd..7f62f8cae8 100644 --- a/modules/core/src/math/transformation/vpThetaUVector.cpp +++ b/modules/core/src/math/transformation/vpThetaUVector.cpp @@ -42,6 +42,7 @@ #include +BEGIN_VISP_NAMESPACE const double vpThetaUVector::minimum = 0.0001; /*! Default constructor that initialize all the 3 angles to zero. */ @@ -616,3 +617,4 @@ vpThetaUVector &vpThetaUVector::operator=(const std::initializer_list &l return *this; } #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpTranslationVector.cpp b/modules/core/src/math/transformation/vpTranslationVector.cpp index 32e71f7bc0..b1d0a65ada 100644 --- a/modules/core/src/math/transformation/vpTranslationVector.cpp +++ b/modules/core/src/math/transformation/vpTranslationVector.cpp @@ -32,16 +32,17 @@ * Translation vector. */ -#include -#include - -#include - /*! \file vpTranslationVector.cpp \brief Class that consider the case of a translation vector. */ +#include +#include + +#include + +BEGIN_VISP_NAMESPACE /*! Construct a translation vector \f$ \bf t \f$ from 3 doubles. @@ -868,3 +869,4 @@ vpTranslationVector vpTranslationVector::mean(const std::vector -#include - -#include -#include - /*! \file vpVelocityTwistMatrix.cpp @@ -47,6 +41,13 @@ transform a velocity skew from one frame to an other. */ +#include +#include + +#include +#include + +BEGIN_VISP_NAMESPACE /*! Copy operator that allow to set a velocity twist matrix from an other one. @@ -719,3 +720,4 @@ int vpVelocityTwistMatrix::print(std::ostream &s, unsigned int length, char cons void vpVelocityTwistMatrix::setIdentity() { eye(); } #endif // #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +END_VISP_NAMESPACE diff --git a/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp index edcff25c1d..042cb63baa 100644 --- a/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp @@ -62,6 +62,7 @@ #define LABEL_XML_TUY "theta_uy" #define LABEL_XML_TUZ "theta_uz" +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpXmlParserHomogeneousMatrix::Impl { @@ -556,7 +557,7 @@ void vpXmlParserHomogeneousMatrix::setHomogeneousMatrixName(const std::string &n { m_impl->setHomogeneousMatrixName(name); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpXmlParserHomogeneousMatrix.cpp.o) has no symbols void dummy_vpXmlParserHomogeneousMatrix() { }; diff --git a/modules/core/src/munkres/vpMunkres.cpp b/modules/core/src/munkres/vpMunkres.cpp index fc8b3c3ec3..05b20113e1 100644 --- a/modules/core/src/munkres/vpMunkres.cpp +++ b/modules/core/src/munkres/vpMunkres.cpp @@ -42,6 +42,7 @@ // Check if std:c++17 or higher #if ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) +BEGIN_VISP_NAMESPACE /*! * Find a starred zero in a specific mask matrix row. * @@ -191,5 +192,5 @@ vpMunkres::STEP_T vpMunkres::stepFive(std::vector } } } - +END_VISP_NAMESPACE #endif diff --git a/modules/core/src/tools/convert/vpConvert.cpp b/modules/core/src/tools/convert/vpConvert.cpp index 6ba42f78c6..3b1ce481b9 100644 --- a/modules/core/src/tools/convert/vpConvert.cpp +++ b/modules/core/src/tools/convert/vpConvert.cpp @@ -44,6 +44,7 @@ #include #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_FEATURES2D) +BEGIN_VISP_NAMESPACE /*! Unary function used to transform a cv::KeyPoint to a vpImagePoint. \param keypoint : KeyPoint to convert. @@ -461,6 +462,7 @@ void vpConvert::convertToOpenCV(const std::vector &from, std::vector +BEGIN_VISP_NAMESPACE namespace vpCPUFeatures { // TODO: try to refactor to keep only SimdCpuInfo code and remove cpu_x86 code? @@ -71,3 +72,4 @@ bool checkNeon() { return SimdCpuInfo(SimdCpuInfoNeon) != 0; } void printCPUInfo() { cpu_features.print(); } } // namespace vpCPUFeatures +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/cpu-features/x86/cpu_x86.cpp b/modules/core/src/tools/cpu-features/x86/cpu_x86.cpp index 3f7dfddb6f..274447c4d6 100644 --- a/modules/core/src/tools/cpu-features/x86/cpu_x86.cpp +++ b/modules/core/src/tools/cpu-features/x86/cpu_x86.cpp @@ -101,15 +101,15 @@ bool cpu_x86::detect_OS_AVX() bool avxSupported = false; - int cpuInfo[4]; + uint32_t cpuInfo[4]; cpuid(cpuInfo, 1); - bool osUsesXSAVE_XRSTORE = (cpuInfo[2] & (1 << 27)) != 0; - bool cpuAVXSuport = (cpuInfo[2] & (1 << 28)) != 0; + bool osUsesXSAVE_XRSTORE = (cpuInfo[2] & (1U << 27)) != 0; + bool cpuAVXSuport = (cpuInfo[2] & (1U << 28)) != 0; if (osUsesXSAVE_XRSTORE && cpuAVXSuport) { uint64_t xcrFeatureMask = xgetbv(_XCR_XFEATURE_ENABLED_MASK); - avxSupported = (xcrFeatureMask & 0x6) == 0x6; + avxSupported = (xcrFeatureMask & 0x6U) == 0x6U; } return avxSupported; @@ -125,7 +125,7 @@ bool cpu_x86::detect_OS_AVX512() } uint64_t xcrFeatureMask = xgetbv(_XCR_XFEATURE_ENABLED_MASK); - return (xcrFeatureMask & 0xe6) == 0xe6; + return (xcrFeatureMask & 0xe6U) == 0xe6U; #else return false; #endif @@ -133,7 +133,7 @@ bool cpu_x86::detect_OS_AVX512() std::string cpu_x86::get_vendor_string() { #ifndef UNKNOWN_ARCH - int32_t CPUInfo[4]; + uint32_t CPUInfo[4]; char name[13]; cpuid(CPUInfo, 0); @@ -168,7 +168,7 @@ void cpu_x86::detect_host() Vendor_AMD = true; } - int info[4]; + uint32_t info[4]; cpuid(info, 0); int nIds = info[0]; @@ -178,49 +178,49 @@ void cpu_x86::detect_host() // Detect Features if (nIds >= 0x00000001) { cpuid(info, 0x00000001); - HW_MMX = (info[3] & ((int)1 << 23)) != 0; - HW_SSE = (info[3] & ((int)1 << 25)) != 0; - HW_SSE2 = (info[3] & ((int)1 << 26)) != 0; - HW_SSE3 = (info[2] & ((int)1 << 0)) != 0; + HW_MMX = (info[3] & (1U << 23)) != 0U; + HW_SSE = (info[3] & (1U << 25)) != 0U; + HW_SSE2 = (info[3] & (1U << 26)) != 0U; + HW_SSE3 = (info[2] & (1U << 0)) != 0U; - HW_SSSE3 = (info[2] & ((int)1 << 9)) != 0; - HW_SSE41 = (info[2] & ((int)1 << 19)) != 0; - HW_SSE42 = (info[2] & ((int)1 << 20)) != 0; - HW_AES = (info[2] & ((int)1 << 25)) != 0; + HW_SSSE3 = (info[2] & (1U << 9)) != 0U; + HW_SSE41 = (info[2] & (1U << 19)) != 0U; + HW_SSE42 = (info[2] & (1U << 20)) != 0U; + HW_AES = (info[2] & (1U << 25)) != 0U; - HW_AVX = (info[2] & ((int)1 << 28)) != 0; - HW_FMA3 = (info[2] & ((int)1 << 12)) != 0; + HW_AVX = (info[2] & (1U << 28)) != 0U; + HW_FMA3 = (info[2] & (1U << 12)) != 0U; - HW_RDRAND = (info[2] & ((int)1 << 30)) != 0; + HW_RDRAND = (info[2] & (1U << 30)) != 0U; } if (nIds >= 0x00000007) { cpuid(info, 0x00000007); - HW_AVX2 = (info[1] & ((int)1 << 5)) != 0; + HW_AVX2 = (info[1] & (1U << 5)) != 0U; - HW_BMI1 = (info[1] & ((int)1 << 3)) != 0; - HW_BMI2 = (info[1] & ((int)1 << 8)) != 0; - HW_ADX = (info[1] & ((int)1 << 19)) != 0; - HW_MPX = (info[1] & ((int)1 << 14)) != 0; - HW_SHA = (info[1] & ((int)1 << 29)) != 0; - HW_PREFETCHWT1 = (info[2] & ((int)1 << 0)) != 0; + HW_BMI1 = (info[1] & (1U << 3)) != 0U; + HW_BMI2 = (info[1] & (1U << 8)) != 0U; + HW_ADX = (info[1] & (1U << 19)) != 0U; + HW_MPX = (info[1] & (1U << 14)) != 0U; + HW_SHA = (info[1] & (1U << 29)) != 0U; + HW_PREFETCHWT1 = (info[2] & (1U << 0)) != 0U; - HW_AVX512_F = (info[1] & ((int)1 << 16)) != 0; - HW_AVX512_CD = (info[1] & ((int)1 << 28)) != 0; - HW_AVX512_PF = (info[1] & ((int)1 << 26)) != 0; - HW_AVX512_ER = (info[1] & ((int)1 << 27)) != 0; - HW_AVX512_VL = (info[1] & ((int)1 << 31)) != 0; - HW_AVX512_BW = (info[1] & ((int)1 << 30)) != 0; - HW_AVX512_DQ = (info[1] & ((int)1 << 17)) != 0; - HW_AVX512_IFMA = (info[1] & ((int)1 << 21)) != 0; - HW_AVX512_VBMI = (info[2] & ((int)1 << 1)) != 0; + HW_AVX512_F = (info[1] & (1U << 16)) != 0U; + HW_AVX512_CD = (info[1] & (1U << 28)) != 0U; + HW_AVX512_PF = (info[1] & (1U << 26)) != 0U; + HW_AVX512_ER = (info[1] & (1U << 27)) != 0U; + HW_AVX512_VL = (info[1] & (1U << 31)) != 0U; + HW_AVX512_BW = (info[1] & (1U << 30)) != 0U; + HW_AVX512_DQ = (info[1] & (1U << 17)) != 0U; + HW_AVX512_IFMA = (info[1] & (1U << 21)) != 0U; + HW_AVX512_VBMI = (info[2] & (1U << 1)) != 0U; } if (nExIds >= 0x80000001) { cpuid(info, 0x80000001); - HW_x64 = (info[3] & ((int)1 << 29)) != 0; - HW_ABM = (info[2] & ((int)1 << 5)) != 0; - HW_SSE4a = (info[2] & ((int)1 << 6)) != 0; - HW_FMA4 = (info[2] & ((int)1 << 16)) != 0; - HW_XOP = (info[2] & ((int)1 << 11)) != 0; + HW_x64 = (info[3] & (1U << 29)) != 0U; + HW_ABM = (info[2] & (1U << 5)) != 0U; + HW_SSE4a = (info[2] & (1U << 6)) != 0U; + HW_FMA4 = (info[2] & (1U << 16)) != 0U; + HW_XOP = (info[2] & (1U << 11)) != 0U; } #endif } diff --git a/modules/core/src/tools/cpu-features/x86/cpu_x86.h b/modules/core/src/tools/cpu-features/x86/cpu_x86.h index 27f2c33a17..a9cf3ec49a 100644 --- a/modules/core/src/tools/cpu-features/x86/cpu_x86.h +++ b/modules/core/src/tools/cpu-features/x86/cpu_x86.h @@ -53,8 +53,9 @@ namespace FeatureDetector //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -struct cpu_x86 { - // Vendor +struct cpu_x86 +{ +// Vendor bool Vendor_AMD; bool Vendor_Intel; @@ -108,7 +109,7 @@ struct cpu_x86 { void print() const; - static void cpuid(int32_t out[4], int32_t x); + static void cpuid(uint32_t out[4], uint32_t x); static std::string get_vendor_string(); private: diff --git a/modules/core/src/tools/cpu-features/x86/cpu_x86_Linux.ipp b/modules/core/src/tools/cpu-features/x86/cpu_x86_Linux.ipp index d192e2d651..9272e6e4a8 100644 --- a/modules/core/src/tools/cpu-features/x86/cpu_x86_Linux.ipp +++ b/modules/core/src/tools/cpu-features/x86/cpu_x86_Linux.ipp @@ -18,7 +18,7 @@ namespace FeatureDetector{ //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -void cpu_x86::cpuid(int32_t out[4], int32_t x){ +void cpu_x86::cpuid(uint32_t out[4], uint32_t x){ __cpuid_count(x, 0, out[0], out[1], out[2], out[3]); } uint64_t xgetbv(unsigned int index){ diff --git a/modules/core/src/tools/cpu-features/x86/cpu_x86_Windows.ipp b/modules/core/src/tools/cpu-features/x86/cpu_x86_Windows.ipp index f4b3f8046e..b8440eed97 100644 --- a/modules/core/src/tools/cpu-features/x86/cpu_x86_Windows.ipp +++ b/modules/core/src/tools/cpu-features/x86/cpu_x86_Windows.ipp @@ -17,6 +17,7 @@ // Dependencies #include #include +#include #include "cpu_x86.h" namespace FeatureDetector { @@ -68,7 +69,7 @@ unsigned __int64 _xgetbv(unsigned int index) } #endif #if defined(__MINGW32__) -void __cpuidex(int CPUInfo[4], int function_id, int subfunction_id) +void __cpuidex(unsigned int CPUInfo[4], unsigned int function_id, unsigned int subfunction_id) { __asm__ __volatile__( "cpuid" @@ -76,9 +77,15 @@ void __cpuidex(int CPUInfo[4], int function_id, int subfunction_id) : "a" (function_id), "c" (subfunction_id)); } #endif -void cpu_x86::cpuid(int32_t out[4], int32_t x) +void cpu_x86::cpuid(uint32_t out[4], uint32_t x) { - __cpuidex(out, x, 0); +#if defined(__MINGW32__) + __cpuidex(out, x, 0U); +#else + int32_t out_as_int[4]; + __cpuidex(out_as_int, x, 0U); + memcpy(out, out_as_int, sizeof(int32_t) * 4); +#endif } __int64 xgetbv(unsigned int x) { diff --git a/modules/core/src/tools/endian/vpEndian.cpp b/modules/core/src/tools/endian/vpEndian.cpp index 234e19f1c8..ccc879ddde 100644 --- a/modules/core/src/tools/endian/vpEndian.cpp +++ b/modules/core/src/tools/endian/vpEndian.cpp @@ -40,6 +40,7 @@ #include #include +BEGIN_VISP_NAMESPACE namespace vpEndian { /*! @@ -64,7 +65,8 @@ uint32_t swap32bits(uint32_t val) */ float swapFloat(float f) { - union { + union + { float f; unsigned char b[4]; } dat1, dat2; @@ -83,7 +85,8 @@ float swapFloat(float f) */ double swapDouble(double d) { - union { + union + { double d; unsigned char b[8]; } dat1, dat2; @@ -116,3 +119,4 @@ uint16_t reinterpret_cast_uchar_to_uint16_LE(unsigned char *const ptr) #endif } } // namespace vpEndian +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/exceptions/vpException.cpp b/modules/core/src/tools/exceptions/vpException.cpp index 8dd97bf362..a3d7859063 100644 --- a/modules/core/src/tools/exceptions/vpException.cpp +++ b/modules/core/src/tools/exceptions/vpException.cpp @@ -39,9 +39,10 @@ #include "visp3/core/vpException.h" #include -vpException::vpException(int id) : code(id), message() {} +BEGIN_VISP_NAMESPACE +vpException::vpException(int id) : code(id), message() { } -vpException::vpException(int id, const std::string &msg) : code(id), message(msg) {} +vpException::vpException(int id, const std::string &msg) : code(id), message(msg) { } vpException::vpException(int id, const char *format, ...) : code(id), message() { @@ -75,3 +76,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpException &error) return os; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/file/basisu_miniz.h b/modules/core/src/tools/file/basisu_miniz.h index 187b8c9bfd..a738875b00 100644 --- a/modules/core/src/tools/file/basisu_miniz.h +++ b/modules/core/src/tools/file/basisu_miniz.h @@ -378,17 +378,17 @@ enum // Function returns a pointer to the decompressed data, or NULL on failure. // *pOut_len will be set to the decompressed data's size, which could be larger than src_buf_len on uncompressible data. // The caller must call mz_free() on the returned block when it's no longer needed. -void *tinfl_decompress_mem_to_heap(const void *pSrc_buf, size_t src_buf_len, size_t *pOut_len, int flags); +void *tinfl_decompress_mem_to_heap(const void *pSrc_buf, size_t src_buf_len, size_t *pOut_len, mz_uint flags); // tinfl_decompress_mem_to_mem() decompresses a block in memory to another block in memory. // Returns TINFL_DECOMPRESS_MEM_TO_MEM_FAILED on failure, or the number of bytes written on success. #define TINFL_DECOMPRESS_MEM_TO_MEM_FAILED ((size_t)(-1)) -size_t tinfl_decompress_mem_to_mem(void *pOut_buf, size_t out_buf_len, const void *pSrc_buf, size_t src_buf_len, int flags); +size_t tinfl_decompress_mem_to_mem(void *pOut_buf, size_t out_buf_len, const void *pSrc_buf, size_t src_buf_len, mz_uint flags); // tinfl_decompress_mem_to_callback() decompresses a block in memory to an internal 32KB buffer, and a user provided callback function will be called to flush the buffer. // Returns 1 on success or 0 on failure. typedef int (*tinfl_put_buf_func_ptr)(const void *pBuf, int len, void *pUser); -int tinfl_decompress_mem_to_callback(const void *pIn_buf, size_t *pIn_buf_size, tinfl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, int flags); +int tinfl_decompress_mem_to_callback(const void *pIn_buf, size_t *pIn_buf_size, tinfl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, mz_uint flags); struct tinfl_decompressor_tag; typedef struct tinfl_decompressor_tag tinfl_decompressor; @@ -490,11 +490,11 @@ enum // Function returns a pointer to the compressed data, or NULL on failure. // *pOut_len will be set to the compressed data's size, which could be larger than src_buf_len on uncompressible data. // The caller must free() the returned block when it's no longer needed. -void *tdefl_compress_mem_to_heap(const void *pSrc_buf, size_t src_buf_len, size_t *pOut_len, int flags); +void *tdefl_compress_mem_to_heap(const void *pSrc_buf, size_t src_buf_len, size_t *pOut_len, mz_uint flags); // tdefl_compress_mem_to_mem() compresses a block in memory to another block in memory. // Returns 0 on failure. -size_t tdefl_compress_mem_to_mem(void *pOut_buf, size_t out_buf_len, const void *pSrc_buf, size_t src_buf_len, int flags); +size_t tdefl_compress_mem_to_mem(void *pOut_buf, size_t out_buf_len, const void *pSrc_buf, size_t src_buf_len, mz_uint flags); // Compresses an image to a compressed PNG file in memory. // On entry: @@ -506,14 +506,14 @@ size_t tdefl_compress_mem_to_mem(void *pOut_buf, size_t out_buf_len, const void // Function returns a pointer to the compressed data, or NULL on failure. // *pLen_out will be set to the size of the PNG image file. // The caller must mz_free() the returned heap block (which will typically be larger than *pLen_out) when it's no longer needed. -void *tdefl_write_image_to_png_file_in_memory_ex(const void *pImage, int w, int h, int num_chans, size_t *pLen_out, mz_uint level, mz_bool flip); -void *tdefl_write_image_to_png_file_in_memory(const void *pImage, int w, int h, int num_chans, size_t *pLen_out); +void *tdefl_write_image_to_png_file_in_memory_ex(const void *pImage, mz_uint8 w, mz_uint8 h, int num_chans, size_t *pLen_out, mz_uint level, mz_bool flip); +void *tdefl_write_image_to_png_file_in_memory(const void *pImage, mz_uint8 w, mz_uint8 h, int num_chans, size_t *pLen_out); // Output stream interface. The compressor uses this interface to write compressed data. It'll typically be called TDEFL_OUT_BUF_SIZE at a time. typedef mz_bool(*tdefl_put_buf_func_ptr)(const void *pBuf, int len, void *pUser); // tdefl_compress_mem_to_output() compresses a block to an output stream. The above helpers use this function internally. -mz_bool tdefl_compress_mem_to_output(const void *pBuf, size_t buf_len, tdefl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, int flags); +mz_bool tdefl_compress_mem_to_output(const void *pBuf, size_t buf_len, tdefl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, mz_uint flags); enum { TDEFL_MAX_HUFF_TABLES = 3, TDEFL_MAX_HUFF_SYMBOLS_0 = 288, TDEFL_MAX_HUFF_SYMBOLS_1 = 32, TDEFL_MAX_HUFF_SYMBOLS_2 = 19, TDEFL_LZ_DICT_SIZE = 32768, TDEFL_LZ_DICT_SIZE_MASK = TDEFL_LZ_DICT_SIZE - 1, TDEFL_MIN_MATCH_LEN = 3, TDEFL_MAX_MATCH_LEN = 258 }; @@ -575,7 +575,7 @@ typedef struct // pBut_buf_func: If NULL, output data will be supplied to the specified callback. In this case, the user should call the tdefl_compress_buffer() API for compression. // If pBut_buf_func is NULL the user should always call the tdefl_compress() API. // flags: See the above enums (TDEFL_HUFFMAN_ONLY, TDEFL_WRITE_ZLIB_HEADER, etc.) -tdefl_status tdefl_init(tdefl_compressor *d, tdefl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, int flags); +tdefl_status tdefl_init(tdefl_compressor *d, tdefl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, mz_uint flags); // Compresses a block of data, consuming as much of the specified input buffer as possible, and writing as much compressed data to the specified output buffer as possible. tdefl_status tdefl_compress(tdefl_compressor *d, const void *pIn_buf, size_t *pIn_buf_size, void *pOut_buf, size_t *pOut_buf_size, tdefl_flush flush); @@ -1224,7 +1224,8 @@ tinfl_status tinfl_decompress(tinfl_decompressor *r, const mz_uint8 *pIn_buf_nex *pOut_buf_cur++ = (mz_uint8)counter; } else { - int sym2; mz_uint code_len; + mz_uint sym2; + mz_uint code_len; #if TINFL_USE_64BIT_BITBUF if (num_bits < 30) { bit_buf |= (((tinfl_bit_buf_t)MZ_READ_LE32(pIn_buf_cur)) << num_bits); pIn_buf_cur += 4; num_bits += 32; } #else @@ -1345,7 +1346,7 @@ tinfl_status tinfl_decompress(tinfl_decompressor *r, const mz_uint8 *pIn_buf_nex } // Higher level helper functions. -void *tinfl_decompress_mem_to_heap(const void *pSrc_buf, size_t src_buf_len, size_t *pOut_len, int flags) +void *tinfl_decompress_mem_to_heap(const void *pSrc_buf, size_t src_buf_len, size_t *pOut_len, mz_uint flags) { tinfl_decompressor decomp; void *pBuf = NULL, *pNew_buf; size_t src_buf_ofs = 0, out_buf_capacity = 0; *pOut_len = 0; @@ -1370,14 +1371,14 @@ void *tinfl_decompress_mem_to_heap(const void *pSrc_buf, size_t src_buf_len, siz return pBuf; } -size_t tinfl_decompress_mem_to_mem(void *pOut_buf, size_t out_buf_len, const void *pSrc_buf, size_t src_buf_len, int flags) +size_t tinfl_decompress_mem_to_mem(void *pOut_buf, size_t out_buf_len, const void *pSrc_buf, size_t src_buf_len, mz_uint flags) { tinfl_decompressor decomp; tinfl_status status; tinfl_init(&decomp); status = tinfl_decompress(&decomp, (const mz_uint8 *)pSrc_buf, &src_buf_len, (mz_uint8 *)pOut_buf, (mz_uint8 *)pOut_buf, &out_buf_len, (flags & ~TINFL_FLAG_HAS_MORE_INPUT) | TINFL_FLAG_USING_NON_WRAPPING_OUTPUT_BUF); return (status != TINFL_STATUS_DONE) ? TINFL_DECOMPRESS_MEM_TO_MEM_FAILED : out_buf_len; } -int tinfl_decompress_mem_to_callback(const void *pIn_buf, size_t *pIn_buf_size, tinfl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, int flags) +int tinfl_decompress_mem_to_callback(const void *pIn_buf, size_t *pIn_buf_size, tinfl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, mz_uint flags) { int result = 0; tinfl_decompressor decomp; @@ -1661,7 +1662,8 @@ static mz_bool tdefl_compress_lz_codes(tdefl_compressor *d) #define TDEFL_PUT_BITS_FAST(b, l) { bit_buffer |= (((mz_uint64)(b)) << bits_in); bits_in += (l); } flags = 1; - for (pLZ_codes = d->m_lz_code_buf; pLZ_codes < pLZ_code_buf_end; flags >>= 1) { + pLZ_codes = d->m_lz_code_buf; + while (pLZ_codes < pLZ_code_buf_end) { if (flags == 1) flags = *pLZ_codes++ | 0x100; @@ -1712,6 +1714,7 @@ static mz_bool tdefl_compress_lz_codes(tdefl_compressor *d) pOutput_buf += (bits_in >> 3); bit_buffer >>= (bits_in & ~7); bits_in &= 7; + flags >>= 1; } #undef TDEFL_PUT_BITS_FAST @@ -2269,10 +2272,12 @@ tdefl_status tdefl_compress_buffer(tdefl_compressor *d, const void *pIn_buf, siz MZ_ASSERT(d->m_pPut_buf_func); return tdefl_compress(d, pIn_buf, &in_buf_size, NULL, NULL, flush); } -tdefl_status tdefl_init(tdefl_compressor *d, tdefl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, int flags) +tdefl_status tdefl_init(tdefl_compressor *d, tdefl_put_buf_func_ptr pPut_buf_func, void *pPut_buf_user, mz_uint flags) { d->m_pPut_buf_func = pPut_buf_func; d->m_pPut_buf_user = pPut_buf_user; - d->m_flags = (mz_uint)(flags); d->m_max_probes[0] = 1 + ((flags & 0xFFF) + 2) / 3; d->m_greedy_parsing = (flags & TDEFL_GREEDY_PARSING_FLAG) != 0; + d->m_flags = (mz_uint)(flags); + d->m_max_probes[0] = 1 + ((flags & 0xFFF) + 2) / 3; + d->m_greedy_parsing = (flags & TDEFL_GREEDY_PARSING_FLAG) != 0; d->m_max_probes[1] = 1 + (((flags & 0xFFF) >> 2) + 2) / 3; if (!(flags & TDEFL_NONDETERMINISTIC_PARSING_FLAG)) MZ_CLEAR_OBJ(d->m_hash); d->m_lookahead_pos = d->m_lookahead_size = d->m_dict_size = d->m_total_lz_bytes = d->m_lz_code_buf_dict_pos = d->m_bits_in = 0; @@ -2373,7 +2378,7 @@ mz_uint tdefl_create_comp_flags_from_zip_params(int level, int window_bits, int // Simple PNG writer function by Alex Evans, 2011. Released into the public domain: https://gist.github.com/908299, more context at // http://altdevblogaday.org/2011/04/06/a-smaller-jpg-encoder/. // This is actually a modification of Alex's original code so PNG files generated by this function pass pngcheck. -void *tdefl_write_image_to_png_file_in_memory_ex(const void *pImage, int w, int h, int num_chans, size_t *pLen_out, mz_uint level, mz_bool flip) +void *tdefl_write_image_to_png_file_in_memory_ex(const void *pImage, mz_uint8 w, mz_uint8 h, int num_chans, size_t *pLen_out, mz_uint level, mz_bool flip) { // Using a local copy of this array here in case MINIZ_NO_ZLIB_APIS was defined. static const mz_uint s_tdefl_png_num_probes[11] = { 0, 1, 6, 32, 16, 32, 128, 256, 512, 768, 1500 }; @@ -2402,7 +2407,7 @@ void *tdefl_write_image_to_png_file_in_memory_ex(const void *pImage, int w, int // compute final size of file, grab compressed data buffer and return *pLen_out += 57; MZ_FREE(pComp); return out_buf.m_pBuf; } -void *tdefl_write_image_to_png_file_in_memory(const void *pImage, int w, int h, int num_chans, size_t *pLen_out) +void *tdefl_write_image_to_png_file_in_memory(const void *pImage, mz_uint8 w, mz_uint8 h, int num_chans, size_t *pLen_out) { // Level 6 corresponds to TDEFL_DEFAULT_MAX_PROBES or MZ_DEFAULT_LEVEL (but we can't depend on MZ_DEFAULT_LEVEL being available in case the zlib API's where #defined out) return tdefl_write_image_to_png_file_in_memory_ex(pImage, w, h, num_chans, pLen_out, 6, MZ_FALSE); diff --git a/modules/core/src/tools/file/vpIoTools.cpp b/modules/core/src/tools/file/vpIoTools.cpp index 42cbd30975..022edf9365 100644 --- a/modules/core/src/tools/file/vpIoTools.cpp +++ b/modules/core/src/tools/file/vpIoTools.cpp @@ -56,7 +56,7 @@ #include #include #include -#include +#include // numeric_limits #include #include #include @@ -104,7 +104,7 @@ #define VP_STAT stat #endif -#if VISP_CXX_STANDARD > VISP_CXX_STANDARD_98 +#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) && defined(VISP_HAVE_MINIZ) #define USE_ZLIB_API 0 #if !USE_ZLIB_API @@ -486,6 +486,7 @@ visp::cnpy::NpyArray visp::cnpy::npy_load(std::string fname) #endif +BEGIN_VISP_NAMESPACE std::string vpIoTools::baseName = ""; std::string vpIoTools::baseDir = ""; std::string vpIoTools::configFile = ""; @@ -498,6 +499,7 @@ const char vpIoTools::separator = #else '/'; #endif +END_VISP_NAMESPACE namespace { @@ -538,10 +540,11 @@ std::string &rtrim(std::string &s) } } // namespace +BEGIN_VISP_NAMESPACE /*! Return build informations (OS, compiler, build flags, used 3rd parties...). */ -const std::string &vpIoTools::getBuildInformation() + const std::string &vpIoTools::getBuildInformation() { static std::string build_info = #include "version_string.inc" @@ -1527,7 +1530,8 @@ bool vpIoTools::readConfigVar(const std::string &var, float &value) { bool found = false; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { if (configValues[k].compare("PI") == 0) { value = static_cast(M_PI); @@ -1543,8 +1547,9 @@ bool vpIoTools::readConfigVar(const std::string &var, float &value) } found = true; } + ++k; } - if (found == false) { + if (!found) { std::cout << var << " not found in config file" << std::endl; } return found; @@ -1561,7 +1566,8 @@ bool vpIoTools::readConfigVar(const std::string &var, double &value) { bool found = false; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { if (configValues[k].compare("PI") == 0) { value = M_PI; @@ -1577,8 +1583,9 @@ bool vpIoTools::readConfigVar(const std::string &var, double &value) } found = true; } + ++k; } - if (found == false) { + if (!found) { std::cout << var << " not found in config file" << std::endl; } return found; @@ -1596,13 +1603,15 @@ bool vpIoTools::readConfigVar(const std::string &var, int &value) { bool found = false; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { value = atoi(configValues[k].c_str()); found = true; } + ++k; } - if (found == false) { + if (!found) { std::cout << var << " not found in config file" << std::endl; } return found; @@ -1668,13 +1677,15 @@ bool vpIoTools::readConfigVar(const std::string &var, std::string &value) { bool found = false; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { value = configValues[k]; found = true; } + ++k; } - if (found == false) { + if (!found) { std::cout << var << " not found in config file" << std::endl; } return found; @@ -1699,7 +1710,8 @@ bool vpIoTools::readConfigVar(const std::string &var, vpArray2D &value, bool found = false; std::string nb; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { found = true; // resize or not @@ -1729,6 +1741,7 @@ bool vpIoTools::readConfigVar(const std::string &var, vpArray2D &value, } } } + ++k; } if (found == false) { std::cout << var << " not found in config file" << std::endl; @@ -2693,3 +2706,4 @@ bool vpIoTools::parseBoolean(std::string input) Remove leading and trailing whitespaces from a string. */ std::string vpIoTools::trim(std::string s) { return ltrim(rtrim(s)); } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/geometry/vpPlane.cpp b/modules/core/src/tools/geometry/vpPlane.cpp index 1abdd1c96a..6125e7bb1f 100644 --- a/modules/core/src/tools/geometry/vpPlane.cpp +++ b/modules/core/src/tools/geometry/vpPlane.cpp @@ -43,6 +43,7 @@ #include // std::fabs #include // numeric_limits +BEGIN_VISP_NAMESPACE /*! Copy operator. */ @@ -385,7 +386,8 @@ void vpPlane::changeFrame(const vpHomogeneousMatrix &cMo) A,B,C and D correspond to the parameters of the plane. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpPlane &p) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpPlane &p) { return (os << "(" << p.getA() << "," << p.getB() << "," << p.getC() << "," << p.getD() << ") "); }; +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/geometry/vpPolygon.cpp b/modules/core/src/tools/geometry/vpPolygon.cpp index 1bc06c352a..a7df252f0d 100644 --- a/modules/core/src/tools/geometry/vpPolygon.cpp +++ b/modules/core/src/tools/geometry/vpPolygon.cpp @@ -49,13 +49,17 @@ #include + /*! * Compute convex hull corners. * * \param[in] ips : List of 2D points. */ -template std::vector convexHull(const IpContainer &ips) +template std::vector convexHull(const IpContainer &ips) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif if (ips.size() == 0) { throw vpException(vpException::badValue, "Convex Hull can not be computed as the input does not contain any image point."); @@ -105,6 +109,7 @@ template std::vector convexHull(const IpCon #endif +BEGIN_VISP_NAMESPACE /*! Default constructor that creates an empty polygon. */ @@ -696,3 +701,4 @@ unsigned int vpPolygon::getSize() const { return (static_cast(_corners.size())); } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/geometry/vpPolygon3D.cpp b/modules/core/src/tools/geometry/vpPolygon3D.cpp index bf8f6b1e8f..f5f47b6034 100644 --- a/modules/core/src/tools/geometry/vpPolygon3D.cpp +++ b/modules/core/src/tools/geometry/vpPolygon3D.cpp @@ -36,29 +36,30 @@ * *****************************************************************************/ -#include - -#include /*! \file vpPolygon3D.cpp \brief Implements a polygon of the model used by the model-based tracker. */ +#include + +#include + #include #include +BEGIN_VISP_NAMESPACE /*! Basic constructor. */ vpPolygon3D::vpPolygon3D() : nbpt(0), nbCornersInsidePrev(0), p(nullptr), polyClipped(), clippingFlag(vpPolygon3D::NO_CLIPPING), - distNearClip(0.001), distFarClip(100.) -{ -} + distNearClip(0.001), distFarClip(100.) +{ } vpPolygon3D::vpPolygon3D(const vpPolygon3D &mbtp) : nbpt(mbtp.nbpt), nbCornersInsidePrev(mbtp.nbCornersInsidePrev), p(nullptr), polyClipped(mbtp.polyClipped), - clippingFlag(mbtp.clippingFlag), distNearClip(mbtp.distNearClip), distFarClip(mbtp.distFarClip) + clippingFlag(mbtp.clippingFlag), distNearClip(mbtp.distNearClip), distFarClip(mbtp.distFarClip) { if (p) delete[] p; @@ -201,23 +202,23 @@ void vpPolygon3D::computePolygonClipped(const vpCameraParameters &cam) break; case 4: problem = - !(vpPolygon3D::getClippedPointsFovGeneric(p1Clipped, p2Clipped, p1Clipped, p2Clipped, p1ClippedInfo, - p2ClippedInfo, fovNormals[0], vpPolygon3D::LEFT_CLIPPING)); + !(vpPolygon3D::getClippedPointsFovGeneric(p1Clipped, p2Clipped, p1Clipped, p2Clipped, p1ClippedInfo, + p2ClippedInfo, fovNormals[0], vpPolygon3D::LEFT_CLIPPING)); break; case 8: problem = - !(vpPolygon3D::getClippedPointsFovGeneric(p1Clipped, p2Clipped, p1Clipped, p2Clipped, p1ClippedInfo, - p2ClippedInfo, fovNormals[1], vpPolygon3D::RIGHT_CLIPPING)); + !(vpPolygon3D::getClippedPointsFovGeneric(p1Clipped, p2Clipped, p1Clipped, p2Clipped, p1ClippedInfo, + p2ClippedInfo, fovNormals[1], vpPolygon3D::RIGHT_CLIPPING)); break; case 16: problem = - !(vpPolygon3D::getClippedPointsFovGeneric(p1Clipped, p2Clipped, p1Clipped, p2Clipped, p1ClippedInfo, - p2ClippedInfo, fovNormals[2], vpPolygon3D::UP_CLIPPING)); + !(vpPolygon3D::getClippedPointsFovGeneric(p1Clipped, p2Clipped, p1Clipped, p2Clipped, p1ClippedInfo, + p2ClippedInfo, fovNormals[2], vpPolygon3D::UP_CLIPPING)); break; case 32: problem = - !(vpPolygon3D::getClippedPointsFovGeneric(p1Clipped, p2Clipped, p1Clipped, p2Clipped, p1ClippedInfo, - p2ClippedInfo, fovNormals[3], vpPolygon3D::DOWN_CLIPPING)); + !(vpPolygon3D::getClippedPointsFovGeneric(p1Clipped, p2Clipped, p1Clipped, p2Clipped, p1ClippedInfo, + p2ClippedInfo, fovNormals[3], vpPolygon3D::DOWN_CLIPPING)); break; } @@ -306,7 +307,8 @@ bool vpPolygon3D::getClippedPointsFovGeneric(const vpPoint &p1, const vpPoint &p if (beta1 < M_PI / 2.0) { p1ClippedInfo = p1ClippedInfo | flag; p1Clipped = pClipped; - } else { + } + else { p2ClippedInfo = p2ClippedInfo | flag; p2Clipped = pClipped; } @@ -361,7 +363,8 @@ bool vpPolygon3D::getClippedPointsDistance(const vpPoint &p1, const vpPoint &p2, p1ClippedInfo = p1ClippedInfo | vpPolygon3D::FAR_CLIPPING; else p1ClippedInfo = p1ClippedInfo | vpPolygon3D::NEAR_CLIPPING; - } else { + } + else { p2Clipped = pClippedNear; if (flag == vpPolygon3D::FAR_CLIPPING) p2ClippedInfo = p2ClippedInfo | vpPolygon3D::FAR_CLIPPING; @@ -645,3 +648,4 @@ bool vpPolygon3D::roiInsideImage(const vpImage &I, const std::vec return true; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/geometry/vpRect.cpp b/modules/core/src/tools/geometry/vpRect.cpp index 8540789159..2bcde5ceb6 100644 --- a/modules/core/src/tools/geometry/vpRect.cpp +++ b/modules/core/src/tools/geometry/vpRect.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Constructs a default rectangle with the \e top, \e left corner set to (0,0) and \e width and \e height set to 1. @@ -271,3 +272,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRect &r) os << r.getLeft() << ", " << r.getTop() << ", " << r.getWidth() << ", " << r.getHeight(); return os; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/geometry/vpRectOriented.cpp b/modules/core/src/tools/geometry/vpRectOriented.cpp index 794edeebec..58139e6a83 100644 --- a/modules/core/src/tools/geometry/vpRectOriented.cpp +++ b/modules/core/src/tools/geometry/vpRectOriented.cpp @@ -36,6 +36,7 @@ #include +BEGIN_VISP_NAMESPACE /// Default constructor. vpRectOriented::vpRectOriented() : m_center(), m_width(), m_height(), m_theta(), m_topLeft(), m_topRight(), m_bottomLeft(), m_bottomRight() @@ -246,3 +247,4 @@ bool vpRectOriented::isLeft(const vpImagePoint &pointToTest, const vpImagePoint double d = (a * pointToTest.get_i()) + (b * pointToTest.get_j()) + c; return (d > 0); } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/geometry/vpTriangle.cpp b/modules/core/src/tools/geometry/vpTriangle.cpp index ff820314c0..eeea8cd25f 100644 --- a/modules/core/src/tools/geometry/vpTriangle.cpp +++ b/modules/core/src/tools/geometry/vpTriangle.cpp @@ -36,6 +36,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Basic constructor. @@ -189,3 +190,4 @@ bool vpTriangle::inTriangle(const vpImagePoint &iP, double threshold) return (p_ds_uv0 + p_ds_uv1 < 1. + threshold && p_ds_uv0 > -threshold && p_ds_uv1 > -threshold); } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/geometry/vpXmlParserRectOriented.cpp b/modules/core/src/tools/geometry/vpXmlParserRectOriented.cpp index 8aca50972f..386f83c8b5 100644 --- a/modules/core/src/tools/geometry/vpXmlParserRectOriented.cpp +++ b/modules/core/src/tools/geometry/vpXmlParserRectOriented.cpp @@ -50,6 +50,7 @@ #include +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpXmlParserRectOriented::Impl { @@ -203,7 +204,7 @@ void vpXmlParserRectOriented::save(const std::string &filename, bool append) { m vpRectOriented vpXmlParserRectOriented::getRectangle() const { return m_impl->getRectangle(); } void vpXmlParserRectOriented::setRectangle(const vpRectOriented &rectangle) { m_impl->setRectangle(rectangle); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpXmlParserRectOriented.cpp.o) has no symbols void dummy_vpXmlParserRectOriented() { }; diff --git a/modules/core/src/tools/histogram/vpHistogram.cpp b/modules/core/src/tools/histogram/vpHistogram.cpp index ff93dc2f48..415c49653b 100644 --- a/modules/core/src/tools/histogram/vpHistogram.cpp +++ b/modules/core/src/tools/histogram/vpHistogram.cpp @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE #if defined(VISP_HAVE_THREADS) #include @@ -1194,3 +1195,4 @@ bool vpHistogram::write(const char *filename) return true; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/histogram/vpHistogramPeak.cpp b/modules/core/src/tools/histogram/vpHistogramPeak.cpp index 42804768f6..c738a4e7f4 100644 --- a/modules/core/src/tools/histogram/vpHistogramPeak.cpp +++ b/modules/core/src/tools/histogram/vpHistogramPeak.cpp @@ -43,15 +43,16 @@ #include +BEGIN_VISP_NAMESPACE /*! Default constructor for a gray level histogram peak. */ -vpHistogramPeak::vpHistogramPeak() : level(0), value(0) {} +vpHistogramPeak::vpHistogramPeak() : level(0), value(0) { } /*! Default constructor for a gray level histogram peak. */ -vpHistogramPeak::vpHistogramPeak(unsigned char lvl, unsigned val) : level(lvl), value(val) {} +vpHistogramPeak::vpHistogramPeak(unsigned char lvl, unsigned val) : level(lvl), value(val) { } /*! Copy constructor of a gray level histogram peak. @@ -96,7 +97,7 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &s, const vpHistogramPeak &p) return s; } - +END_VISP_NAMESPACE /* * Local variables: * c-basic-offset: 2 diff --git a/modules/core/src/tools/histogram/vpHistogramValey.cpp b/modules/core/src/tools/histogram/vpHistogramValey.cpp index 2a0f14f78f..6c61700c84 100644 --- a/modules/core/src/tools/histogram/vpHistogramValey.cpp +++ b/modules/core/src/tools/histogram/vpHistogramValey.cpp @@ -43,6 +43,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Copy operator. @@ -85,6 +86,7 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &s, const vpHistogramValey &v) return s; } +END_VISP_NAMESPACE /* * Local variables: * c-basic-offset: 2 diff --git a/modules/core/src/tools/network/vpClient.cpp b/modules/core/src/tools/network/vpClient.cpp index 19d0994c8e..93fdc6f22e 100644 --- a/modules/core/src/tools/network/vpClient.cpp +++ b/modules/core/src/tools/network/vpClient.cpp @@ -40,7 +40,7 @@ // inet_ntop() not supported on win XP #ifdef VISP_HAVE_FUNC_INET_NTOP - +BEGIN_VISP_NAMESPACE vpClient::vpClient() : vpNetwork(), m_numberOfAttempts(0) { } /*! @@ -94,18 +94,18 @@ bool vpClient::connectToHostname(const std::string &hostname, const unsigned int serv.receptorIP = inet_ntoa(*(in_addr *)server->h_addr); return connectServer(serv); - } +} - /*! - Connect to the server represented by the given ip, and at a given port. +/*! + Connect to the server represented by the given ip, and at a given port. - \sa vpClient::connectToHostname() + \sa vpClient::connectToHostname() - \param ip : IP of the server. - \param port_serv : Port used for the connection. + \param ip : IP of the server. + \param port_serv : Port used for the connection. - \return True if the connection has been etablished, false otherwise. - */ + \return True if the connection has been etablished, false otherwise. +*/ bool vpClient::connectToIP(const std::string &ip, const unsigned int &port_serv) { vpNetwork::vpReceptor serv; @@ -127,13 +127,13 @@ bool vpClient::connectToIP(const std::string &ip, const unsigned int &port_serv) serv.receptorAddress.sin_port = htons((unsigned short)port_serv); return connectServer(serv); - } +} - /*! - Deconnect from the server at a specific index. +/*! + Deconnect from the server at a specific index. - \param index : Index of the server. - */ + \param index : Index of the server. +*/ void vpClient::deconnect(const unsigned int &index) { if (index < receptor_list.size()) { @@ -214,7 +214,7 @@ bool vpClient::connectServer(vpNetwork::vpReceptor &serv) std::cout << "Connected!" << std::endl; return true; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpClient.cpp.o) has no symbols void dummy_vpClient() { }; diff --git a/modules/core/src/tools/network/vpNetwork.cpp b/modules/core/src/tools/network/vpNetwork.cpp index 158c5942e3..8419f05e97 100644 --- a/modules/core/src/tools/network/vpNetwork.cpp +++ b/modules/core/src/tools/network/vpNetwork.cpp @@ -40,7 +40,7 @@ // inet_ntop() not supported on win XP #ifdef VISP_HAVE_FUNC_INET_NTOP - +BEGIN_VISP_NAMESPACE vpNetwork::vpNetwork() : emitter(), receptor_list(), readFileDescriptor(), socketMax(0), request_list(), max_size_message(999999), separator("[*@*]"), beginning("[*start*]"), end("[*end*]"), param_sep("[*|*]"), currentMessageReceived(), tv(), @@ -794,7 +794,7 @@ int vpNetwork::privReceiveRequestOnceFrom(const unsigned int &receptorEmitting) return numbytes; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpNetwork.cpp.o) has no symbols void dummy_vpNetwork() { }; diff --git a/modules/core/src/tools/network/vpRequest.cpp b/modules/core/src/tools/network/vpRequest.cpp index bc3fd7b313..75e201aa0f 100644 --- a/modules/core/src/tools/network/vpRequest.cpp +++ b/modules/core/src/tools/network/vpRequest.cpp @@ -38,6 +38,7 @@ #include +BEGIN_VISP_NAMESPACE vpRequest::vpRequest() : request_id(""), listOfParams() { } vpRequest::~vpRequest() { } @@ -78,3 +79,4 @@ void vpRequest::addParameter(const std::vector &listOfparams) this->listOfParams.push_back(listOfparams[i]); } } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/network/vpServer.cpp b/modules/core/src/tools/network/vpServer.cpp index 80d68105ca..c1e62cfab1 100644 --- a/modules/core/src/tools/network/vpServer.cpp +++ b/modules/core/src/tools/network/vpServer.cpp @@ -44,6 +44,7 @@ #include // To detect OSX or IOS using TARGET_OS_IPHONE or TARGET_OS_IOS macro #endif +BEGIN_VISP_NAMESPACE /*! Construct a server on the machine launching it. */ @@ -174,7 +175,8 @@ bool vpServer::start() int set_option = 1; if (0 == setsockopt(emitter.socketFileDescriptorEmitter, SOL_SOCKET, SO_NOSIGPIPE, &set_option, sizeof(set_option))) { - } else { + } + else { std::cout << "Failed to set socket signal option" << std::endl; } } @@ -232,9 +234,11 @@ bool vpServer::checkForConnections() if (value == -1) { // vpERROR_TRACE( "vpServer::run(), select()" ); return false; - } else if (value == 0) { + } + else if (value == 0) { return false; - } else { + } + else { if (FD_ISSET((unsigned int)emitter.socketFileDescriptorEmitter, &readFileDescriptor)) { vpNetwork::vpReceptor client; client.receptorAddressSize = sizeof(client.receptorAddress); @@ -243,8 +247,8 @@ bool vpServer::checkForConnections() emitter.socketFileDescriptorEmitter, (struct sockaddr *)&client.receptorAddress, &client.receptorAddressSize); #else // Win32 client.socketFileDescriptorReceptor = - accept((unsigned int)emitter.socketFileDescriptorEmitter, (struct sockaddr *)&client.receptorAddress, - &client.receptorAddressSize); + accept((unsigned int)emitter.socketFileDescriptorEmitter, (struct sockaddr *)&client.receptorAddress, + &client.receptorAddressSize); #endif #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX @@ -259,7 +263,8 @@ bool vpServer::checkForConnections() receptor_list.push_back(client); return true; - } else { + } + else { for (unsigned int i = 0; i < receptor_list.size(); i++) { if (FD_ISSET((unsigned int)receptor_list[i].socketFileDescriptorReceptor, &readFileDescriptor)) { char deco; @@ -286,8 +291,8 @@ bool vpServer::checkForConnections() Print the connected clients. */ void vpServer::print() { vpNetwork::print("Client"); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpServer.cpp.o) has no symbols -void dummy_vpServer(){}; +void dummy_vpServer() { }; #endif diff --git a/modules/core/src/tools/network/vpUDPClient.cpp b/modules/core/src/tools/network/vpUDPClient.cpp index eba00e84f4..cee4559cbc 100644 --- a/modules/core/src/tools/network/vpUDPClient.cpp +++ b/modules/core/src/tools/network/vpUDPClient.cpp @@ -58,6 +58,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Default constructor. @@ -66,11 +67,10 @@ vpUDPClient::vpUDPClient() : m_is_init(false), m_serverAddress(), m_serverLength(0), m_socketFileDescriptor() #if defined(_WIN32) - , - m_wsa() + , + m_wsa() #endif -{ -} +{ } /*! Create a (IPv4) UDP client. @@ -81,8 +81,8 @@ vpUDPClient::vpUDPClient() vpUDPClient::vpUDPClient(const std::string &hostname, int port) : m_is_init(false), m_serverAddress(), m_serverLength(0), m_socketFileDescriptor() #if defined(_WIN32) - , - m_wsa() + , + m_wsa() #endif { init(hostname, port); @@ -345,8 +345,8 @@ int vpUDPClient::send(const void *msg, size_t len) return sendto(m_socketFileDescriptor, (char *)msg, (int)len, 0, (struct sockaddr *)&m_serverAddress, m_serverLength); #endif } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpUDPClient.cpp.o) has no symbols -void dummy_vpUDPClient(){}; +void dummy_vpUDPClient() { }; #endif diff --git a/modules/core/src/tools/network/vpUDPServer.cpp b/modules/core/src/tools/network/vpUDPServer.cpp index 42725f7db3..f804858813 100644 --- a/modules/core/src/tools/network/vpUDPServer.cpp +++ b/modules/core/src/tools/network/vpUDPServer.cpp @@ -65,6 +65,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Create a (IPv4) UDP server. @@ -74,8 +75,8 @@ vpUDPServer::vpUDPServer(int port) : m_clientAddress(), m_clientLength(0), m_serverAddress(), m_socketFileDescriptor(0) #if defined(_WIN32) - , - m_wsa() + , + m_wsa() #endif { init("", port); @@ -90,8 +91,8 @@ vpUDPServer::vpUDPServer(int port) vpUDPServer::vpUDPServer(const std::string &hostname, int port) : m_clientAddress(), m_clientLength(0), m_serverAddress(), m_socketFileDescriptor(0) #if defined(_WIN32) - , - m_wsa() + , + m_wsa() #endif { init(hostname, port); @@ -145,7 +146,8 @@ void vpUDPServer::init(const std::string &hostname, int port) m_serverAddress.sin_family = AF_INET; m_serverAddress.sin_addr.s_addr = htonl(INADDR_ANY); m_serverAddress.sin_port = htons((unsigned short)port); - } else { + } + else { std::stringstream ss; ss << port; struct addrinfo hints; @@ -234,7 +236,7 @@ int vpUDPServer::receive(std::string &msg, std::string &hostInfo, int timeoutMs) (struct sockaddr *)&m_clientAddress, (socklen_t *)&m_clientLength)); #else int length = - recvfrom(m_socketFileDescriptor, m_buf, sizeof(m_buf), 0, (struct sockaddr *)&m_clientAddress, &m_clientLength); + recvfrom(m_socketFileDescriptor, m_buf, sizeof(m_buf), 0, (struct sockaddr *)&m_clientAddress, &m_clientLength); #endif if (length <= 0) { return length < 0 ? -1 : 0; @@ -251,7 +253,8 @@ int vpUDPServer::receive(std::string &msg, std::string &hostInfo, int timeoutMs) std::string hostName = "", hostIp = "", hostPort = ""; if (dwRetval != 0) { std::cerr << "getnameinfo failed with error: " << WSAGetLastError() << std::endl; - } else { + } + else { hostName = hostname; hostPort = servInfo; } @@ -260,7 +263,8 @@ int vpUDPServer::receive(std::string &msg, std::string &hostInfo, int timeoutMs) const char *ptr = inet_ntop(AF_INET, (void *)&m_clientAddress.sin_addr, result, sizeof(result)); if (ptr == nullptr) { std::cerr << "inet_ntop failed with error: " << WSAGetLastError() << std::endl; - } else { + } + else { hostIp = result; } @@ -330,8 +334,8 @@ int vpUDPServer::send(const std::string &msg, const std::string &hostname, int p m_clientLength); #endif } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpUDPServer.cpp.o) has no symbols -void dummy_vpUDPServer(){}; +void dummy_vpUDPServer() { }; #endif diff --git a/modules/core/src/tools/optimization/vpLinProg.cpp b/modules/core/src/tools/optimization/vpLinProg.cpp index fea24cea8f..67dbf4446d 100644 --- a/modules/core/src/tools/optimization/vpLinProg.cpp +++ b/modules/core/src/tools/optimization/vpLinProg.cpp @@ -38,6 +38,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Reduces the search space induced by an equality constraint. @@ -727,5 +728,5 @@ bool vpLinProg::simplex(const vpColVector &c, vpMatrix A, vpColVector b, vpColVe std::swap(B[k], N[j]); } } - #endif +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/optimization/vpQuadProg.cpp b/modules/core/src/tools/optimization/vpQuadProg.cpp index fdac7be8f2..05a7d3d210 100644 --- a/modules/core/src/tools/optimization/vpQuadProg.cpp +++ b/modules/core/src/tools/optimization/vpQuadProg.cpp @@ -41,7 +41,7 @@ #include #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - +BEGIN_VISP_NAMESPACE /*! Changes a canonical quadratic cost \f$\min \frac{1}{2}\mathbf{x}^T\mathbf{H}\mathbf{x} + \mathbf{c}^T\mathbf{x}\f$ to the formulation used by this class \f$ \min ||\mathbf{Q}\mathbf{x} - \mathbf{r}||^2\f$. @@ -678,7 +678,7 @@ vpColVector vpQuadProg::solveSVDorQR(const vpMatrix &A, const vpColVector &b) return A.solveBySVD(b); return A.solveByQR(b); } - +END_VISP_NAMESPACE #else void dummy_vpQuadProg() { }; #endif diff --git a/modules/core/src/tools/serial/vpSerial.cpp b/modules/core/src/tools/serial/vpSerial.cpp index a36e5e16f1..dc67b13159 100644 --- a/modules/core/src/tools/serial/vpSerial.cpp +++ b/modules/core/src/tools/serial/vpSerial.cpp @@ -59,6 +59,7 @@ #endif #endif +BEGIN_VISP_NAMESPACE /*! Creates a serial port object that opens the port if the parameter is not empty. \code @@ -97,7 +98,7 @@ int main() vpSerial::vpSerial(const std::string &port, unsigned long baudrate, bytesize_t bytesize, parity_t parity, stopbits_t stopbits, flowcontrol_t flowcontrol) : m_port(port), m_fd(-1), m_is_open(false), m_xonxoff(false), m_rtscts(false), m_baudrate(baudrate), m_parity(parity), - m_bytesize(bytesize), m_stopbits(stopbits), m_flowcontrol(flowcontrol) + m_bytesize(bytesize), m_stopbits(stopbits), m_flowcontrol(flowcontrol) { if (m_port.empty() == false) open(); @@ -168,7 +169,8 @@ int vpSerial::available() int count = 0; if (-1 == ioctl(m_fd, TIOCINQ, &count)) { throw(vpException(vpException::fatalError, "Cannot check is serial port data available")); - } else { + } + else { return count; } } @@ -185,7 +187,8 @@ void vpSerial::close() ret = ::close(m_fd); if (ret == 0) { m_fd = -1; - } else { + } + else { throw(vpException(vpException::fatalError, "Cannot close serial port")); } } @@ -262,7 +265,7 @@ bool vpSerial::read(char *c, long timeout_s) } fd_set readfds; /* list of fds for select to listen to */ - struct timeval timeout = {timeout_s, 0}; // seconde, micro-sec + struct timeval timeout = { timeout_s, 0 }; // seconde, micro-sec FD_ZERO(&readfds); FD_SET(static_cast(m_fd), &readfds); @@ -271,10 +274,12 @@ bool vpSerial::read(char *c, long timeout_s) if (ret < 0) { throw(vpException(vpException::fatalError, "Serial i/o exception")); - } else if (ret == 0) { - // Timeout occurred + } + else if (ret == 0) { + // Timeout occurred return false; - } else { + } + else { ssize_t n = ::read(m_fd, c, 1); // read one character at a time if (n != 1) return false; @@ -337,10 +342,10 @@ void vpSerial::configure() // set up raw mode / no echo / binary options.c_cflag |= (tcflag_t)(CLOCAL | CREAD); - options.c_lflag &= (tcflag_t) ~(ICANON | ECHO | ECHOE | ECHOK | ECHONL | ISIG | IEXTEN); //|ECHOPRT + options.c_lflag &= (tcflag_t)~(ICANON | ECHO | ECHOE | ECHOK | ECHONL | ISIG | IEXTEN); //|ECHOPRT - options.c_oflag &= (tcflag_t) ~(OPOST); - options.c_iflag &= (tcflag_t) ~(INLCR | IGNCR | ICRNL | IGNBRK); + options.c_oflag &= (tcflag_t)~(OPOST); + options.c_iflag &= (tcflag_t)~(INLCR | IGNCR | ICRNL | IGNBRK); #ifdef IUCLC options.c_iflag &= (tcflag_t)~IUCLC; @@ -541,7 +546,7 @@ void vpSerial::configure() switch (m_stopbits) { case stopbits_one: - options.c_cflag &= (tcflag_t) ~(CSTOPB); + options.c_cflag &= (tcflag_t)~(CSTOPB); break; case stopbits_two: options.c_cflag |= (CSTOPB); @@ -549,13 +554,13 @@ void vpSerial::configure() } // setup parity - options.c_iflag &= (tcflag_t) ~(INPCK | ISTRIP); + options.c_iflag &= (tcflag_t)~(INPCK | ISTRIP); switch (m_parity) { case parity_none: - options.c_cflag &= (tcflag_t) ~(PARENB | PARODD); + options.c_cflag &= (tcflag_t)~(PARENB | PARODD); break; case parity_even: - options.c_cflag &= (tcflag_t) ~(PARODD); + options.c_cflag &= (tcflag_t)~(PARODD); options.c_cflag |= (PARENB); break; case parity_odd: @@ -584,9 +589,9 @@ void vpSerial::configure() options.c_iflag |= (IXON | IXOFF); else #ifdef IXANY - options.c_iflag &= (tcflag_t) ~(IXON | IXOFF | IXANY); + options.c_iflag &= (tcflag_t)~(IXON | IXOFF | IXANY); #else - options.c_iflag &= (tcflag_t) ~(IXON | IXOFF); + options.c_iflag &= (tcflag_t)~(IXON | IXOFF); #endif // rtscts @@ -610,8 +615,8 @@ void vpSerial::configure() // activate settings ::tcsetattr(m_fd, TCSANOW, &options); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_ar.a(vpAROgre.cpp.o) has no symbols -void dummy_vpSerial(){}; +void dummy_vpSerial() { }; #endif diff --git a/modules/core/src/tools/time/vpTime.cpp b/modules/core/src/tools/time/vpTime.cpp index d4250259d8..b735961e7e 100644 --- a/modules/core/src/tools/time/vpTime.cpp +++ b/modules/core/src/tools/time/vpTime.cpp @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + \file vpTime.cpp + \brief Time management and measurement +*/ + #include #include @@ -46,11 +51,6 @@ #define USE_CXX11_CHRONO 0 #endif -/*! - \file vpTime.cpp - \brief Time management and measurement -*/ - // Unix depend version #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX @@ -61,6 +61,7 @@ #include #endif +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS namespace vpTime { @@ -210,17 +211,17 @@ int wait(double t0, double t) "vpTime::wait() is not implemented on Windows Phone 8.0")); #endif #endif + } } -} -/*! - Wait t miliseconds from now. + /*! + Wait t miliseconds from now. - The waiting is done by a call to usleep() if the time to wait is greater - than vpTime::minTimeForUsleepCall. + The waiting is done by a call to usleep() if the time to wait is greater + than vpTime::minTimeForUsleepCall. - \param t : Time to wait in ms. -*/ + \param t : Time to wait in ms. + */ void wait(double t) { double timeToWait = t; @@ -261,14 +262,14 @@ void wait(double t) "vpTime::wait() is not implemented on Windows Phone 8.0")); #endif #endif + } } -} -/*! - Sleep t miliseconds from now. + /*! + Sleep t miliseconds from now. - \param t : Time to sleep in ms. -*/ + \param t : Time to sleep in ms. + */ void sleepMs(double t) { #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX @@ -419,3 +420,4 @@ void vpChrono::stop() m_durationMs += vpTime::measureTimeMs() - m_lastTimePoint; #endif } +END_VISP_NAMESPACE diff --git a/modules/core/src/tools/xml/vpXmlParser.cpp b/modules/core/src/tools/xml/vpXmlParser.cpp index 56480aee98..140b5f83fe 100644 --- a/modules/core/src/tools/xml/vpXmlParser.cpp +++ b/modules/core/src/tools/xml/vpXmlParser.cpp @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Basic constructor. @@ -481,7 +482,7 @@ void vpXmlParser::save(const std::string &filename, bool append) xmlSaveFormatFile(filename.c_str(), doc, 1); xmlFreeDoc(doc); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpXmlParser.cpp.o) has no symbols void dummy_vpXmlParser() { }; diff --git a/modules/core/src/tracking/forward-projection/vpCircle.cpp b/modules/core/src/tracking/forward-projection/vpCircle.cpp index a5674ba4fa..024c400e6d 100644 --- a/modules/core/src/tracking/forward-projection/vpCircle.cpp +++ b/modules/core/src/tracking/forward-projection/vpCircle.cpp @@ -37,6 +37,7 @@ #include +BEGIN_VISP_NAMESPACE void vpCircle::init() { oP.resize(7); @@ -432,3 +433,4 @@ void vpCircle::computeIntersectionPoint(const vpCircle &circle, const vpCameraPa (ctheta * n11 * Yg)) + (ctheta3 * n11 * Yg) + (ctheta * n02 * Xg)) - (ctheta3 * n02 * Xg)) / (((n20 * ctheta2) + (2.0 * n11 * stheta * ctheta) + n02) - (n02 * ctheta2)) / stheta); } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/forward-projection/vpCylinder.cpp b/modules/core/src/tracking/forward-projection/vpCylinder.cpp index 65b83613f7..a73171ae80 100644 --- a/modules/core/src/tracking/forward-projection/vpCylinder.cpp +++ b/modules/core/src/tracking/forward-projection/vpCylinder.cpp @@ -36,6 +36,7 @@ #include #include +BEGIN_VISP_NAMESPACE void vpCylinder::init() { oP.resize(7); @@ -420,3 +421,4 @@ void vpCylinder::display(const vpImage &I, const vpCameraParameters &cam { vpFeatureDisplay::displayCylinder(p[0], p[1], p[2], p[3], cam, I, color, thickness); } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/forward-projection/vpForwardProjection.cpp b/modules/core/src/tracking/forward-projection/vpForwardProjection.cpp index 285008782e..247d985251 100644 --- a/modules/core/src/tracking/forward-projection/vpForwardProjection.cpp +++ b/modules/core/src/tracking/forward-projection/vpForwardProjection.cpp @@ -33,14 +33,15 @@ * *****************************************************************************/ -#include -#include - /*! \file vpForwardProjection.cpp \brief class that defines what is a point */ +#include +#include + +BEGIN_VISP_NAMESPACE /*! Print to stdout the feature parameters in: - the object frame @@ -101,3 +102,4 @@ void vpForwardProjection::project(const vpHomogeneousMatrix &cMo) */ void vpForwardProjection::track(const vpHomogeneousMatrix &cMo) { project(cMo); } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/forward-projection/vpLine.cpp b/modules/core/src/tracking/forward-projection/vpLine.cpp index 2d7a7113c3..168461f95f 100644 --- a/modules/core/src/tracking/forward-projection/vpLine.cpp +++ b/modules/core/src/tracking/forward-projection/vpLine.cpp @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + \file vpLine.cpp + \brief class that defines what is a line +*/ + #include #include @@ -40,11 +45,7 @@ #include -/*! - \file vpLine.cpp - \brief class that defines what is a line -*/ - +BEGIN_VISP_NAMESPACE /*! Initialize the memory space requested for the 2D line parameters (\e @@ -549,3 +550,4 @@ vpLine *vpLine::duplicate() const vpLine *feature = new vpLine(*this); return feature; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/forward-projection/vpPoint.cpp b/modules/core/src/tracking/forward-projection/vpPoint.cpp index 2767575b43..a684f74d7c 100644 --- a/modules/core/src/tracking/forward-projection/vpPoint.cpp +++ b/modules/core/src/tracking/forward-projection/vpPoint.cpp @@ -33,15 +33,16 @@ * *****************************************************************************/ -#include -#include -#include - /*! \file vpPoint.cpp \brief Class that defines what is a 3D point. */ +#include +#include +#include + +BEGIN_VISP_NAMESPACE void vpPoint::init() { p.resize(3); @@ -410,8 +411,6 @@ void vpPoint::display(const vpImage &I, const vpHomogeneousMatrix &cMo, vpFeatureDisplay::displayPoint(v_p[0], v_p[1], cam, I, color, thickness); } -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpPoint & /* vpp */) { return (os << "vpPoint"); } - /*! * Display the projection of a 3D point in image \e I. * @@ -506,3 +505,6 @@ void vpPoint::set_x(double x) { p[0] = x; } void vpPoint::set_y(double y) { p[1] = y; } //! Set the point w coordinate in the image plane. void vpPoint::set_w(double w) { p[2] = w; } + +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpPoint & /* vpp */) { return (os << "vpPoint"); } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/forward-projection/vpSphere.cpp b/modules/core/src/tracking/forward-projection/vpSphere.cpp index 1f892dd383..953c3e7c71 100644 --- a/modules/core/src/tracking/forward-projection/vpSphere.cpp +++ b/modules/core/src/tracking/forward-projection/vpSphere.cpp @@ -36,6 +36,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Initialize internal sphere parameters. */ @@ -297,3 +298,4 @@ void vpSphere::display(const vpImage &I, const vpCameraParameters &cam, { vpFeatureDisplay::displayEllipse(p[0], p[1], p[2], p[3], p[4], cam, I, color, thickness); } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMoment.cpp b/modules/core/src/tracking/moments/vpMoment.cpp index 121ab5dc81..144423d381 100644 --- a/modules/core/src/tracking/moments/vpMoment.cpp +++ b/modules/core/src/tracking/moments/vpMoment.cpp @@ -40,6 +40,21 @@ #include #include #include + +BEGIN_VISP_NAMESPACE +/*! + * Prints the moment contents to a stream + * \param os : a std::stream. + * \param m : a moment instance. + */ +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMoment &m) +{ + for (std::vector::const_iterator i = m.values.begin(); i != m.values.end(); ++i) + os << *i << ","; + + return os; +} + /*! * Default constructor */ @@ -107,19 +122,6 @@ void vpMoment::linkTo(vpMomentDatabase &data_base) */ void vpMoment::update(vpMomentObject &moment_object) { this->object = &moment_object; } -/*! - * Prints the moment contents to a stream - * \param os : a std::stream. - * \param m : a moment instance. - */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMoment &m) -{ - for (std::vector::const_iterator i = m.values.begin(); i != m.values.end(); ++i) - os << *i << ","; - - return os; -} - /*! * Prints values of all dependent moments required to calculate a specific * vpMoment. Not made pure to maintain compatibility Recommended : Types @@ -132,3 +134,4 @@ void vpMoment::printDependencies(std::ostream &os) const "the derived classes!" << std::endl; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentAlpha.cpp b/modules/core/src/tracking/moments/vpMomentAlpha.cpp index 19ace725f7..61ed730227 100644 --- a/modules/core/src/tracking/moments/vpMomentAlpha.cpp +++ b/modules/core/src/tracking/moments/vpMomentAlpha.cpp @@ -41,6 +41,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Empty constructor. Initializes alpha moment as a reference alpha with a value in \f$[-\pi/2 ; \pi/2]\f$. A default-constructed alpha moment may be @@ -67,7 +68,7 @@ vpMomentAlpha::vpMomentAlpha() */ vpMomentAlpha::vpMomentAlpha(const std::vector &mu3_ref, double alpha_ref, double threshold) : vpMoment(), m_isRef(false), m_symmetric(true), m_mu3Ref(mu3_ref), m_alphaRef(alpha_ref), - m_symmetricThreshold(threshold) + m_symmetricThreshold(threshold) { for (std::vector::const_iterator it = mu3_ref.begin(); it != mu3_ref.end(); ++it) { if (std::fabs(*it) > m_symmetricThreshold) { @@ -89,7 +90,7 @@ void vpMomentAlpha::compute() bool found_moment_centered; const vpMomentCentered &momentCentered = - (static_cast(getMoments().get("vpMomentCentered", found_moment_centered))); + (static_cast(getMoments().get("vpMomentCentered", found_moment_centered))); if (!found_moment_centered) throw vpException(vpException::notInitialized, "vpMomentCentered not found"); @@ -100,7 +101,8 @@ void vpMomentAlpha::compute() if (m_isRef) { m_alphaRef = alpha; - } else { + } + else { if (!m_symmetric) { double r11 = cos(alpha - m_alphaRef); double r12 = sin(alpha - m_alphaRef); @@ -145,7 +147,8 @@ void vpMomentAlpha::compute() if (signChange) { if (alpha < 0) { alpha += M_PI; - } else { + } + else { alpha -= M_PI; } } @@ -154,16 +157,6 @@ void vpMomentAlpha::compute() values[0] = alpha; } -/*! - Prints the value of the major-axis orientation in degrees and rad - */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAlpha &c) -{ - os << (__FILE__) << std::endl; - os << "Alpha = " << c.values[0] << "rad = " << vpMath::deg(c.values[0]) << "deg " << std::endl; - return os; -} - /*! Prints the dependencies of alpha, namely centered moments mu11, mu20 ad mu02 */ @@ -172,7 +165,7 @@ void vpMomentAlpha::printDependencies(std::ostream &os) const os << (__FILE__) << std::endl; bool found_moment_centered; const vpMomentCentered &momentCentered = - (static_cast(getMoments().get("vpMomentCentered", found_moment_centered))); + (static_cast(getMoments().get("vpMomentCentered", found_moment_centered))); if (!found_moment_centered) throw vpException(vpException::notInitialized, "vpMomentCentered not found"); @@ -180,3 +173,18 @@ void vpMomentAlpha::printDependencies(std::ostream &os) const os << "mu20 = " << momentCentered.get(2, 0) << "\t"; os << "mu02 = " << momentCentered.get(0, 2) << std::endl; } + +/*! + Prints the value of the major-axis orientation in degrees and rad + */ +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAlpha &c) +{ +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + os << (__FILE__) << std::endl; + os << "Alpha = " << c.values[0] << "rad = " << vpMath::deg(c.values[0]) << "deg " << std::endl; + return os; +} + +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentArea.cpp b/modules/core/src/tracking/moments/vpMomentArea.cpp index 4a916f0b8e..434c6f8135 100644 --- a/modules/core/src/tracking/moments/vpMomentArea.cpp +++ b/modules/core/src/tracking/moments/vpMomentArea.cpp @@ -41,6 +41,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Has the area \f$ a = m_{00} = \mu_{00} \f$ for dense objects, \f$ \mu_{20}+\mu_{02} \f$ for a discrete set of points. @@ -58,11 +59,12 @@ void vpMomentArea::compute() * linked to it */ const vpMomentCentered &momentCentered = - static_cast(getMoments().get("vpMomentCentered", found_moment_centered)); + static_cast(getMoments().get("vpMomentCentered", found_moment_centered)); if (!found_moment_centered) throw vpException(vpException::notInitialized, "vpMomentCentered not found"); values[0] = momentCentered.get(2, 0) + momentCentered.get(0, 2); - } else { + } + else { values[0] = getObject().get(0, 0); } } @@ -72,16 +74,6 @@ void vpMomentArea::compute() */ vpMomentArea::vpMomentArea() : vpMoment() { values.resize(1); } -/*! - Outputs the moment's values to a stream. -*/ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentArea &m) -{ - os << (__FILE__) << std::endl; - os << "a(m00) = " << m.values[0] << std::endl; - return os; -} - /*! If the vpMomentObject type is 1. DISCRETE(set of discrete points), uses mu20+mu02 @@ -93,14 +85,27 @@ void vpMomentArea::printDependencies(std::ostream &os) const bool found_moment_centered; const vpMomentCentered &momentCentered = - static_cast(getMoments().get("vpMomentCentered", found_moment_centered)); + static_cast(getMoments().get("vpMomentCentered", found_moment_centered)); if (!found_moment_centered) throw vpException(vpException::notInitialized, "vpMomentCentered not found"); if (getObject().getType() == vpMomentObject::DISCRETE) { os << "mu20 = " << momentCentered.get(2, 0) << "\t"; os << "mu02 = " << momentCentered.get(0, 2) << std::endl; - } else { + } + else { os << "mu00 = " << momentCentered.get(0, 0) << std::endl; } } + +/*! + Outputs the moment's values to a stream. +*/ +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentArea &m) +{ + os << (__FILE__) << std::endl; + os << "a(m00) = " << m.values[0] << std::endl; + return os; +} + +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentAreaNormalized.cpp b/modules/core/src/tracking/moments/vpMomentAreaNormalized.cpp index e81999de34..6b8b96ceb3 100644 --- a/modules/core/src/tracking/moments/vpMomentAreaNormalized.cpp +++ b/modules/core/src/tracking/moments/vpMomentAreaNormalized.cpp @@ -41,6 +41,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! Computes the normalized area \f$ a_n=Z^* \sqrt{\frac{a^*}{a}} \f$. Depends on vpMomentCentered. @@ -82,16 +84,6 @@ vpMomentAreaNormalized::vpMomentAreaNormalized(double a_star, double Z_star) values.resize(1); } -/*! - Outputs the moment's values to a stream. -*/ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAreaNormalized &m) -{ - os << (__FILE__) << std::endl; - os << "An = " << m.values[0] << std::endl; - return os; -} - /*! Prints dependencies namely, 1. Depth at desired pose Z* @@ -119,3 +111,14 @@ void vpMomentAreaNormalized::printDependencies(std::ostream &os) const a = getObject().get(0, 0); os << "a = " << a << std::endl; } + +/*! + Outputs the moment's values to a stream. +*/ +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAreaNormalized &m) +{ + os << (__FILE__) << std::endl; + os << "An = " << m.values[0] << std::endl; + return os; +} +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentBasic.cpp b/modules/core/src/tracking/moments/vpMomentBasic.cpp index 336c731871..aa56683d28 100644 --- a/modules/core/src/tracking/moments/vpMomentBasic.cpp +++ b/modules/core/src/tracking/moments/vpMomentBasic.cpp @@ -38,10 +38,12 @@ #include #include + +BEGIN_VISP_NAMESPACE /*! Default constructor. */ -vpMomentBasic::vpMomentBasic() : vpMoment() {} +vpMomentBasic::vpMomentBasic() : vpMoment() { } /*! Retrieve all moments of all orders computed. vpMomentBasic::get()[j*order+i] @@ -64,28 +66,29 @@ double vpMomentBasic::get(unsigned int i, unsigned int j) const { return getObje /*! Dummy function. Everything is already done in object. */ -void vpMomentBasic::compute() {} +void vpMomentBasic::compute() { } /*! - Outputs the moment's values to a stream. - Same output as in vpMomentObject. +No dependencies on other vpMoments, since basic moments are computed in +vpMomentObject Just prints the basic moments in vpMomentObject with indices */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentBasic &m) +void vpMomentBasic::printDependencies(std::ostream &os) const { os << (__FILE__) << std::endl; - vpMomentObject::printWithIndices(m.getObject(), os); - return os; + os << "No dependencies on other vpMoments, since basic moments are " + "computed in vpMomentObject" + << std::endl; + vpMomentObject::printWithIndices(getObject(), os); } /*! -No dependencies on other vpMoments, since basic moments are computed in -vpMomentObject Just prints the basic moments in vpMomentObject with indices + Outputs the moment's values to a stream. + Same output as in vpMomentObject. */ -void vpMomentBasic::printDependencies(std::ostream &os) const +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentBasic &m) { os << (__FILE__) << std::endl; - os << "No dependencies on other vpMoments, since basic moments are " - "computed in vpMomentObject" - << std::endl; - vpMomentObject::printWithIndices(getObject(), os); + vpMomentObject::printWithIndices(m.getObject(), os); + return os; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentCInvariant.cpp b/modules/core/src/tracking/moments/vpMomentCInvariant.cpp index 782c199e3b..a5f32da3a0 100644 --- a/modules/core/src/tracking/moments/vpMomentCInvariant.cpp +++ b/modules/core/src/tracking/moments/vpMomentCInvariant.cpp @@ -41,6 +41,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Default constructor. (option to use a different calculation mode for sx and sy) @@ -122,15 +123,15 @@ void vpMomentCInvariant::computeI(const vpMomentCentered &momentCentered, std::v I_val[4] = (mu30 + mu12) * (mu30 + mu12) + (mu21 + mu03) * (mu21 + mu03); I_val[5] = -mu30_2 * mu03_2 + (-4 * mu12_3 + 6 * mu21 * mu12 * mu03) * mu30 - 4 * mu21_3 * mu03 + 3 * mu21_2 * mu12_2; I_val[6] = 3 * mu12_4 + 2 * mu30 * mu12_3 + (3 * mu30_2 - 6 * mu03 * mu21) * mu12_2 - - 6 * mu30 * mu21 * (mu21 + mu03) * mu12 + 2 * mu30_2 * mu03_2 + 2 * mu21_3 * mu03 + 3 * mu21_2 * mu03_2 + - 3 * mu21_4; + 6 * mu30 * mu21 * (mu21 + mu03) * mu12 + 2 * mu30_2 * mu03_2 + 2 * mu21_3 * mu03 + 3 * mu21_2 * mu03_2 + + 3 * mu21_4; I_val[7] = (3 * mu21 + 2 * mu03) * mu12_3 + 3 * mu30 * (mu03 + 2 * mu21) * mu12_2 - - 3 * mu21 * (mu30 + mu03 + mu21) * (-mu30 + mu03 + mu21) * mu12 + - mu30 * (-mu30_2 * mu03 - 2 * mu21_3 - 3 * mu03 * mu21_2 + mu03_3); - // I_val[8]=3*mu21_4-3*mu21_3*mu03+(3*mu03_2+kappa-6*mu12_2)*mu21_2-mu03*(-15*mu12_2+kappa)*mu21-(-3*mu12_2*mu30+(2*kappa-3*mu03_2)*mu12+kappa*mu30)*mu12; + 3 * mu21 * (mu30 + mu03 + mu21) * (-mu30 + mu03 + mu21) * mu12 + + mu30 * (-mu30_2 * mu03 - 2 * mu21_3 - 3 * mu03 * mu21_2 + mu03_3); +// I_val[8]=3*mu21_4-3*mu21_3*mu03+(3*mu03_2+kappa-6*mu12_2)*mu21_2-mu03*(-15*mu12_2+kappa)*mu21-(-3*mu12_2*mu30+(2*kappa-3*mu03_2)*mu12+kappa*mu30)*mu12; I_val[8] = 3 * mu03 * mu21_3 - 2 * mu03_2 * mu21_2 + mu21_2 * mu30_2 + 3 * mu12_2 * mu03 * mu21 - - mu03 * mu21 * mu30_2 - mu03_3 * mu21 + 3 * mu12_3 * mu30 - 2 * mu12_2 * mu30_2 + mu12_2 * mu03_2 - - mu12 * mu30_3 - mu12 * mu30 * mu03_2 + 3 * mu12 * mu30 * mu21_2 - 6 * mu12 * mu30 * mu03 * mu21; + mu03 * mu21 * mu30_2 - mu03_3 * mu21 + 3 * mu12_3 * mu30 - 2 * mu12_2 * mu30_2 + mu12_2 * mu03_2 - + mu12 * mu30_3 - mu12 * mu30 * mu03_2 + 3 * mu12 * mu30 * mu21_2 - 6 * mu12 * mu30 * mu03 * mu21; I_val[9] = omicron * omicron; I_val[10] = mu40 * mu04 - 4 * mu31 * mu13 + 3 * mu22_2; @@ -169,7 +170,7 @@ void vpMomentCInvariant::computeI(const vpMomentCentered &momentCentered, std::v double p02 = momentCentered.get(0, 2) / II[3]; double d = - sqrt(std::fabs(a)) / (II[3] * sqrt(std::fabs(II[3]))); // d is the normalization factor for 3rd order moments + sqrt(std::fabs(a)) / (II[3] * sqrt(std::fabs(II[3]))); // d is the normalization factor for 3rd order moments double p30 = momentCentered.get(3, 0) * d; double p21 = momentCentered.get(2, 1) * d; double p12 = momentCentered.get(1, 2) * d; @@ -199,7 +200,7 @@ void vpMomentCInvariant::compute() "Specify at least order 5."); bool found_moment_centered; const vpMomentCentered &momentCentered = - (static_cast(getMoments().get("vpMomentCentered", found_moment_centered))); + (static_cast(getMoments().get("vpMomentCentered", found_moment_centered))); if (!found_moment_centered) throw vpException(vpException::notInitialized, "vpMomentCentered not found"); @@ -292,3 +293,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentCInvariant } return os; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentCentered.cpp b/modules/core/src/tracking/moments/vpMomentCentered.cpp index 5ea7600b3a..c51be2a96a 100644 --- a/modules/core/src/tracking/moments/vpMomentCentered.cpp +++ b/modules/core/src/tracking/moments/vpMomentCentered.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! To set the values of centred moments. Required when normalizing the moment values. @@ -68,7 +69,7 @@ void vpMomentCentered::compute() values.resize((getObject().getOrder() + 1) * (getObject().getOrder() + 1)); const vpMomentGravityCenter &momentGravity = - static_cast(getMoments().get("vpMomentGravityCenter", found_moment_gravity)); + static_cast(getMoments().get("vpMomentGravityCenter", found_moment_gravity)); if (!found_moment_gravity) throw vpException(vpException::notInitialized, "vpMomentGravityCenter not found"); @@ -92,7 +93,7 @@ void vpMomentCentered::compute() /*! Default constructor. */ -vpMomentCentered::vpMomentCentered() : vpMoment() {} +vpMomentCentered::vpMomentCentered() : vpMoment() { } /*! Gets the desired moment using indexes. @@ -112,42 +113,6 @@ double vpMomentCentered::get(unsigned int i, unsigned int j) const return values[j * (order + 1) + i]; } -/*! - Outputs the centered moment's values \f$\mu_{ij}\f$ to a stream presented as -a matrix. The first line corresponds to \f$\mu_{0[0:order]}\f$, the second one -to \f$\mu_{1[0:order]}\f$ Values in table corresponding to a higher order are -marked with an "x" and not computed. - - For example, if the maximal order is 3, the following values are provided: - - \code -u00 u10 u20 u30 -u01 u11 u21 x -u02 u12 x x -u30 x x x - \endcode - - This output will be followed by an output with indexes as produced by -printWithIndices() function -*/ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentCentered &m) -{ - for (unsigned int i = 0; i < m.values.size(); i++) { - if (i % (m.getObject().getOrder() + 1) == 0) - os << std::endl; - - if ((i % (m.getObject().getOrder() + 1) + i / (m.getObject().getOrder() + 1)) < m.getObject().getOrder() + 1) - os << m.values[i]; - else - os << "x"; - - os << "\t"; - } - os << std::endl; - m.printWithIndices(os); - return os; -} - /*! Print in a readable form which looks better than output from << operator */ @@ -183,9 +148,46 @@ void vpMomentCentered::printDependencies(std::ostream &os) const */ bool found_moment_gravity; const vpMomentGravityCenter &momentGravity = - static_cast(getMoments().get("vpMomentGravityCenter", found_moment_gravity)); + static_cast(getMoments().get("vpMomentGravityCenter", found_moment_gravity)); if (!found_moment_gravity) throw vpException(vpException::notInitialized, "vpMomentGravityCenter not found"); os << "Xg = " << momentGravity.getXg() << "\t" - << "Yg = " << momentGravity.getYg() << std::endl; + << "Yg = " << momentGravity.getYg() << std::endl; +} + +/*! + Outputs the centered moment's values \f$\mu_{ij}\f$ to a stream presented as +a matrix. The first line corresponds to \f$\mu_{0[0:order]}\f$, the second one +to \f$\mu_{1[0:order]}\f$ Values in table corresponding to a higher order are +marked with an "x" and not computed. + + For example, if the maximal order is 3, the following values are provided: + + \code +u00 u10 u20 u30 +u01 u11 u21 x +u02 u12 x x +u30 x x x + \endcode + + This output will be followed by an output with indexes as produced by +printWithIndices() function +*/ +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentCentered &m) +{ + for (unsigned int i = 0; i < m.values.size(); i++) { + if (i % (m.getObject().getOrder() + 1) == 0) + os << std::endl; + + if ((i % (m.getObject().getOrder() + 1) + i / (m.getObject().getOrder() + 1)) < m.getObject().getOrder() + 1) + os << m.values[i]; + else + os << "x"; + + os << "\t"; + } + os << std::endl; + m.printWithIndices(os); + return os; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentCommon.cpp b/modules/core/src/tracking/moments/vpMomentCommon.cpp index e890a0fb77..c15a7c4984 100644 --- a/modules/core/src/tracking/moments/vpMomentCommon.cpp +++ b/modules/core/src/tracking/moments/vpMomentCommon.cpp @@ -39,6 +39,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Default constructor. Initializes the common database with the following moments: basic, gravity,centered,centered+normalized,normalized @@ -227,3 +228,4 @@ vpMomentCommon::~vpMomentCommon() if (momentCInvariant) delete momentCInvariant; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentDatabase.cpp b/modules/core/src/tracking/moments/vpMomentDatabase.cpp index aab0306600..29264a40dd 100644 --- a/modules/core/src/tracking/moments/vpMomentDatabase.cpp +++ b/modules/core/src/tracking/moments/vpMomentDatabase.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Adds a moment to the database. * \param moment : Moment to add. @@ -92,6 +93,9 @@ void vpMomentDatabase::updateAll(vpMomentObject &object) */ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentDatabase &m) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::map::const_iterator itr; os << "{"; @@ -102,3 +106,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentDatabase &m return os; } +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentGravityCenter.cpp b/modules/core/src/tracking/moments/vpMomentGravityCenter.cpp index ee6307fcdc..6a1af4340b 100644 --- a/modules/core/src/tracking/moments/vpMomentGravityCenter.cpp +++ b/modules/core/src/tracking/moments/vpMomentGravityCenter.cpp @@ -38,6 +38,8 @@ #include #include + +BEGIN_VISP_NAMESPACE /*! Computes the two gravity center coordinates commonly called \f$x_g\f$ and \f$y_g\f$. @@ -59,16 +61,6 @@ vpMomentGravityCenter::vpMomentGravityCenter() : vpMoment() { values.resize(2); */ const std::vector &vpMomentGravityCenter::get() const { return values; } -/*! - Outputs the moment's values to a stream. -*/ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenter &m) -{ - os << (__FILE__) << std::endl; - os << "(Xg,Yg) = (" << m.values[0] << ", " << m.values[1] << ")" << std::endl; - return os; -} - /*! Prints its dependencies Basic moments m10, m01 and m00 from vpMomentObject @@ -80,3 +72,14 @@ void vpMomentGravityCenter::printDependencies(std::ostream &os) const os << "m00 = " << getObject().get(0, 1) << "\t"; os << "m00 = " << getObject().get(0, 0) << std::endl; } + +/*! + Outputs the moment's values to a stream. +*/ +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenter &m) +{ + os << (__FILE__) << std::endl; + os << "(Xg,Yg) = (" << m.values[0] << ", " << m.values[1] << ")" << std::endl; + return os; +} +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentGravityCenterNormalized.cpp b/modules/core/src/tracking/moments/vpMomentGravityCenterNormalized.cpp index c9efb735d7..3a8cb33947 100644 --- a/modules/core/src/tracking/moments/vpMomentGravityCenterNormalized.cpp +++ b/modules/core/src/tracking/moments/vpMomentGravityCenterNormalized.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Computes normalized gravity center moment. Depends on vpMomentAreaNormalized and on vpMomentGravityCenter. @@ -54,7 +55,7 @@ void vpMomentGravityCenterNormalized::compute() const vpMomentAreaNormalized &momentSurfaceNormalized = static_cast( getMoments().get("vpMomentAreaNormalized", found_moment_surface_normalized)); const vpMomentGravityCenter &momentGravity = - static_cast(getMoments().get("vpMomentGravityCenter", found_moment_gravity)); + static_cast(getMoments().get("vpMomentGravityCenter", found_moment_gravity)); if (!found_moment_surface_normalized) throw vpException(vpException::notInitialized, "vpMomentAreaNormalized not found"); @@ -71,17 +72,7 @@ void vpMomentGravityCenterNormalized::compute() /*! Default constructor. */ -vpMomentGravityCenterNormalized::vpMomentGravityCenterNormalized() : vpMomentGravityCenter() {} - -/*! - Outputs the moment's values to a stream. -*/ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenterNormalized &m) -{ - os << (__FILE__) << std::endl; - os << "(Xn,Yn) = (" << m.values[0] << ", " << m.values[1] << ")" << std::endl; - return os; -} +vpMomentGravityCenterNormalized::vpMomentGravityCenterNormalized() : vpMomentGravityCenter() { } /*! Prints the dependent moments, @@ -97,13 +88,24 @@ void vpMomentGravityCenterNormalized::printDependencies(std::ostream &os) const const vpMomentAreaNormalized &momentSurfaceNormalized = static_cast( getMoments().get("vpMomentAreaNormalized", found_moment_surface_normalized)); const vpMomentGravityCenter &momentGravity = - static_cast(getMoments().get("vpMomentGravityCenter", found_moment_gravity)); + static_cast(getMoments().get("vpMomentGravityCenter", found_moment_gravity)); if (!found_moment_surface_normalized) throw vpException(vpException::notInitialized, "vpMomentAreaNormalized not found"); if (!found_moment_gravity) throw vpException(vpException::notInitialized, "vpMomentGravityCenter not found"); os << "Xg = " << momentGravity.get()[0] << "\t" - << "Yg = " << momentGravity.get()[1] << std::endl; + << "Yg = " << momentGravity.get()[1] << std::endl; os << "An = " << momentSurfaceNormalized.get()[0] << std::endl; } + +/*! + Outputs the moment's values to a stream. +*/ +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenterNormalized &m) +{ + os << (__FILE__) << std::endl; + os << "(Xn,Yn) = (" << m.values[0] << ", " << m.values[1] << ")" << std::endl; + return os; +} +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/moments/vpMomentObject.cpp b/modules/core/src/tracking/moments/vpMomentObject.cpp index d206132df8..5abf0b7514 100644 --- a/modules/core/src/tracking/moments/vpMomentObject.cpp +++ b/modules/core/src/tracking/moments/vpMomentObject.cpp @@ -51,6 +51,7 @@ #endif #include +BEGIN_VISP_NAMESPACE /*! Computes moments from a vector of points describing a polygon (\cite Steger96). The points must be stored in a clockwise order. Used internally. @@ -236,7 +237,8 @@ void vpMomentObject::fromVector(std::vector &points) for (unsigned int j = 0; j < order * order; j++) { values[j] = calc_mom_polygon(j % order, j / order, points); } - } else { + } + else { std::vector cache(order * order, 0.); values.assign(order * order, 0); for (unsigned int i = 0; i < points.size(); i++) { @@ -415,8 +417,9 @@ void vpMomentObject::fromImage(const vpImage &image, const vpCame } } } - } else { - /////////// BLACK BACKGROUND /////////// + } + else { + /////////// BLACK BACKGROUND /////////// for (unsigned int j = 0; j < image.getRows(); j++) { for (unsigned int i = 0; i < image.getCols(); i++) { x = 0; @@ -559,39 +562,6 @@ void vpMomentObject::set(unsigned int i, unsigned int j, const double &value_ij) values[j * order + i] = value_ij; } -/*! - Outputs the basic moment's values \f$m_{ij}\f$ to a stream presented as a - matrix. The first line corresponds to \f$m_{0[0:order]}\f$, the second one - to \f$m_{1[0:order]}\f$ Values in table corresponding to a higher order are - marked with an "x" and not computed. - - For example, if the maximal order is 3, the following values are provided: - - \code - m00 m10 m20 m30 - m01 m11 m21 x - m02 m12 x x - m03 x x x - \endcode -*/ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentObject &m) -{ - for (unsigned int i = 0; i < m.values.size(); i++) { - - if (i % (m.order) == 0) - os << std::endl; - - if ((i % (m.order) + i / (m.order)) < m.order) - os << m.values[i]; - else - os << "x"; - - os << "\t"; - } - - return os; -} - /*! Outputs the raw moment values \f$m_{ij}\f$ in indexed form. The moment values are same as provided by the operator << which outputs x @@ -662,3 +632,39 @@ vpMomentObject::~vpMomentObject() { // deliberate empty } + +/*! + Outputs the basic moment's values \f$m_{ij}\f$ to a stream presented as a + matrix. The first line corresponds to \f$m_{0[0:order]}\f$, the second one + to \f$m_{1[0:order]}\f$ Values in table corresponding to a higher order are + marked with an "x" and not computed. + + For example, if the maximal order is 3, the following values are provided: + + \code + m00 m10 m20 m30 + m01 m11 m21 x + m02 m12 x x + m03 x x x + \endcode +*/ +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentObject &m) +{ + for (unsigned int i = 0; i < m.values.size(); ++i) { + + if (i % (m.order) == 0) + os << std::endl; + + if ((i % (m.order) + i / (m.order)) < m.order) { + os << m.values[i]; + } + else { + os << "x"; + } + + os << "\t"; + } + + return os; +} +END_VISP_NAMESPACE diff --git a/modules/core/src/tracking/vpTracker.cpp b/modules/core/src/tracking/vpTracker.cpp index e0ec1f0e6f..9c2a5374e1 100644 --- a/modules/core/src/tracking/vpTracker.cpp +++ b/modules/core/src/tracking/vpTracker.cpp @@ -33,17 +33,19 @@ * *****************************************************************************/ -#include -#include - /*! \file vpTracker.cpp \brief Class that defines what is a generic tracker. */ +#include +#include + +BEGIN_VISP_NAMESPACE + void vpTracker::init() { cPAvailable = false; } -vpTracker::vpTracker() : p(), cP(), cPAvailable(false) {} +vpTracker::vpTracker() : p(), cP(), cPAvailable(false) { } vpTracker::vpTracker(const vpTracker &tracker) : p(), cP(), cPAvailable(false) { *this = tracker; } @@ -55,7 +57,7 @@ vpTracker &vpTracker::operator=(const vpTracker &tracker) return *this; } - +END_VISP_NAMESPACE /* * Local variables: * c-basic-offset: 2 diff --git a/modules/core/test/camera/testCameraParametersConversion.cpp b/modules/core/test/camera/testCameraParametersConversion.cpp index 7c8f691715..ce807c3b93 100644 --- a/modules/core/test/camera/testCameraParametersConversion.cpp +++ b/modules/core/test/camera/testCameraParametersConversion.cpp @@ -51,6 +51,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { { std::cout << "* Test operator=()" << std::endl; @@ -103,8 +106,8 @@ int main() vpMeterPixelConversion::convertPoint(cam, x1, y1, u2, v2); if (!vpMath::equal(u1, u2) || !vpMath::equal(v1, v2)) { std::cerr << "Error in point conversion without distortion:\n" - << "u1 = " << u1 << ", u2 = " << u2 << std::endl - << "v1 = " << v1 << ", v2 = " << v2 << std::endl; + << "u1 = " << u1 << ", u2 = " << u2 << std::endl + << "v1 = " << v1 << ", v2 = " << v2 << std::endl; return EXIT_FAILURE; } @@ -113,8 +116,8 @@ int main() vpMeterPixelConversion::convertPoint(camDist, x1, y1, u2, v2); if (!vpMath::equal(u1, u2) || !vpMath::equal(v1, v2)) { std::cerr << "Error in point conversion without distortion:\n" - << "u1 = " << u1 << ", u2 = " << u2 << std::endl - << "v1 = " << v1 << ", v2 = " << v2 << std::endl; + << "u1 = " << u1 << ", u2 = " << u2 << std::endl + << "v1 = " << v1 << ", v2 = " << v2 << std::endl; return EXIT_FAILURE; } @@ -129,7 +132,7 @@ int main() vpPixelMeterConversion::convertPoint(cameraMatrix, distCoeffs, u1, v1, x2, y2); if (!vpMath::equal(x1, x2, 1e-6) || !vpMath::equal(y1, y2, 1e-6)) { std::cerr << "Error in point pixel meter conversion: visp result (" << x1 << ", " << y1 << ") " - << "differ from OpenCV result (" << x2 << ", " << y2 << ")" << std::endl; + << "differ from OpenCV result (" << x2 << ", " << y2 << ")" << std::endl; return EXIT_FAILURE; } @@ -138,7 +141,7 @@ int main() vpPixelMeterConversion::convertPoint(cameraMatrix, distCoeffs, ip, x2, y2); if (!vpMath::equal(x1, x2, 1e-6) || !vpMath::equal(y1, y2, 1e-6)) { std::cerr << "Error in point pixel meter conversion: visp result (" << x1 << ", " << y1 << ") " - << "differ from OpenCV result (" << x2 << ", " << y2 << ")" << std::endl; + << "differ from OpenCV result (" << x2 << ", " << y2 << ")" << std::endl; return EXIT_FAILURE; } @@ -147,7 +150,7 @@ int main() vpMeterPixelConversion::convertPoint(cameraMatrix, distCoeffs, x1, y1, u2, v2); if (!vpMath::equal(u1, u2, 1e-6) || !vpMath::equal(v1, v2, 1e-6)) { std::cerr << "Error in point meter pixel conversion: visp result (" << u1 << ", " << v1 << ") " - << "differ from OpenCV result (" << u2 << ", " << v2 << ")" << std::endl; + << "differ from OpenCV result (" << u2 << ", " << v2 << ")" << std::endl; return EXIT_FAILURE; } @@ -156,7 +159,7 @@ int main() vpMeterPixelConversion::convertPoint(cameraMatrix, distCoeffs, x1, y1, iP2); if (vpImagePoint::distance(iP1, iP2) > 1e-6) { std::cerr << "Error in point meter pixel conversion: visp result (" << u1 << ", " << v1 << ") " - << "differ from OpenCV result (" << u2 << ", " << v2 << ")" << std::endl; + << "differ from OpenCV result (" << u2 << ", " << v2 << ")" << std::endl; return EXIT_FAILURE; } } @@ -172,7 +175,7 @@ int main() vpPixelMeterConversion::convertPoint(cameraMatrix, distCoeffs, u1, v1, x2, y2); if (!vpMath::equal(x1, x2, 1e-6) || !vpMath::equal(y1, y2, 1e-6)) { std::cerr << "Error in point conversion: visp result (" << x1 << ", " << y1 << ") " - << "differ from OpenCV result (" << x2 << ", " << y2 << ")" << std::endl; + << "differ from OpenCV result (" << x2 << ", " << y2 << ")" << std::endl; return EXIT_FAILURE; } @@ -182,7 +185,7 @@ int main() vpMeterPixelConversion::convertPoint(cameraMatrix, distCoeffs, x1, y1, u2, v2); if (!vpMath::equal(u1, u2, 1e-6) || !vpMath::equal(v1, v2, 1e-6)) { std::cerr << "Error in point meter pixel conversion: visp result (" << u1 << ", " << v1 << ") " - << "differ from OpenCV result (" << u2 << ", " << v2 << ")" << std::endl; + << "differ from OpenCV result (" << u2 << ", " << v2 << ")" << std::endl; return EXIT_FAILURE; } } @@ -197,7 +200,7 @@ int main() vpPixelMeterConversion::convertLine(cameraMatrix, rho_p, theta_p, rho_m2, theta_m2); if (!vpMath::equal(rho_m1, rho_m2, 1e-6) || !vpMath::equal(theta_m1, theta_m2, 1e-6)) { std::cerr << "Error in line pixel meter conversion: visp result (" << rho_m1 << ", " << theta_m1 << ") " - << "differ from OpenCV result (" << rho_m2 << ", " << theta_m1 << ")" << std::endl; + << "differ from OpenCV result (" << rho_m2 << ", " << theta_m1 << ")" << std::endl; return EXIT_FAILURE; } @@ -207,7 +210,7 @@ int main() vpMeterPixelConversion::convertLine(cameraMatrix, rho_m1, theta_m1, rho_p2, theta_p2); if (!vpMath::equal(rho_p1, rho_p2, 1e-6) || !vpMath::equal(theta_p1, theta_p2, 1e-6)) { std::cerr << "Error in line meter pixel conversion: visp result (" << rho_p1 << ", " << theta_p1 << ") " - << "differ from OpenCV result (" << rho_p2 << ", " << theta_p1 << ")" << std::endl; + << "differ from OpenCV result (" << rho_p2 << ", " << theta_p1 << ")" << std::endl; return EXIT_FAILURE; } } @@ -234,8 +237,8 @@ int main() for (unsigned int j = 0; j < m1.getCols(); j++) { if (!vpMath::equal(m1[i][j], m1[i][j], 1e-6)) { std::cerr << "Error in moments pixel meter conversion: visp result for [" << i << "][" << j << "] (" - << m1[i][j] << ") " - << "differ from OpenCV result (" << m2[i][j] << ")" << std::endl; + << m1[i][j] << ") " + << "differ from OpenCV result (" << m2[i][j] << ")" << std::endl; return EXIT_FAILURE; } } @@ -244,7 +247,7 @@ int main() { std::cout << "* Compare ViSP and OpenCV ellipse from circle meter pixel conversion without distortion" - << std::endl; + << std::endl; cv::Mat cameraMatrix = (cv::Mat_(3, 3) << px, 0, u0, 0, py, v0, 0, 0, 1); vpCircle circle; circle.setWorldCoordinates(0, 0, 1, 0, 0, 0, 0.1); // plane:(Z=0),X0=0,Y0=0,Z=0,R=0.1 @@ -260,18 +263,18 @@ int main() if (!vpMath::equal(n20_p1, n20_p2, 1e-6) || !vpMath::equal(n11_p1, n11_p2, 1e-6) || !vpMath::equal(n02_p1, n02_p2, 1e-6)) { std::cerr << "Error in ellipse from circle meter pixel conversion: visp result (" << n20_p1 << ", " << n11_p1 - << ", " << n02_p1 << ") " - << "differ from OpenCV result (" << n20_p2 << ", " << n11_p2 << ", " << n02_p2 << ")" << std::endl; + << ", " << n02_p1 << ") " + << "differ from OpenCV result (" << n20_p2 << ", " << n11_p2 << ", " << n02_p2 << ")" << std::endl; return EXIT_FAILURE; } if (vpImagePoint::distance(center_p1, center_p2) > 1e-6) { std::cerr << "Error in ellipse from circle meter pixel conversion: visp result (" << center_p1 << ") " - << "differ from OpenCV result (" << center_p2 << ")" << std::endl; + << "differ from OpenCV result (" << center_p2 << ")" << std::endl; return EXIT_FAILURE; } std::cout << "* Compare ViSP and OpenCV ellipse from sphere meter pixel conversion without distortion" - << std::endl; + << std::endl; vpSphere sphere; sphere.setWorldCoordinates(0, 0, 0, 0.1); // X0=0,Y0=0,Z0=0,R=0.1 circle.changeFrame(cMo); @@ -282,13 +285,13 @@ int main() if (!vpMath::equal(n20_p1, n20_p2, 1e-6) || !vpMath::equal(n11_p1, n11_p2, 1e-6) || !vpMath::equal(n02_p1, n02_p2, 1e-6)) { std::cerr << "Error in ellipse from sphere meter pixel conversion: visp result (" << n20_p1 << ", " << n11_p1 - << ", " << n02_p1 << ") " - << "differ from OpenCV result (" << n20_p2 << ", " << n11_p2 << ", " << n02_p2 << ")" << std::endl; + << ", " << n02_p1 << ") " + << "differ from OpenCV result (" << n20_p2 << ", " << n11_p2 << ", " << n02_p2 << ")" << std::endl; return EXIT_FAILURE; } if (vpImagePoint::distance(center_p1, center_p2) > 1e-6) { std::cerr << "Error in ellipse from sphere meter pixel conversion: visp result (" << center_p1 << ") " - << "differ from OpenCV result (" << center_p2 << ")" << std::endl; + << "differ from OpenCV result (" << center_p2 << ")" << std::endl; return EXIT_FAILURE; } } @@ -296,7 +299,8 @@ int main() std::cout << "Test successful" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/camera/testJsonCamera.cpp b/modules/core/test/camera/testJsonCamera.cpp index 2d406d2674..2eea57cf25 100644 --- a/modules/core/test/camera/testJsonCamera.cpp +++ b/modules/core/test/camera/testJsonCamera.cpp @@ -49,6 +49,10 @@ using json = nlohmann::json; //! json namespace shortcut #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #include namespace { diff --git a/modules/core/test/camera/testXmlParserCamera.cpp b/modules/core/test/camera/testXmlParserCamera.cpp index bf26a31369..37c531b673 100644 --- a/modules/core/test/camera/testXmlParserCamera.cpp +++ b/modules/core/test/camera/testXmlParserCamera.cpp @@ -44,6 +44,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if defined(VISP_HAVE_PUGIXML) #if defined(_WIN32) diff --git a/modules/core/test/image-with-dataset/common.hpp b/modules/core/test/image-with-dataset/common.hpp index a10efa2d21..9a059f8d4d 100644 --- a/modules/core/test/image-with-dataset/common.hpp +++ b/modules/core/test/image-with-dataset/common.hpp @@ -46,6 +46,9 @@ namespace common_tools { +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif static const int g_nearest_neighbor = 0; static const int g_bilinear = 1; diff --git a/modules/core/test/image-with-dataset/perfColorConversion.cpp b/modules/core/test/image-with-dataset/perfColorConversion.cpp index e6df803d23..3dd6446ca3 100644 --- a/modules/core/test/image-with-dataset/perfColorConversion.cpp +++ b/modules/core/test/image-with-dataset/perfColorConversion.cpp @@ -50,6 +50,9 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif static std::string ipath = vpIoTools::getViSPImagesDataPath(); static std::string imagePathColor = vpIoTools::createFilePath(ipath, "Klimt/Klimt.ppm"); static std::string imagePathGray = vpIoTools::createFilePath(ipath, "Klimt/Klimt.pgm"); diff --git a/modules/core/test/image-with-dataset/perfGaussianFilter.cpp b/modules/core/test/image-with-dataset/perfGaussianFilter.cpp index e557cf30ce..39cd7f6603 100644 --- a/modules/core/test/image-with-dataset/perfGaussianFilter.cpp +++ b/modules/core/test/image-with-dataset/perfGaussianFilter.cpp @@ -50,6 +50,9 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif static const std::string ipath = vpIoTools::getViSPImagesDataPath(); static std::string imagePath = vpIoTools::createFilePath(ipath, "faces/1280px-Solvay_conference_1927.png"); diff --git a/modules/core/test/image-with-dataset/perfImageAddSub.cpp b/modules/core/test/image-with-dataset/perfImageAddSub.cpp index 94456af16c..79372cf975 100644 --- a/modules/core/test/image-with-dataset/perfImageAddSub.cpp +++ b/modules/core/test/image-with-dataset/perfImageAddSub.cpp @@ -50,6 +50,9 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif TEST_CASE("Benchmark vpImageTools::imageAdd()", "[benchmark]") { const std::string filepath = vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "Klimt/Klimt.pgm"); @@ -146,11 +149,11 @@ int main(int argc, char *argv[]) // Build a new parser on top of Catch's using namespace Catch::clara; auto cli = session.cli() // Get Catch's composite command line parser - | Opt(runBenchmark) // bind variable to a new option, with a hint string - ["--benchmark"] // the option names it will respond to - ("run benchmark?"); // description string for the help output + | Opt(runBenchmark) // bind variable to a new option, with a hint string + ["--benchmark"] // the option names it will respond to + ("run benchmark?"); // description string for the help output - // Now pass the new composite back to Catch so it uses that +// Now pass the new composite back to Catch so it uses that session.cli(cli); // Let Catch (using Clara) parse the command line diff --git a/modules/core/test/image-with-dataset/perfImageMorphology.cpp b/modules/core/test/image-with-dataset/perfImageMorphology.cpp index 2635e46150..a592bc36a7 100644 --- a/modules/core/test/image-with-dataset/perfImageMorphology.cpp +++ b/modules/core/test/image-with-dataset/perfImageMorphology.cpp @@ -46,6 +46,9 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif static std::string ipath = vpIoTools::getViSPImagesDataPath(); TEST_CASE("Benchmark binary image morphology", "[benchmark]") @@ -238,7 +241,7 @@ TEST_CASE("Benchmark gray image morphology", "[benchmark]") } #endif -int main(int argc, char *argv []) +int main(int argc, char *argv[]) { Catch::Session session; // There must be exactly one instance diff --git a/modules/core/test/image-with-dataset/perfImageResize.cpp b/modules/core/test/image-with-dataset/perfImageResize.cpp index 98fb426a42..529a1cca71 100644 --- a/modules/core/test/image-with-dataset/perfImageResize.cpp +++ b/modules/core/test/image-with-dataset/perfImageResize.cpp @@ -51,6 +51,9 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif static const std::string ipath = vpIoTools::getViSPImagesDataPath(); static std::string imagePathColor = vpIoTools::createFilePath(ipath, "Klimt/Klimt.ppm"); static std::string imagePathGray = vpIoTools::createFilePath(ipath, "Klimt/Klimt.pgm"); diff --git a/modules/core/test/image-with-dataset/perfImageWarp.cpp b/modules/core/test/image-with-dataset/perfImageWarp.cpp index f5ed50cf31..0d747d07c2 100644 --- a/modules/core/test/image-with-dataset/perfImageWarp.cpp +++ b/modules/core/test/image-with-dataset/perfImageWarp.cpp @@ -44,6 +44,9 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif namespace { static std::string ipath = vpIoTools::getViSPImagesDataPath(); @@ -341,11 +344,11 @@ int main(int argc, char *argv[]) // Build a new parser on top of Catch's using namespace Catch::clara; auto cli = session.cli() // Get Catch's composite command line parser - | Opt(runBenchmark) // bind variable to a new option, with a hint string - ["--benchmark"] // the option names it will respond to - ("run benchmark?"); // description string for the help output + | Opt(runBenchmark) // bind variable to a new option, with a hint string + ["--benchmark"] // the option names it will respond to + ("run benchmark?"); // description string for the help output - // Now pass the new composite back to Catch so it uses that +// Now pass the new composite back to Catch so it uses that session.cli(cli); // Let Catch (using Clara) parse the command line diff --git a/modules/core/test/image-with-dataset/testColorConversion.cpp b/modules/core/test/image-with-dataset/testColorConversion.cpp index 3ee2ded944..136adae9ce 100644 --- a/modules/core/test/image-with-dataset/testColorConversion.cpp +++ b/modules/core/test/image-with-dataset/testColorConversion.cpp @@ -49,6 +49,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + static const double maxMeanPixelError = 1.5; // conversion to gray produce an error = 1.0 static const unsigned int width = 223, height = 151; diff --git a/modules/core/test/image-with-dataset/testConversion.cpp b/modules/core/test/image-with-dataset/testConversion.cpp index 053c6fab95..128dcf556d 100644 --- a/modules/core/test/image-with-dataset/testConversion.cpp +++ b/modules/core/test/image-with-dataset/testConversion.cpp @@ -50,6 +50,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! \example testConversion.cpp diff --git a/modules/core/test/image-with-dataset/testCrop.cpp b/modules/core/test/image-with-dataset/testCrop.cpp index ef420ee246..f974926635 100644 --- a/modules/core/test/image-with-dataset/testCrop.cpp +++ b/modules/core/test/image-with-dataset/testCrop.cpp @@ -43,6 +43,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! \example testCrop.cpp @@ -78,7 +82,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n\ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -204,7 +208,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; @@ -219,8 +224,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; } } @@ -229,9 +234,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; } @@ -261,7 +266,8 @@ int main(int argc, const char **argv) std::cout << "Write cropped image: " << filename << std::endl; vpImageIo::write(C, filename); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/image-with-dataset/testCropAdvanced.cpp b/modules/core/test/image-with-dataset/testCropAdvanced.cpp index 06c662b6f4..ae1593d47f 100644 --- a/modules/core/test/image-with-dataset/testCropAdvanced.cpp +++ b/modules/core/test/image-with-dataset/testCropAdvanced.cpp @@ -38,6 +38,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! \example testCropAdvanced.cpp @@ -195,7 +199,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; @@ -210,8 +215,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; } } @@ -220,9 +225,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; } @@ -401,7 +406,8 @@ int main(int argc, const char **argv) std::cout << "Test succeed" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/image-with-dataset/testGaussianFilter.cpp b/modules/core/test/image-with-dataset/testGaussianFilter.cpp index 7c2c1a66a7..8051517ad0 100644 --- a/modules/core/test/image-with-dataset/testGaussianFilter.cpp +++ b/modules/core/test/image-with-dataset/testGaussianFilter.cpp @@ -33,14 +33,14 @@ * *****************************************************************************/ -#include - /*! \example testGaussianFilter.cpp \brief Test Gaussian filter. */ +#include + #if defined(VISP_HAVE_SIMDLIB) && defined(VISP_HAVE_CATCH2) && (VISP_HAVE_DATASET_VERSION >= 0x030400) #define CATCH_CONFIG_RUNNER #include @@ -49,6 +49,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + TEST_CASE("Test vpGaussianFilter (unsigned char)") { const std::string filepath = vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "Klimt/Klimt.pgm"); diff --git a/modules/core/test/image-with-dataset/testImageAddSub.cpp b/modules/core/test/image-with-dataset/testImageAddSub.cpp index b4bb3224f2..7aacf3a18e 100644 --- a/modules/core/test/image-with-dataset/testImageAddSub.cpp +++ b/modules/core/test/image-with-dataset/testImageAddSub.cpp @@ -49,6 +49,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + TEST_CASE("Test vpImageTools::imageAdd()", "[image_add]") { const std::string filepath = vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "Klimt/Klimt.pgm"); diff --git a/modules/core/test/image-with-dataset/testImageComparison.cpp b/modules/core/test/image-with-dataset/testImageComparison.cpp index 19821c0726..35510f384d 100644 --- a/modules/core/test/image-with-dataset/testImageComparison.cpp +++ b/modules/core/test/image-with-dataset/testImageComparison.cpp @@ -46,6 +46,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + // List of allowed command line options #define GETOPTARGS "cdi:h" @@ -68,7 +72,7 @@ SYNOPSIS\n\ %s [-i ]\n\ [-h]\n \ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -170,8 +174,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; } } @@ -180,9 +184,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath); 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; exit(EXIT_FAILURE); } @@ -217,7 +221,8 @@ int main(int argc, const char **argv) // Modify I_Klimt1 if (I_Klimt1[I_Klimt1.getHeight() / 2][I_Klimt1.getWidth() / 2] < 255) { I_Klimt1[I_Klimt1.getHeight() / 2][I_Klimt1.getWidth() / 2]++; - } else { + } + else { I_Klimt1[I_Klimt1.getHeight() / 2][I_Klimt1.getWidth() / 2]--; } @@ -262,7 +267,8 @@ int main(int argc, const char **argv) // Modify I_color_Klimt2 if (I_color_Klimt2[I_color_Klimt2.getHeight() / 2][I_color_Klimt2.getWidth() / 2].R < 255) { I_color_Klimt2[I_color_Klimt2.getHeight() / 2][I_color_Klimt2.getWidth() / 2].R++; - } else { + } + else { I_color_Klimt2[I_color_Klimt2.getHeight() / 2][I_color_Klimt2.getWidth() / 2].R--; } @@ -280,7 +286,8 @@ int main(int argc, const char **argv) throw vpException(vpException::fatalError, ss.str()); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "\nCatch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/image-with-dataset/testImageFilter.cpp b/modules/core/test/image-with-dataset/testImageFilter.cpp index d05719987c..07e5978d85 100644 --- a/modules/core/test/image-with-dataset/testImageFilter.cpp +++ b/modules/core/test/image-with-dataset/testImageFilter.cpp @@ -49,6 +49,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:p:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { /* diff --git a/modules/core/test/image-with-dataset/testImageNormalizedCorrelation.cpp b/modules/core/test/image-with-dataset/testImageNormalizedCorrelation.cpp index 6819c9bde6..b54c03c308 100644 --- a/modules/core/test/image-with-dataset/testImageNormalizedCorrelation.cpp +++ b/modules/core/test/image-with-dataset/testImageNormalizedCorrelation.cpp @@ -50,6 +50,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void usage(const char *name, const char *badparam, std::string ipath) @@ -174,8 +178,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; } } @@ -184,9 +188,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath); 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; exit(EXIT_FAILURE); } @@ -218,7 +222,7 @@ int main(int argc, const char **argv) for (unsigned int j = 0; j < I_score.getWidth(); j++) { if (!vpMath::equal(I_score[i][j], I_score_gold[i][j], 1e-9)) { std::cerr << "Issue with normalizedCorrelation, gold: " << std::setprecision(17) << I_score_gold[i][j] - << " ; compute: " << I_score[i][j] << std::endl; + << " ; compute: " << I_score[i][j] << std::endl; return EXIT_FAILURE; } } @@ -240,7 +244,8 @@ int main(int argc, const char **argv) return EXIT_FAILURE; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "\nCatch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/image-with-dataset/testImageTemplateMatching.cpp b/modules/core/test/image-with-dataset/testImageTemplateMatching.cpp index e3f589c703..16bdc269de 100644 --- a/modules/core/test/image-with-dataset/testImageTemplateMatching.cpp +++ b/modules/core/test/image-with-dataset/testImageTemplateMatching.cpp @@ -50,6 +50,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:th" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void usage(const char *name, const char *badparam, std::string ipath) @@ -182,13 +186,13 @@ int main(int argc, const char **argv) for (int j = 0; j < w; j++) { if (!vpMath::equal(II[i][j], sum.at(i, j), std::numeric_limits::epsilon())) { std::cerr << "Error vpImageTools::integralImage(II), reference: " << std::setprecision(17) - << sum.at(i, j) << " ; compute: " << II[i][j] << std::endl; + << sum.at(i, j) << " ; compute: " << II[i][j] << std::endl; return EXIT_FAILURE; } if (!vpMath::equal(IIsq[i][j], sqsum.at(i, j), std::numeric_limits::epsilon())) { std::cerr << "Error vpImageTools::integralImage(IIsq), reference: " << std::setprecision(17) - << sqsum.at(i, j) << " ; compute: " << IIsq[i][j] << std::endl; + << sqsum.at(i, j) << " ; compute: " << IIsq[i][j] << std::endl; return EXIT_FAILURE; } } @@ -196,178 +200,180 @@ int main(int argc, const char **argv) } #endif - try { - std::string env_ipath; - std::string opt_ipath; - std::string ipath; - std::string filename; - bool click = false; - bool doTemplateMatching = false; +try { + std::string env_ipath; + std::string opt_ipath; + std::string ipath; + std::string filename; + bool click = false; + bool doTemplateMatching = false; #if VISP_HAVE_DATASET_VERSION >= 0x030600 - std::string ext("png"); + std::string ext("png"); #else - std::string ext("pgm"); + std::string ext("pgm"); #endif // Get the visp-images-data package path or VISP_INPUT_IMAGE_PATH // environment variable value - env_ipath = vpIoTools::getViSPImagesDataPath(); + env_ipath = vpIoTools::getViSPImagesDataPath(); - // Set the default input path - if (!env_ipath.empty()) { - ipath = env_ipath; - } + // Set the default input path + if (!env_ipath.empty()) { + ipath = env_ipath; + } - // Read the command line options - if (!getOptions(argc, argv, opt_ipath, click, doTemplateMatching)) { - exit(EXIT_FAILURE); - } + // Read the command line options + if (!getOptions(argc, argv, opt_ipath, click, doTemplateMatching)) { + exit(EXIT_FAILURE); + } - // Get the option values - if (!opt_ipath.empty()) { - ipath = opt_ipath; - } + // Get the option values + if (!opt_ipath.empty()) { + ipath = opt_ipath; + } - // Compare ipath and env_ipath. If they differ, we take into account - // the input path coming from the command line option - if (!opt_ipath.empty() && !env_ipath.empty()) { - 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; - } + // Compare ipath and env_ipath. If they differ, we take into account + // the input path coming from the command line option + if (!opt_ipath.empty() && !env_ipath.empty()) { + 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; } + } - // Test if an input path is set - if (opt_ipath.empty() && env_ipath.empty()) { - usage(argv[0], nullptr, ipath); - 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; - exit(EXIT_FAILURE); - } + // Test if an input path is set + if (opt_ipath.empty() && env_ipath.empty()) { + usage(argv[0], nullptr, ipath); + 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; + exit(EXIT_FAILURE); + } - // - // Here starts really the test - // + // + // Here starts really the test + // - // Load cube sequence - filename = vpIoTools::createFilePath(ipath, "mbt/cube/image%04d." + ext); + // Load cube sequence + filename = vpIoTools::createFilePath(ipath, "mbt/cube/image%04d." + ext); - vpVideoReader reader; - reader.setFileName(filename); - vpImage I, I_template; - reader.open(I); - vpRect template_roi(vpImagePoint(201, 310), vpImagePoint(201 + 152 - 1, 310 + 138 - 1)); - vpImageTools::crop(I, template_roi, I_template); + vpVideoReader reader; + reader.setFileName(filename); + vpImage I, I_template; + reader.open(I); + vpRect template_roi(vpImagePoint(201, 310), vpImagePoint(201 + 152 - 1, 310 + 138 - 1)); + vpImageTools::crop(I, template_roi, I_template); - if (doTemplateMatching) { + if (doTemplateMatching) { #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV) #if defined(VISP_HAVE_X11) - vpDisplayX d; + vpDisplayX d; #elif defined(VISP_HAVE_GDI) - vpDisplayGDI d; + vpDisplayGDI d; #elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV d; + vpDisplayOpenCV d; #endif - d.init(I, 0, 0, "Image"); + d.init(I, 0, 0, "Image"); - vpImage I_score; - std::vector benchmark_vec; - bool quit = false; - while (!reader.end() && !quit) { - reader.acquire(I); + vpImage I_score; + std::vector benchmark_vec; + bool quit = false; + while (!reader.end() && !quit) { + reader.acquire(I); - vpDisplay::display(I); + vpDisplay::display(I); - std::stringstream ss; - ss << "Frame: " << reader.getFrameIndex(); - vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red); + std::stringstream ss; + ss << "Frame: " << reader.getFrameIndex(); + vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red); - // Basic template matching - double t_proc = vpTime::measureTimeMs(); - const unsigned int step_u = 5, step_v = 5; - vpImageTools::templateMatching(I, I_template, I_score, step_u, step_v); + // Basic template matching + double t_proc = vpTime::measureTimeMs(); + const unsigned int step_u = 5, step_v = 5; + vpImageTools::templateMatching(I, I_template, I_score, step_u, step_v); - vpImagePoint max_loc; - double max_correlation = -1.0; - I_score.getMinMaxLoc(nullptr, &max_loc, nullptr, &max_correlation); - t_proc = vpTime::measureTimeMs() - t_proc; - benchmark_vec.push_back(t_proc); + vpImagePoint max_loc; + double max_correlation = -1.0; + I_score.getMinMaxLoc(nullptr, &max_loc, nullptr, &max_correlation); + t_proc = vpTime::measureTimeMs() - t_proc; + benchmark_vec.push_back(t_proc); - ss.str(""); - ss << "Template matching: " << t_proc << " ms"; - vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red); + ss.str(""); + ss << "Template matching: " << t_proc << " ms"; + vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red); - ss.str(""); - ss << "Max correlation: " << max_correlation; - vpDisplay::displayText(I, 60, 20, ss.str(), vpColor::red); + ss.str(""); + ss << "Max correlation: " << max_correlation; + vpDisplay::displayText(I, 60, 20, ss.str(), vpColor::red); - vpDisplay::displayRectangle(I, max_loc, I_template.getWidth(), I_template.getHeight(), vpColor::red, false, 1); + vpDisplay::displayRectangle(I, max_loc, I_template.getWidth(), I_template.getHeight(), vpColor::red, false, 1); - vpDisplay::flush(I); + vpDisplay::flush(I); - vpMouseButton::vpMouseButtonType button; - if (vpDisplay::getClick(I, button, click)) { - switch (button) { - case vpMouseButton::button1: - quit = !click; - break; + vpMouseButton::vpMouseButtonType button; + if (vpDisplay::getClick(I, button, click)) { + switch (button) { + case vpMouseButton::button1: + quit = !click; + break; - case vpMouseButton::button3: - click = !click; - break; + case vpMouseButton::button3: + click = !click; + break; - default: - break; - } + default: + break; } } + } - if (!benchmark_vec.empty()) { - std::cout << "Processing time, Mean: " << vpMath::getMean(benchmark_vec) - << " ms ; Median: " << vpMath::getMedian(benchmark_vec) - << " ms ; Std: " << vpMath::getStdev(benchmark_vec) << " ms" << std::endl; - } + if (!benchmark_vec.empty()) { + std::cout << "Processing time, Mean: " << vpMath::getMean(benchmark_vec) + << " ms ; Median: " << vpMath::getMedian(benchmark_vec) + << " ms ; Std: " << vpMath::getStdev(benchmark_vec) << " ms" << std::endl; + } #endif - } else { - // ctest case - // Basic template matching - const unsigned int step_u = 5, step_v = 5; - vpImage I_score, I_score_gold; - - double t = vpTime::measureTimeMs(); - vpImageTools::templateMatching(I, I_template, I_score, step_u, step_v, true); - t = vpTime::measureTimeMs() - t; - - double t_gold = vpTime::measureTimeMs(); - vpImageTools::templateMatching(I, I_template, I_score_gold, step_u, step_v, false); - t_gold = vpTime::measureTimeMs() - t_gold; - - std::cout << "Template matching: " << t << " ms" << std::endl; - std::cout << "Template matching (gold): " << t_gold << " ms" << std::endl; - - for (unsigned int i = 0; i < I_score.getHeight(); i++) { - for (unsigned int j = 0; j < I_score.getWidth(); j++) { - if (!vpMath::equal(I_score[i][j], I_score_gold[i][j], 1e-9)) { - std::cerr << "Issue with template matching, gold: " << std::setprecision(17) << I_score_gold[i][j] - << " ; compute: " << I_score[i][j] << std::endl; - return EXIT_FAILURE; - } + } + else { + // ctest case + // Basic template matching + const unsigned int step_u = 5, step_v = 5; + vpImage I_score, I_score_gold; + + double t = vpTime::measureTimeMs(); + vpImageTools::templateMatching(I, I_template, I_score, step_u, step_v, true); + t = vpTime::measureTimeMs() - t; + + double t_gold = vpTime::measureTimeMs(); + vpImageTools::templateMatching(I, I_template, I_score_gold, step_u, step_v, false); + t_gold = vpTime::measureTimeMs() - t_gold; + + std::cout << "Template matching: " << t << " ms" << std::endl; + std::cout << "Template matching (gold): " << t_gold << " ms" << std::endl; + + for (unsigned int i = 0; i < I_score.getHeight(); i++) { + for (unsigned int j = 0; j < I_score.getWidth(); j++) { + if (!vpMath::equal(I_score[i][j], I_score_gold[i][j], 1e-9)) { + std::cerr << "Issue with template matching, gold: " << std::setprecision(17) << I_score_gold[i][j] + << " ; compute: " << I_score[i][j] << std::endl; + return EXIT_FAILURE; } } } - - } catch (const vpException &e) { - std::cerr << "\nCatch an exception: " << e << std::endl; - return EXIT_FAILURE; } - return EXIT_SUCCESS; +} +catch (const vpException &e) { + std::cerr << "\nCatch an exception: " << e << std::endl; + return EXIT_FAILURE; +} + +return EXIT_SUCCESS; } diff --git a/modules/core/test/image-with-dataset/testImageWarp.cpp b/modules/core/test/image-with-dataset/testImageWarp.cpp index 3bebc67edb..136a922014 100644 --- a/modules/core/test/image-with-dataset/testImageWarp.cpp +++ b/modules/core/test/image-with-dataset/testImageWarp.cpp @@ -50,6 +50,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { static const double g_threshold_value = 0.5; diff --git a/modules/core/test/image-with-dataset/testIoEXR.cpp b/modules/core/test/image-with-dataset/testIoEXR.cpp index 88d0001736..8474ca7597 100644 --- a/modules/core/test/image-with-dataset/testIoEXR.cpp +++ b/modules/core/test/image-with-dataset/testIoEXR.cpp @@ -53,6 +53,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { #ifdef VISP_LITTLE_ENDIAN diff --git a/modules/core/test/image-with-dataset/testIoPFM.cpp b/modules/core/test/image-with-dataset/testIoPFM.cpp index 4d724ff6d3..5dfb0d9e52 100644 --- a/modules/core/test/image-with-dataset/testIoPFM.cpp +++ b/modules/core/test/image-with-dataset/testIoPFM.cpp @@ -50,6 +50,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void checkColorImages(const vpImage &I1, const vpImage &I2) @@ -80,7 +84,7 @@ TEST_CASE("HDR PFM image read", "[hdr_pfm_image_io]") SECTION("Color") { const std::string imgPath = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_LSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_LSB.pfm"); REQUIRE(vpIoTools::checkFilename(imgPath)); vpImage I; @@ -90,7 +94,7 @@ TEST_CASE("HDR PFM image read", "[hdr_pfm_image_io]") SECTION("Gray") { const std::string imgPath = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_LSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_LSB.pfm"); REQUIRE(vpIoTools::checkFilename(imgPath)); vpImage I; @@ -104,7 +108,7 @@ TEST_CASE("HDR PFM image read", "[hdr_pfm_image_io]") SECTION("Color") { const std::string imgPath = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_MSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_MSB.pfm"); REQUIRE(vpIoTools::checkFilename(imgPath)); vpImage I; @@ -114,7 +118,7 @@ TEST_CASE("HDR PFM image read", "[hdr_pfm_image_io]") SECTION("Gray") { const std::string imgPath = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_MSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_MSB.pfm"); REQUIRE(vpIoTools::checkFilename(imgPath)); vpImage I; @@ -128,9 +132,9 @@ TEST_CASE("HDR PFM image read", "[hdr_pfm_image_io]") SECTION("Color") { const std::string imgPathLSB = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_LSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_LSB.pfm"); const std::string imgPathMSB = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_MSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_MSB.pfm"); REQUIRE(vpIoTools::checkFilename(imgPathLSB)); REQUIRE(vpIoTools::checkFilename(imgPathMSB)); @@ -150,9 +154,9 @@ TEST_CASE("HDR PFM image read", "[hdr_pfm_image_io]") SECTION("Gray") { const std::string imgPathLSB = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_LSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_LSB.pfm"); const std::string imgPathMSB = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_MSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_MSB.pfm"); REQUIRE(vpIoTools::checkFilename(imgPathLSB)); REQUIRE(vpIoTools::checkFilename(imgPathMSB)); @@ -182,7 +186,7 @@ TEST_CASE("HDR PFM image write", "[hdr_pfm_image_io]") SECTION("Color") { const std::string imgPath = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_LSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_color_LSB.pfm"); REQUIRE(vpIoTools::checkFilename(imgPath)); vpImage I; @@ -201,7 +205,7 @@ TEST_CASE("HDR PFM image write", "[hdr_pfm_image_io]") SECTION("Gray") { const std::string imgPath = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_LSB.pfm"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "memorial/memorial_gray_LSB.pfm"); REQUIRE(vpIoTools::checkFilename(imgPath)); vpImage I; diff --git a/modules/core/test/image-with-dataset/testIoPGM.cpp b/modules/core/test/image-with-dataset/testIoPGM.cpp index 2c5d507367..b5ffe32f66 100644 --- a/modules/core/test/image-with-dataset/testIoPGM.cpp +++ b/modules/core/test/image-with-dataset/testIoPGM.cpp @@ -51,6 +51,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /* Print the program options. @@ -72,7 +76,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n\ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -198,7 +202,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; @@ -213,8 +218,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; } } @@ -223,9 +228,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; } @@ -251,7 +256,8 @@ int main(int argc, const char **argv) filename = vpIoTools::createFilePath(ipath, "image-that-does-not-exist.pgm"); std::cout << "Read image: " << filename << std::endl; vpImageIo::read(I, filename); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception due to a non existing file: " << e << std::endl; } @@ -260,11 +266,13 @@ int main(int argc, const char **argv) filename = vpIoTools::createFilePath(opath, "directory-that-does-not-exist/Klimt.pgm"); std::cout << "Write image: " << filename << std::endl; vpImageIo::write(I, filename); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception due to a non existing file: " << e << std::endl; } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/image-with-dataset/testIoPPM.cpp b/modules/core/test/image-with-dataset/testIoPPM.cpp index 5319ce63ac..783de2289f 100644 --- a/modules/core/test/image-with-dataset/testIoPPM.cpp +++ b/modules/core/test/image-with-dataset/testIoPPM.cpp @@ -52,6 +52,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /* Print the program options. @@ -73,7 +77,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n\ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -200,7 +204,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; @@ -215,8 +220,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; } } @@ -225,9 +230,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; } @@ -254,7 +259,8 @@ int main(int argc, const char **argv) filename = vpIoTools::createFilePath(ipath, "image-that-does-not-exist.ppm"); std::cout << "Read image: " << filename << std::endl; vpImageIo::read(I, filename); - } catch (vpImageException &e) { + } + catch (vpImageException &e) { vpERROR_TRACE("at main level"); std::cout << e << std::endl; } @@ -264,7 +270,8 @@ int main(int argc, const char **argv) filename = vpIoTools::createFilePath(opath, "directory-that-does-not-exist/Klimt.ppm"); std::cout << "Write image: " << filename << std::endl; vpImageIo::write(I, filename); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception due to a non existing file: " << e << std::endl; } @@ -287,7 +294,8 @@ int main(int argc, const char **argv) filename = vpIoTools::createFilePath(ipath, "image-that-does-not-exist.ppm"); std::cout << "Read image: " << filename << std::endl; vpImageIo::read(Irgba, filename); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception due to a non existing file: " << e << std::endl; } @@ -296,11 +304,13 @@ int main(int argc, const char **argv) filename = vpIoTools::createFilePath(opath, "directory-that-does-not-exist/Klimt.ppm"); std::cout << "Write image: " << filename << std::endl; vpImageIo::write(Irgba, filename); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception due to a non existing file: " << e << std::endl; } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/image-with-dataset/testPerformanceLUT.cpp b/modules/core/test/image-with-dataset/testPerformanceLUT.cpp index 9d8f95db45..8cbdf167ed 100644 --- a/modules/core/test/image-with-dataset/testPerformanceLUT.cpp +++ b/modules/core/test/image-with-dataset/testPerformanceLUT.cpp @@ -39,6 +39,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! * \example testPerformanceLUT.cpp * diff --git a/modules/core/test/image-with-dataset/testReadImage.cpp b/modules/core/test/image-with-dataset/testReadImage.cpp index 7d63c4faa4..05e2a23c14 100644 --- a/modules/core/test/image-with-dataset/testReadImage.cpp +++ b/modules/core/test/image-with-dataset/testReadImage.cpp @@ -48,6 +48,10 @@ */ +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + // List of allowed command line options #define GETOPTARGS "cdi:p:h" @@ -72,7 +76,7 @@ SYNOPSIS\n\ %s [-i ] [-p ]\n\ [-h]\n\ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -179,8 +183,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; } } @@ -220,12 +224,14 @@ int main(int argc, const char **argv) filename = vpIoTools::createFilePath(ipath, "Klimt/Klimt.png"); vpImageIo::read(Irgb, filename); printf("Read png ok\n"); - } else { + } + else { filename = opt_ppath; vpImageIo::read(I, filename); printf("Image \"%s\" read successfully\n", filename.c_str()); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/image-with-dataset/testUndistortImage.cpp b/modules/core/test/image-with-dataset/testUndistortImage.cpp index 3f871a0983..0eb164b3b1 100644 --- a/modules/core/test/image-with-dataset/testUndistortImage.cpp +++ b/modules/core/test/image-with-dataset/testUndistortImage.cpp @@ -53,6 +53,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:o:t:s:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /* Print the program options. diff --git a/modules/core/test/image/common.hpp b/modules/core/test/image/common.hpp index 5d1f424fe6..4ae826cf2e 100644 --- a/modules/core/test/image/common.hpp +++ b/modules/core/test/image/common.hpp @@ -46,6 +46,9 @@ namespace common_tools { +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif static const int g_nearest_neighbor = 0; static const int g_bilinear = 1; diff --git a/modules/core/test/image/testImageBinarise.cpp b/modules/core/test/image/testImageBinarise.cpp index e828aff8d9..3dbcdba534 100644 --- a/modules/core/test/image/testImageBinarise.cpp +++ b/modules/core/test/image/testImageBinarise.cpp @@ -46,6 +46,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::cout << "Test vpImageTools::binarise() with different data types." << std::endl; unsigned int width = 5, height = 4; @@ -82,8 +85,8 @@ int main() for (unsigned int i = 0; i < I_rgba.getHeight(); i++) { for (unsigned int j = 0; j < I_rgba.getWidth(); j++) { std::cout << static_cast(I_rgba[i][j].R) << " ; " << static_cast(I_rgba[i][j].G) << " ; " - << static_cast(I_rgba[i][j].B) << " ; " << static_cast(I_rgba[i][j].A) - << std::endl; + << static_cast(I_rgba[i][j].B) << " ; " << static_cast(I_rgba[i][j].A) + << std::endl; } std::cout << std::endl; } @@ -113,7 +116,7 @@ int main() for (unsigned int i = 0; i < I_rgba.getHeight(); i++) { for (unsigned int j = 0; j < I_rgba.getWidth(); j++) { std::cout << static_cast(I_rgba[i][j].R) << " ; " << static_cast(I_rgba[i][j].G) << " ; " - << static_cast(I_rgba[i][j].B) << " ; " << static_cast(I_rgba[i][j].A) << std::endl; + << static_cast(I_rgba[i][j].B) << " ; " << static_cast(I_rgba[i][j].A) << std::endl; } std::cout << std::endl; } diff --git a/modules/core/test/image/testImageDifference.cpp b/modules/core/test/image/testImageDifference.cpp index e3b773f7bc..71450593e4 100644 --- a/modules/core/test/image/testImageDifference.cpp +++ b/modules/core/test/image/testImageDifference.cpp @@ -44,6 +44,10 @@ \brief Test vpImageTools::imageDifference() */ +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void regularImageDifference(const vpImage &I1, const vpImage &I2, @@ -94,7 +98,7 @@ int main() unsigned int width = 501, height = 447; vpImage I1(height, width), I2(height, width), Idiff_regular(height, width), Idiff_sse(height, width); vpImage I1_color(height, width), I2_color(height, width), Idiff_regular_color(height, width), - Idiff_sse_color(height, width); + Idiff_sse_color(height, width); for (unsigned int i = 0; i < I1.getRows(); i++) { for (unsigned int j = 0; j < I1.getCols(); j++) { I1[i][j] = static_cast(i * I1.getCols() + j); @@ -212,7 +216,7 @@ int main() } } - { + { std::cout << "Test vpRGBf" << std::endl; vpRGBf rgbf_1(10.f, 20.f, 30.f); vpRGBf rgbf_2(10.f, 20.f, 30.f); diff --git a/modules/core/test/image/testImageDraw.cpp b/modules/core/test/image/testImageDraw.cpp index 08026571bf..25aee19d53 100644 --- a/modules/core/test/image/testImageDraw.cpp +++ b/modules/core/test/image/testImageDraw.cpp @@ -45,6 +45,9 @@ int main(int argc, char *argv[]) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif bool save = false; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--save") { diff --git a/modules/core/test/image/testImageGetValue.cpp b/modules/core/test/image/testImageGetValue.cpp index 577d24e59a..fe20646340 100644 --- a/modules/core/test/image/testImageGetValue.cpp +++ b/modules/core/test/image/testImageGetValue.cpp @@ -41,6 +41,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { template PixelType checkPixelAccess(unsigned int height, unsigned int width, double v, double u) diff --git a/modules/core/test/image/testImageMeanAndStdev.cpp b/modules/core/test/image/testImageMeanAndStdev.cpp index 71b0904c3b..c5280e7b81 100644 --- a/modules/core/test/image/testImageMeanAndStdev.cpp +++ b/modules/core/test/image/testImageMeanAndStdev.cpp @@ -56,6 +56,9 @@ void printHelp(const std::string &progName) int main(const int argc, const char *argv[]) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif bool opt_verbose = false; for (int i = 1; i < argc; ++i) { std::string argName(argv[i]); diff --git a/modules/core/test/image/testImageMorphology.cpp b/modules/core/test/image/testImageMorphology.cpp index 8e051b8330..2125ffbfaa 100644 --- a/modules/core/test/image/testImageMorphology.cpp +++ b/modules/core/test/image/testImageMorphology.cpp @@ -48,6 +48,9 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif TEST_CASE("Binary image morphology", "[image_morphology]") { unsigned char image_data[8 * 16] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, diff --git a/modules/core/test/image/testImageOwnership.cpp b/modules/core/test/image/testImageOwnership.cpp index 9c3a1770b4..72af85a704 100644 --- a/modules/core/test/image/testImageOwnership.cpp +++ b/modules/core/test/image/testImageOwnership.cpp @@ -43,6 +43,9 @@ int main(int /* argc */, const char ** /* argv */) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { { unsigned char bitmap[4]; diff --git a/modules/core/test/image/testImagePoint.cpp b/modules/core/test/image/testImagePoint.cpp index 9a03c4a236..c226befd43 100644 --- a/modules/core/test/image/testImagePoint.cpp +++ b/modules/core/test/image/testImagePoint.cpp @@ -48,6 +48,9 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif TEST_CASE("Test comparison operator", "[operator]") { vpImagePoint ip1, ip2, ip3; @@ -152,7 +155,8 @@ int main() if (ip1 == ip2) { std::cout << "ip1 == ip2" << std::endl; - } else { + } + else { std::cout << "ip1 != ip2 (bad result)" << std::endl; return EXIT_FAILURE; } @@ -160,20 +164,23 @@ int main() if (ip1 != ip2) { std::cout << "ip1 != ip2 (bad result)" << std::endl; return EXIT_FAILURE; - } else { + } + else { std::cout << "ip1 == ip2" << std::endl; } if (ip1 == ip3) { std::cout << "ip1 == ip3 (bad result)" << std::endl; return EXIT_FAILURE; - } else { + } + else { std::cout << "ip1 != ip3" << std::endl; } if (ip1 != ip3) { std::cout << "ip1 != ip3" << std::endl; - } else { + } + else { std::cout << "ip1 == ip3 (bad result)" << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/image/testImagePrint.cpp b/modules/core/test/image/testImagePrint.cpp index 91dbcbbfc7..9144ae019a 100644 --- a/modules/core/test/image/testImagePrint.cpp +++ b/modules/core/test/image/testImagePrint.cpp @@ -43,6 +43,9 @@ */ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif unsigned int size = 16; vpImage I_int(size, size); vpImage I_uchar(size, size); diff --git a/modules/core/test/image/testImageResize.cpp b/modules/core/test/image/testImageResize.cpp index 1d5bc6961d..6e77322767 100644 --- a/modules/core/test/image/testImageResize.cpp +++ b/modules/core/test/image/testImageResize.cpp @@ -52,6 +52,9 @@ static unsigned int g_input_height = 5; static unsigned int g_output_width = 4; static unsigned int g_output_height = 3; +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif TEST_CASE("Nearest neighbor interpolation", "[image_resize]") { SECTION("unsigned char") @@ -136,20 +139,20 @@ int main(int argc, char *argv[]) // Build a new parser on top of Catch's using namespace Catch::clara; auto cli = session.cli() // Get Catch's composite command line parser - | Opt(g_input_width, "g_input_width") // bind variable to a new option, with a hint string - ["--iw"] // the option names it will respond to - ("Input image width.") // description string for the help output - | Opt(g_input_height, "g_input_height") // bind variable to a new option, with a hint string - ["--ih"] // the option names it will respond to - ("Input image height.") | - Opt(g_output_width, "g_output_width") // bind variable to a new option, with a hint string - ["--ow"] // the option names it will respond to - ("Output image width.") | - Opt(g_output_height, "g_output_height") // bind variable to a new option, with a hint string - ["--oh"] // the option names it will respond to - ("Output image height."); - - // Now pass the new composite back to Catch so it uses that + | Opt(g_input_width, "g_input_width") // bind variable to a new option, with a hint string + ["--iw"] // the option names it will respond to + ("Input image width.") // description string for the help output + | Opt(g_input_height, "g_input_height") // bind variable to a new option, with a hint string + ["--ih"] // the option names it will respond to + ("Input image height.") | + Opt(g_output_width, "g_output_width") // bind variable to a new option, with a hint string + ["--ow"] // the option names it will respond to + ("Output image width.") | + Opt(g_output_height, "g_output_height") // bind variable to a new option, with a hint string + ["--oh"] // the option names it will respond to + ("Output image height."); + +// Now pass the new composite back to Catch so it uses that session.cli(cli); // Let Catch (using Clara) parse the command line diff --git a/modules/core/test/math/perfColVectorOperations.cpp b/modules/core/test/math/perfColVectorOperations.cpp index c67a0790ec..344f739c0e 100644 --- a/modules/core/test/math/perfColVectorOperations.cpp +++ b/modules/core/test/math/perfColVectorOperations.cpp @@ -42,6 +42,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { static bool g_runBenchmark = false; diff --git a/modules/core/test/math/perfMatrixMultiplication.cpp b/modules/core/test/math/perfMatrixMultiplication.cpp index 0f12b36ec9..0e200134c6 100644 --- a/modules/core/test/math/perfMatrixMultiplication.cpp +++ b/modules/core/test/math/perfMatrixMultiplication.cpp @@ -50,6 +50,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { @@ -214,8 +218,8 @@ bool equalMatrix(const vpMatrix &A, const vpMatrix &B, double tol = 1e-9) TEST_CASE("Benchmark matrix-matrix multiplication", "[benchmark]") { if (runBenchmark || runBenchmarkAll) { - std::vector > sizes = {{3, 3}, {6, 6}, {8, 8}, {10, 10}, {20, 20}, {6, 200}, - {200, 6}, {207, 119}, {83, 201}, {600, 400}, {400, 600}}; + std::vector > sizes = { {3, 3}, {6, 6}, {8, 8}, {10, 10}, {20, 20}, {6, 200}, + {200, 6}, {207, 119}, {83, 201}, {600, 400}, {400, 600} }; for (auto sz : sizes) { vpMatrix A = generateRandomMatrix(sz.first, sz.second); @@ -273,7 +277,7 @@ TEST_CASE("Benchmark matrix-matrix multiplication", "[benchmark]") oss.str(""); oss << "(" << eigenA.rows() << "x" << eigenA.cols() << ")x(" << eigenB.rows() << "x" << eigenB.cols() - << ") - Eigen"; + << ") - Eigen"; BENCHMARK(oss.str().c_str()) { Eigen::MatrixXd eigenC = eigenA * eigenB; @@ -298,7 +302,7 @@ TEST_CASE("Benchmark matrix-matrix multiplication", "[benchmark]") TEST_CASE("Benchmark matrix-rotation matrix multiplication", "[benchmark]") { if (runBenchmark || runBenchmarkAll) { - std::vector > sizes = {{3, 3}}; + std::vector > sizes = { {3, 3} }; for (auto sz : sizes) { vpMatrix A = generateRandomMatrix(sz.first, sz.second); @@ -365,7 +369,7 @@ TEST_CASE("Benchmark matrix-rotation matrix multiplication", "[benchmark]") oss.str(""); oss << "(" << eigenA.rows() << "x" << eigenA.cols() << ")x(" << eigenB.rows() << "x" << eigenB.cols() - << ") - Eigen"; + << ") - Eigen"; BENCHMARK(oss.str().c_str()) { Eigen::MatrixXd eigenC = eigenA * eigenB; @@ -391,7 +395,7 @@ TEST_CASE("Benchmark matrix-rotation matrix multiplication", "[benchmark]") TEST_CASE("Benchmark matrix-homogeneous matrix multiplication", "[benchmark]") { if (runBenchmark || runBenchmarkAll) { - std::vector > sizes = {{4, 4}}; + std::vector > sizes = { {4, 4} }; for (auto sz : sizes) { vpMatrix A = generateRandomMatrix(sz.first, sz.second); @@ -459,7 +463,7 @@ TEST_CASE("Benchmark matrix-homogeneous matrix multiplication", "[benchmark]") oss.str(""); oss << "(" << eigenA.rows() << "x" << eigenA.cols() << ")x(" << eigenB.rows() << "x" << eigenB.cols() - << ") - Eigen"; + << ") - Eigen"; BENCHMARK(oss.str().c_str()) { Eigen::MatrixXd eigenC = eigenA * eigenB; @@ -487,8 +491,8 @@ TEST_CASE("Benchmark matrix-homogeneous matrix multiplication", "[benchmark]") TEST_CASE("Benchmark matrix-vector multiplication", "[benchmark]") { if (runBenchmark || runBenchmarkAll) { - std::vector > sizes = {{3, 3}, {6, 6}, {8, 8}, {10, 10}, {20, 20}, {6, 200}, - {200, 6}, {207, 119}, {83, 201}, {600, 400}, {400, 600}}; + std::vector > sizes = { {3, 3}, {6, 6}, {8, 8}, {10, 10}, {20, 20}, {6, 200}, + {200, 6}, {207, 119}, {83, 201}, {600, 400}, {400, 600} }; for (auto sz : sizes) { vpMatrix A = generateRandomMatrix(sz.first, sz.second); @@ -550,7 +554,7 @@ TEST_CASE("Benchmark matrix-vector multiplication", "[benchmark]") oss.str(""); oss << "(" << eigenA.rows() << "x" << eigenA.cols() << ")x(" << eigenB.rows() << "x" << eigenB.cols() - << ") - Eigen"; + << ") - Eigen"; BENCHMARK(oss.str().c_str()) { Eigen::MatrixXd eigenC = eigenA * eigenB; @@ -575,8 +579,8 @@ TEST_CASE("Benchmark matrix-vector multiplication", "[benchmark]") TEST_CASE("Benchmark AtA", "[benchmark]") { if (runBenchmark || runBenchmarkAll) { - std::vector > sizes = {{3, 3}, {6, 6}, {8, 8}, {10, 10}, {20, 20}, {6, 200}, - {200, 6}, {207, 119}, {83, 201}, {600, 400}, {400, 600}}; + std::vector > sizes = { {3, 3}, {6, 6}, {8, 8}, {10, 10}, {20, 20}, {6, 200}, + {200, 6}, {207, 119}, {83, 201}, {600, 400}, {400, 600} }; for (auto sz : sizes) { vpMatrix A = generateRandomMatrix(sz.first, sz.second); @@ -654,7 +658,7 @@ TEST_CASE("Benchmark AAt", "[benchmark]") if (runBenchmark || runBenchmarkAll) { std::vector > sizes = { {3, 3}, {6, 6}, {8, 8}, {10, 10}, - {20, 20}, {6, 200}, {200, 6}}; //, {207, 119}, {83, 201}, {600, 400}, {400, 600} }; + {20, 20}, {6, 200}, {200, 6} }; //, {207, 119}, {83, 201}, {600, 400}, {400, 600} }; for (auto sz : sizes) { vpMatrix A = generateRandomMatrix(sz.first, sz.second); @@ -730,7 +734,7 @@ TEST_CASE("Benchmark AAt", "[benchmark]") TEST_CASE("Benchmark matrix-velocity twist multiplication", "[benchmark]") { if (runBenchmark || runBenchmarkAll) { - std::vector > sizes = {{6, 6}, {20, 6}, {207, 6}, {600, 6}, {1201, 6}}; + std::vector > sizes = { {6, 6}, {20, 6}, {207, 6}, {600, 6}, {1201, 6} }; for (auto sz : sizes) { vpMatrix A = generateRandomMatrix(sz.first, sz.second); @@ -820,7 +824,7 @@ TEST_CASE("Benchmark matrix-velocity twist multiplication", "[benchmark]") TEST_CASE("Benchmark matrix-force twist multiplication", "[benchmark]") { if (runBenchmark || runBenchmarkAll) { - std::vector > sizes = {{6, 6}, {20, 6}, {207, 6}, {600, 6}, {1201, 6}}; + std::vector > sizes = { {6, 6}, {20, 6}, {207, 6}, {600, 6}, {1201, 6} }; for (auto sz : sizes) { vpMatrix A = generateRandomMatrix(sz.first, sz.second); @@ -921,18 +925,18 @@ int main(int argc, char *argv[]) // Build a new parser on top of Catch's using namespace Catch::clara; auto cli = session.cli() // Get Catch's composite command line parser - | Opt(runBenchmark) // bind variable to a new option, with a hint string - ["--benchmark"] // the option names it will respond to - ("run benchmark comparing naive code with ViSP implementation") // description string for the help output - | Opt(runBenchmarkAll) // bind variable to a new option, with a hint string - ["--benchmark-all"] // the option names it will respond to - ("run benchmark comparing naive code with ViSP, OpenCV, Eigen implementation") // description string for - // the help output - | Opt(lapackMinSize, "min size") // bind variable to a new option, with a hint string - ["--lapack-min-size"] // the option names it will respond to - ("matrix/vector min size to enable blas/lapack usage"); // description string for the help output - - // Now pass the new composite back to Catch so it uses that + | Opt(runBenchmark) // bind variable to a new option, with a hint string + ["--benchmark"] // the option names it will respond to + ("run benchmark comparing naive code with ViSP implementation") // description string for the help output + | Opt(runBenchmarkAll) // bind variable to a new option, with a hint string + ["--benchmark-all"] // the option names it will respond to + ("run benchmark comparing naive code with ViSP, OpenCV, Eigen implementation") // description string for + // the help output + | Opt(lapackMinSize, "min size") // bind variable to a new option, with a hint string + ["--lapack-min-size"] // the option names it will respond to + ("matrix/vector min size to enable blas/lapack usage"); // description string for the help output + +// Now pass the new composite back to Catch so it uses that session.cli(cli); // Let Catch (using Clara) parse the command line @@ -940,7 +944,7 @@ int main(int argc, char *argv[]) vpMatrix::setLapackMatrixMinSize(lapackMinSize); std::cout << "Used matrix/vector min size to enable Blas/Lapack optimization: " << vpMatrix::getLapackMatrixMinSize() - << std::endl; + << std::endl; int numFailed = session.run(); diff --git a/modules/core/test/math/perfMatrixTranspose.cpp b/modules/core/test/math/perfMatrixTranspose.cpp index 373a295e17..d2a50d5e30 100644 --- a/modules/core/test/math/perfMatrixTranspose.cpp +++ b/modules/core/test/math/perfMatrixTranspose.cpp @@ -50,6 +50,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { @@ -176,7 +180,7 @@ TEST_CASE("Benchmark vpMatrix transpose", "[benchmark]") const std::vector > sizes = { {701, 1503}, {1791, 837}, {1201, 1201}, {1024, 1024}, {2000, 2000}, {10, 6}, {25, 6}, {100, 6}, {200, 6}, {500, 6}, {1000, 6}, {1500, 6}, {2000, 6}, {6, 10}, {6, 25}, {6, 100}, {6, 200}, {6, 500}, - {6, 1000}, {6, 1500}, {6, 2000}, {640, 1000}, {800, 640}, {640, 500}, {500, 640}, {640, 837}}; + {6, 1000}, {6, 1500}, {6, 2000}, {640, 1000}, {800, 640}, {640, 500}, {500, 640}, {640, 837} }; for (auto sz : sizes) { vpMatrix M = generateMatrix(sz.first, sz.second); @@ -270,7 +274,8 @@ TEST_CASE("Benchmark vpMatrix transpose", "[benchmark]") }; #endif } - } else { + } + else { vpMatrix M = generateMatrix(11, 17); vpMatrix Mt_true = generateMatrixTranspose(11, 17); @@ -286,12 +291,12 @@ int main(int argc, char *argv[]) // Build a new parser on top of Catch's using namespace Catch::clara; auto cli = session.cli() // Get Catch's composite command line parser - | Opt(g_runBenchmark) // bind variable to a new option, with a hint string - ["--benchmark"] // the option names it will respond to - ("run benchmark?") // description string for the help output - | Opt(g_tileSize, "tileSize")["--tileSize"]("Tile size?"); + | Opt(g_runBenchmark) // bind variable to a new option, with a hint string + ["--benchmark"] // the option names it will respond to + ("run benchmark?") // description string for the help output + | Opt(g_tileSize, "tileSize")["--tileSize"]("Tile size?"); - // Now pass the new composite back to Catch so it uses that +// Now pass the new composite back to Catch so it uses that session.cli(cli); // Let Catch (using Clara) parse the command line diff --git a/modules/core/test/math/testArray2D.cpp b/modules/core/test/math/testArray2D.cpp index 50dcb0cc9c..9194e0f2ff 100644 --- a/modules/core/test/math/testArray2D.cpp +++ b/modules/core/test/math/testArray2D.cpp @@ -51,6 +51,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + template bool test(const std::string &s, const vpArray2D &A, const std::vector &bench) { static unsigned int cpt = 0; diff --git a/modules/core/test/math/testColVector.cpp b/modules/core/test/math/testColVector.cpp index b6eac7a01b..94f2654557 100644 --- a/modules/core/test/math/testColVector.cpp +++ b/modules/core/test/math/testColVector.cpp @@ -46,6 +46,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { bool test(const std::string &s, const vpColVector &v, const std::vector &bench) diff --git a/modules/core/test/math/testEigenConversion.cpp b/modules/core/test/math/testEigenConversion.cpp index 47ad406e20..4bd11c6232 100644 --- a/modules/core/test/math/testEigenConversion.cpp +++ b/modules/core/test/math/testEigenConversion.cpp @@ -46,6 +46,10 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { template std::ostream &operator<<(std::ostream &os, const Eigen::Quaternion &q) @@ -56,8 +60,8 @@ template std::ostream &operator<<(std::ostream &os, const Eigen: template std::ostream &operator<<(std::ostream &os, const Eigen::AngleAxis &aa) { return os << "angle: " << aa.angle() << " ; axis: " << aa.axis()(0) << " ; " << aa.axis()(1) << " ; " << aa.axis()(2) - << " ; thetau: " << aa.angle() * aa.axis()(0) << " ; " << aa.angle() * aa.axis()(1) << " ; " - << aa.angle() * aa.axis()(2); + << " ; thetau: " << aa.angle() * aa.axis()(0) << " ; " << aa.angle() * aa.axis()(1) << " ; " + << aa.angle() * aa.axis()(2); } } // namespace @@ -70,11 +74,11 @@ TEST_CASE("vpMatrix <--> Eigen::MatrixXd/Matrix3Xd conversion", "[eigen_conversi { Eigen::MatrixXd eigen_m; - vp::visp2eigen(visp_m, eigen_m); + VISP_NAMESPACE_NAME::visp2eigen(visp_m, eigen_m); std::cout << "Eigen MatrixXd:\n" << eigen_m << std::endl; vpMatrix visp_m2; - vp::eigen2visp(eigen_m, visp_m2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m, visp_m2); std::cout << "ViSP vpMatrix:\n" << visp_m2 << std::endl; REQUIRE(visp_m == visp_m2); @@ -82,11 +86,11 @@ TEST_CASE("vpMatrix <--> Eigen::MatrixXd/Matrix3Xd conversion", "[eigen_conversi } { Eigen::Matrix3Xd eigen_m; - vp::visp2eigen(visp_m, eigen_m); + VISP_NAMESPACE_NAME::visp2eigen(visp_m, eigen_m); std::cout << "Eigen Matrix3Xd:\n" << eigen_m << std::endl; vpMatrix visp_m2; - vp::eigen2visp(eigen_m, visp_m2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m, visp_m2); std::cout << "ViSP vpMatrix:\n" << visp_m2 << std::endl; REQUIRE(visp_m == visp_m2); @@ -110,15 +114,15 @@ TEST_CASE("Eigen::MatrixXd <--> vpMatrix conversion", "[eigen_conversion]") std::cout << "Eigen Matrix (row major: " << eigen_m.IsRowMajor << "):\n" << eigen_m << std::endl; vpMatrix visp_m; - vp::eigen2visp(eigen_m, visp_m); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m, visp_m); std::cout << "ViSP vpMatrix:\n" << visp_m << std::endl; Eigen::MatrixXd eigen_m2; - vp::visp2eigen(visp_m, eigen_m2); + VISP_NAMESPACE_NAME::visp2eigen(visp_m, eigen_m2); std::cout << "Eigen MatrixXd (row major: " << eigen_m2.IsRowMajor << "):\n" << eigen_m2 << std::endl; vpMatrix visp_m2; - vp::eigen2visp(eigen_m2, visp_m2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m2, visp_m2); REQUIRE(visp_m == visp_m2); std::cout << std::endl; } @@ -139,15 +143,15 @@ TEST_CASE("Eigen::MatrixX4d <--> vpMatrix conversion", "[eigen_conversion]") std::cout << "Eigen MatrixX4d (row major: " << eigen_m.IsRowMajor << "):\n" << eigen_m << std::endl; vpMatrix visp_m; - vp::eigen2visp(eigen_m, visp_m); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m, visp_m); std::cout << "ViSP vpMatrix:\n" << visp_m << std::endl; Eigen::MatrixX4d eigen_m2; - vp::visp2eigen(visp_m, eigen_m2); + VISP_NAMESPACE_NAME::visp2eigen(visp_m, eigen_m2); std::cout << "Eigen MatrixX4d (row major: " << eigen_m2.IsRowMajor << "):\n" << eigen_m2 << std::endl; vpMatrix visp_m2; - vp::eigen2visp(eigen_m2, visp_m2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m2, visp_m2); REQUIRE(visp_m == visp_m2); std::cout << std::endl; } @@ -168,15 +172,15 @@ TEST_CASE("Eigen::Matrix <--> vpMatrix conve std::cout << "Eigen Matrix (RowMajor):\n" << eigen_m << std::endl; vpMatrix visp_m; - vp::eigen2visp(eigen_m, visp_m); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m, visp_m); std::cout << "ViSP vpMatrix:\n" << visp_m << std::endl; Eigen::MatrixXd eigen_m2; - vp::visp2eigen(visp_m, eigen_m2); + VISP_NAMESPACE_NAME::visp2eigen(visp_m, eigen_m2); std::cout << "Eigen MatrixXd (row major: " << eigen_m2.IsRowMajor << "):\n" << eigen_m2 << std::endl; vpMatrix visp_m2; - vp::eigen2visp(eigen_m2, visp_m2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m2, visp_m2); REQUIRE(visp_m == visp_m2); std::cout << std::endl; } @@ -197,15 +201,15 @@ TEST_CASE("Eigen::Matrix <--> vpMatrix conve std::cout << "Eigen Matrix (ColMajor):\n" << eigen_m << std::endl; vpMatrix visp_m; - vp::eigen2visp(eigen_m, visp_m); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m, visp_m); std::cout << "ViSP vpMatrix:\n" << visp_m << std::endl; Eigen::MatrixXd eigen_m2; - vp::visp2eigen(visp_m, eigen_m2); + VISP_NAMESPACE_NAME::visp2eigen(visp_m, eigen_m2); std::cout << "Eigen MatrixXd (row major: " << eigen_m2.IsRowMajor << "):\n" << eigen_m2 << std::endl; vpMatrix visp_m2; - vp::eigen2visp(eigen_m2, visp_m2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_m2, visp_m2); REQUIRE(visp_m == visp_m2); std::cout << std::endl; } @@ -214,11 +218,11 @@ TEST_CASE("vpHomogeneousMatrix <--> Eigen::Matrix4d conversion", "[eigen_convers { vpHomogeneousMatrix visp_cMo(0.1, 0.2, 0.3, 0.1, 0.2, 0.3); Eigen::Matrix4d eigen_cMo; - vp::visp2eigen(visp_cMo, eigen_cMo); + VISP_NAMESPACE_NAME::visp2eigen(visp_cMo, eigen_cMo); std::cout << "Eigen Matrix4d cMo:\n" << eigen_cMo << std::endl; vpHomogeneousMatrix visp_cMo2; - vp::eigen2visp(eigen_cMo, visp_cMo2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_cMo, visp_cMo2); std::cout << "ViSP vpHomogeneousMatrix cMo:\n" << visp_cMo2 << std::endl; REQUIRE(visp_cMo == visp_cMo2); std::cout << std::endl; @@ -228,12 +232,12 @@ TEST_CASE("vpHomogeneousMatrix <--> Eigen::Matrix4f + double casting conversion" { vpHomogeneousMatrix visp_cMo; // identity for float to double casting Eigen::Matrix4d eigen_cMo_tmp; - vp::visp2eigen(visp_cMo, eigen_cMo_tmp); + VISP_NAMESPACE_NAME::visp2eigen(visp_cMo, eigen_cMo_tmp); Eigen::Matrix4f eigen_cMo = eigen_cMo_tmp.cast(); std::cout << "Eigen Matrix4f cMo:\n" << eigen_cMo << std::endl; vpHomogeneousMatrix visp_cMo2; - vp::eigen2visp(eigen_cMo.cast(), visp_cMo2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_cMo.cast(), visp_cMo2); std::cout << "ViSP vpHomogeneousMatrix cMo:\n" << visp_cMo2 << std::endl; REQUIRE(visp_cMo == visp_cMo2); std::cout << std::endl; @@ -243,11 +247,11 @@ TEST_CASE("vpQuaternionVector <--> Eigen::Quaternionf conversion", "[eigen_conve { vpQuaternionVector visp_quaternion(0, 1, 2, 3); Eigen::Quaternionf eigen_quaternion; - vp::visp2eigen(visp_quaternion, eigen_quaternion); + VISP_NAMESPACE_NAME::visp2eigen(visp_quaternion, eigen_quaternion); std::cout << "Eigen quaternion: " << eigen_quaternion << std::endl; vpQuaternionVector visp_quaternion2; - vp::eigen2visp(eigen_quaternion, visp_quaternion2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_quaternion, visp_quaternion2); std::cout << "ViSP quaternion: " << visp_quaternion2.t() << std::endl; REQUIRE(visp_quaternion == visp_quaternion2); std::cout << std::endl; @@ -257,11 +261,11 @@ TEST_CASE("vpThetaUVector <--> Eigen::AngleAxisf conversion", "[eigen_conversion { vpThetaUVector visp_thetau(0, 1, 2); Eigen::AngleAxisf eigen_angle_axis; - vp::visp2eigen(visp_thetau, eigen_angle_axis); + VISP_NAMESPACE_NAME::visp2eigen(visp_thetau, eigen_angle_axis); std::cout << "Eigen AngleAxis: " << eigen_angle_axis << std::endl; vpThetaUVector visp_thetau2; - vp::eigen2visp(eigen_angle_axis, visp_thetau2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_angle_axis, visp_thetau2); std::cout << "ViSP AngleAxis: " << visp_thetau2.t() << std::endl; REQUIRE(visp_thetau == visp_thetau2); std::cout << std::endl; @@ -272,11 +276,11 @@ TEST_CASE("vpColVector <--> Eigen::VectorXd conversion", "[eigen_conversion]") vpColVector visp_col(4, 4); visp_col = 10; Eigen::VectorXd eigen_col; - vp::visp2eigen(visp_col, eigen_col); + VISP_NAMESPACE_NAME::visp2eigen(visp_col, eigen_col); std::cout << "Eigen VectorXd: " << eigen_col.transpose() << std::endl; vpColVector visp_col2; - vp::eigen2visp(eigen_col, visp_col2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_col, visp_col2); std::cout << "ViSP vpColVector: " << visp_col2.t() << std::endl; REQUIRE(visp_col == visp_col2); std::cout << std::endl; @@ -287,11 +291,11 @@ TEST_CASE("vpRowVector <--> Eigen::RowVectorXd conversion", "[eigen_conversion]" vpRowVector visp_row(4, 10); visp_row = 10; Eigen::RowVectorXd eigen_row; - vp::visp2eigen(visp_row, eigen_row); + VISP_NAMESPACE_NAME::visp2eigen(visp_row, eigen_row); std::cout << "Eigen RowVectorXd: " << eigen_row << std::endl; vpRowVector visp_row2; - vp::eigen2visp(eigen_row, visp_row2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_row, visp_row2); std::cout << "ViSP vpRowVector: " << visp_row2 << std::endl; REQUIRE(visp_row == visp_row2); std::cout << std::endl; @@ -302,15 +306,15 @@ TEST_CASE("Eigen::RowVector4d <--> vpRowVector conversion", "[eigen_conversion]" Eigen::RowVector4d eigen_row; eigen_row << 9, 8, 7, 6; vpRowVector visp_row; - vp::eigen2visp(eigen_row, visp_row); + VISP_NAMESPACE_NAME::eigen2visp(eigen_row, visp_row); std::cout << "ViSP vpRowVector: " << visp_row << std::endl; Eigen::RowVector4d eigen_row2; - vp::visp2eigen(visp_row, eigen_row2); + VISP_NAMESPACE_NAME::visp2eigen(visp_row, eigen_row2); std::cout << "Eigen RowVector4d: " << eigen_row2 << std::endl; vpRowVector visp_row2; - vp::eigen2visp(eigen_row2, visp_row2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_row2, visp_row2); REQUIRE(visp_row == visp_row2); std::cout << std::endl; } @@ -320,11 +324,11 @@ TEST_CASE("vpRowVector <--> Eigen::RowVector4d conversion", "[eigen_conversion]" vpRowVector visp_row(4, 10); visp_row = 10; Eigen::RowVector4d eigen_row; - vp::visp2eigen(visp_row, eigen_row); + VISP_NAMESPACE_NAME::visp2eigen(visp_row, eigen_row); std::cout << "Eigen RowVector4d: " << eigen_row << std::endl; vpRowVector visp_row2; - vp::eigen2visp(eigen_row, visp_row2); + VISP_NAMESPACE_NAME::eigen2visp(eigen_row, visp_row2); std::cout << "ViSP vpRowVector: " << visp_row2 << std::endl; REQUIRE(visp_row == visp_row2); std::cout << std::endl; diff --git a/modules/core/test/math/testHomogeneousMatrix.cpp b/modules/core/test/math/testHomogeneousMatrix.cpp index 9f7df93d43..9a3c7549a0 100644 --- a/modules/core/test/math/testHomogeneousMatrix.cpp +++ b/modules/core/test/math/testHomogeneousMatrix.cpp @@ -44,6 +44,10 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool test_matrix_equal(const vpHomogeneousMatrix &M1, const vpHomogeneousMatrix &M2, double epsilon = 1e-10) { for (unsigned int i = 0; i < 4; i++) { diff --git a/modules/core/test/math/testJsonArrayConversion.cpp b/modules/core/test/math/testJsonArrayConversion.cpp index 152836a9b0..a2a88dd73d 100644 --- a/modules/core/test/math/testJsonArrayConversion.cpp +++ b/modules/core/test/math/testJsonArrayConversion.cpp @@ -53,6 +53,10 @@ using json = nlohmann::json; //! json namespace shortcut #define CATCH_CONFIG_RUNNER #include "catch.hpp" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { using StringMatcherBase = Catch::Matchers::StdString::StringMatcherBase; diff --git a/modules/core/test/math/testKalmanAcceleration.cpp b/modules/core/test/math/testKalmanAcceleration.cpp index f7105fb6fb..32b2ce93da 100644 --- a/modules/core/test/math/testKalmanAcceleration.cpp +++ b/modules/core/test/math/testKalmanAcceleration.cpp @@ -46,6 +46,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { unsigned int nsignal = 1; // Number of signal to filter unsigned int niter = 100; @@ -105,7 +109,8 @@ int main() flog.close(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/math/testKalmanVelocity.cpp b/modules/core/test/math/testKalmanVelocity.cpp index a3d84250c5..cef84f56ac 100644 --- a/modules/core/test/math/testKalmanVelocity.cpp +++ b/modules/core/test/math/testKalmanVelocity.cpp @@ -44,13 +44,17 @@ #include #include -typedef enum { +typedef enum +{ Position, // Considered measures are the successive positions of the target Velocity // Considered measures are the successive velocities of the target } vpMeasureType; int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { unsigned int nsignal = 2; // Number of signal to filter unsigned int niter = 200; @@ -127,7 +131,8 @@ int main() flog.close(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/math/testLineFitting.cpp b/modules/core/test/math/testLineFitting.cpp index e8d5617ab1..b5e33fd947 100644 --- a/modules/core/test/math/testLineFitting.cpp +++ b/modules/core/test/math/testLineFitting.cpp @@ -48,6 +48,10 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void convertLineEquation(double A, double B, double C, double &a, double &b) @@ -121,7 +125,7 @@ TEST_CASE("Line fitting - Gaussian noise", "[line_fitting]") double y = a * x + b; imPts.push_back(vpImagePoint(y + gauss(), x + gauss())); std::cout << "x: " << x << " ; y: " << y << " ; imPts: (" << imPts.back().get_u() << ", " << imPts.back().get_v() - << ")" << std::endl; + << ")" << std::endl; } double A = 0, B = 0, C = 0; diff --git a/modules/core/test/math/testMath.cpp b/modules/core/test/math/testMath.cpp index 75e10d2215..7b45907617 100644 --- a/modules/core/test/math/testMath.cpp +++ b/modules/core/test/math/testMath.cpp @@ -66,6 +66,9 @@ static const unsigned long __nan[2] = { 0xffffffff, 0x7fffffff }; int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif // Test isNaN if (vpMath::isNaN(0.0)) { std::cerr << "Fail: IsNaN(0.0)=" << vpMath::isNaN(0.0) << " / should be false" << std::endl; diff --git a/modules/core/test/math/testMathUtils.cpp b/modules/core/test/math/testMathUtils.cpp index 0073d8a6f2..3a55d02afe 100644 --- a/modules/core/test/math/testMathUtils.cpp +++ b/modules/core/test/math/testMathUtils.cpp @@ -55,6 +55,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + TEST_CASE("Lon-Lat generator", "[math_lonlat]") { const int lonStart = 0, lonEnd = 360, nlon = 20; @@ -132,11 +136,11 @@ TEST_CASE("Lon-Lat generator", "[math_lonlat]") if (file.is_open()) { (ecef_M_enu * enu_M_cv).save(file); } - } -#endif } +#endif } } +} TEST_CASE("Equidistributed sphere point", "[math_equi_sphere_pts]") { diff --git a/modules/core/test/math/testMatrix.cpp b/modules/core/test/math/testMatrix.cpp index b894a63a42..b4200852fe 100644 --- a/modules/core/test/math/testMatrix.cpp +++ b/modules/core/test/math/testMatrix.cpp @@ -51,6 +51,10 @@ #include // for std::back_inserter +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { bool test_memory(unsigned int nrows, unsigned int ncols, const vpMatrix &M, const std::string &matrix_name, bool pointer_is_null) diff --git a/modules/core/test/math/testMatrixCholesky.cpp b/modules/core/test/math/testMatrixCholesky.cpp index 8f4572d0fa..24db7d6dba 100644 --- a/modules/core/test/math/testMatrixCholesky.cpp +++ b/modules/core/test/math/testMatrixCholesky.cpp @@ -48,6 +48,9 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif bool equal(const vpMatrix &A, const vpMatrix &B) { diff --git a/modules/core/test/math/testMatrixConditionNumber.cpp b/modules/core/test/math/testMatrixConditionNumber.cpp index 956ac8b3d6..54363c578a 100644 --- a/modules/core/test/math/testMatrixConditionNumber.cpp +++ b/modules/core/test/math/testMatrixConditionNumber.cpp @@ -42,6 +42,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + int test_condition_number(const std::string &test_name, const vpMatrix &M) { double precision = 1e-6; @@ -97,7 +101,8 @@ int main() if (test_condition_number("* Test square matrix M", M)) { std::cout << " - Condition number computation fails" << std::endl; return EXIT_FAILURE; - } else { + } + else { std::cout << " + Condition number computation succeed" << std::endl; } @@ -112,7 +117,8 @@ int main() if (test_condition_number("* Test rect matrix M", M)) { std::cout << " - Condition number computation fails" << std::endl; return EXIT_FAILURE; - } else { + } + else { std::cout << " + Condition number computation succeed" << std::endl; } @@ -121,7 +127,8 @@ int main() if (test_condition_number("* Test rect matrix M", M)) { std::cout << " - Condition number computation fails" << std::endl; return EXIT_FAILURE; - } else { + } + else { std::cout << " + Condition number computation succeed" << std::endl; } @@ -142,7 +149,8 @@ int main() if (test_condition_number("* Test rect matrix M", M)) { std::cout << " - Condition number computation fails" << std::endl; return EXIT_FAILURE; - } else { + } + else { std::cout << " + Condition number computation succeed" << std::endl; } @@ -151,7 +159,8 @@ int main() if (test_condition_number("* Test rect matrix M", M)) { std::cout << " - Condition number computation fails" << std::endl; return EXIT_FAILURE; - } else { + } + else { std::cout << " + Condition number computation succeed" << std::endl; } std::cout << "Test succeed" << std::endl; diff --git a/modules/core/test/math/testMatrixConvolution.cpp b/modules/core/test/math/testMatrixConvolution.cpp index bb92a8bc30..02f59cd9f8 100644 --- a/modules/core/test/math/testMatrixConvolution.cpp +++ b/modules/core/test/math/testMatrixConvolution.cpp @@ -41,6 +41,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { bool compareMatrix(const vpMatrix &m, const double *const array) @@ -86,8 +90,8 @@ int main() { vpMatrix res = vpMatrix::conv2(A, B, "full"); - double ground_truth[5 * 5] = {16, 50, 9, 22, 39, 69, 66, 59, 96, 50, 29, 88, 89, - 82, 52, 40, 72, 95, 106, 27, 16, 64, 88, 34, 2}; + double ground_truth[5 * 5] = { 16, 50, 9, 22, 39, 69, 66, 59, 96, 50, 29, 88, 89, + 82, 52, 40, 72, 95, 106, 27, 16, 64, 88, 34, 2 }; std::cout << "A:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(A, B, full):\n" << res << std::endl; @@ -97,7 +101,7 @@ int main() } { vpMatrix res = vpMatrix::conv2(A, B, "same"); - double ground_truth[4 * 4] = {66, 59, 96, 50, 88, 89, 82, 52, 72, 95, 106, 27, 64, 88, 34, 2}; + double ground_truth[4 * 4] = { 66, 59, 96, 50, 88, 89, 82, 52, 72, 95, 106, 27, 64, 88, 34, 2 }; std::cout << "\nA:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(A, B, same):\n" << res << std::endl; @@ -107,7 +111,7 @@ int main() } { vpMatrix res = vpMatrix::conv2(A, B, "valid"); - double ground_truth[3 * 3] = {66, 59, 96, 88, 89, 82, 72, 95, 106}; + double ground_truth[3 * 3] = { 66, 59, 96, 88, 89, 82, 72, 95, 106 }; std::cout << "\nA:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(A, B, valid):\n" << res << std::endl; @@ -130,8 +134,8 @@ int main() { vpMatrix res = vpMatrix::conv2(A, B, "full"); - double ground_truth[5 * 7] = {0, 0, 1, 2, 3, 4, 5, 0, 8, 14, 20, 26, 32, 26, 12, 36, 50, 64, - 78, 92, 58, 24, 64, 86, 108, 130, 152, 90, 36, 84, 97, 110, 123, 136, 77}; + double ground_truth[5 * 7] = { 0, 0, 1, 2, 3, 4, 5, 0, 8, 14, 20, 26, 32, 26, 12, 36, 50, 64, + 78, 92, 58, 24, 64, 86, 108, 130, 152, 90, 36, 84, 97, 110, 123, 136, 77 }; std::cout << "A:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(A, B, full):\n" << res << std::endl; @@ -141,7 +145,7 @@ int main() } { vpMatrix res = vpMatrix::conv2(A, B, "same"); - double ground_truth[2 * 6] = {36, 50, 64, 78, 92, 58, 64, 86, 108, 130, 152, 90}; + double ground_truth[2 * 6] = { 36, 50, 64, 78, 92, 58, 64, 86, 108, 130, 152, 90 }; std::cout << "\nA:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(A, B, same):\n" << res << std::endl; @@ -161,8 +165,8 @@ int main() { vpMatrix res = vpMatrix::conv2(B, A, "full"); - double ground_truth[5 * 7] = {0, 0, 1, 2, 3, 4, 5, 0, 8, 14, 20, 26, 32, 26, 12, 36, 50, 64, - 78, 92, 58, 24, 64, 86, 108, 130, 152, 90, 36, 84, 97, 110, 123, 136, 77}; + double ground_truth[5 * 7] = { 0, 0, 1, 2, 3, 4, 5, 0, 8, 14, 20, 26, 32, 26, 12, 36, 50, 64, + 78, 92, 58, 24, 64, 86, 108, 130, 152, 90, 36, 84, 97, 110, 123, 136, 77 }; std::cout << "A:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(B, A, full):\n" << res << std::endl; @@ -172,7 +176,7 @@ int main() } { vpMatrix res = vpMatrix::conv2(B, A, "same"); - double ground_truth[4 * 2] = {20, 26, 64, 78, 108, 130, 110, 123}; + double ground_truth[4 * 2] = { 20, 26, 64, 78, 108, 130, 110, 123 }; std::cout << "\nA:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(B, A, same):\n" << res << std::endl; @@ -223,9 +227,9 @@ int main() { vpMatrix res = vpMatrix::conv2(A, B, "full"); - double ground_truth[6 * 6] = {128, 32, 122, 119, 31, 78, 88, 179, 252, 208, 154, 139, + double ground_truth[6 * 6] = { 128, 32, 122, 119, 31, 78, 88, 179, 252, 208, 154, 139, 151, 275, 291, 378, 281, 154, 79, 271, 423, 366, 285, 106, - 48, 171, 248, 292, 230, 31, 16, 92, 194, 167, 39, 2}; + 48, 171, 248, 292, 230, 31, 16, 92, 194, 167, 39, 2 }; std::cout << "A:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(A, B, full):\n" << res << std::endl; @@ -235,7 +239,7 @@ int main() } { vpMatrix res = vpMatrix::conv2(A, B, "same"); - double ground_truth[4 * 4] = {179, 252, 208, 154, 275, 291, 378, 281, 271, 423, 366, 285, 171, 248, 292, 230}; + double ground_truth[4 * 4] = { 179, 252, 208, 154, 275, 291, 378, 281, 271, 423, 366, 285, 171, 248, 292, 230 }; std::cout << "\nA:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(A, B, same):\n" << res << std::endl; @@ -245,7 +249,7 @@ int main() } { vpMatrix res = vpMatrix::conv2(A, B, "valid"); - double ground_truth[2 * 2] = {291, 378, 423, 366}; + double ground_truth[2 * 2] = { 291, 378, 423, 366 }; std::cout << "\nA:\n" << A << "\nB:\n" << B << "\nvpMatrix::conv2(A, B, valid):\n" << res << std::endl; @@ -254,7 +258,8 @@ int main() } } } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/math/testMatrixDeterminant.cpp b/modules/core/test/math/testMatrixDeterminant.cpp index 77ed348f5e..0b6a0d4d2d 100644 --- a/modules/core/test/math/testMatrixDeterminant.cpp +++ b/modules/core/test/math/testMatrixDeterminant.cpp @@ -45,6 +45,10 @@ // List of allowed command line options #define GETOPTARGS "cdn:i:pf:R:C:vh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -290,22 +294,22 @@ int main(int argc, const char *argv[]) if (use_plot_file) { of.open(plotfile.c_str()); of << "iter" - << "\t"; + << "\t"; of << "\"Determinant default\"" - << "\t"; + << "\t"; #if defined(VISP_HAVE_LAPACK) of << "\"Determinant Lapack\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_EIGEN3) of << "\"Determinant Eigen3\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_OPENCV) of << "\"Determinant OpenCV\"" - << "\t"; + << "\t"; #endif of << std::endl; } @@ -350,7 +354,7 @@ int main(int argc, const char *argv[]) for (unsigned int i = 0; i < bench.size(); i++) { if (std::fabs(result_lapack[i] - result_opencv[i]) > 1e-6) { std::cout << "Determinant differ between Lapack and OpenCV: " << result_lapack[i] << " " << result_opencv[i] - << std::endl; + << std::endl; ret = EXIT_FAILURE; } } @@ -360,7 +364,7 @@ int main(int argc, const char *argv[]) for (unsigned int i = 0; i < bench.size(); i++) { if (std::fabs(result_eigen3[i] - result_opencv[i]) > 1e-6) { std::cout << "Determinant differ between Eigen3 and OpenCV: " << result_eigen3[i] << " " << result_opencv[i] - << std::endl; + << std::endl; ret = EXIT_FAILURE; } } @@ -370,7 +374,7 @@ int main(int argc, const char *argv[]) for (unsigned int i = 0; i < bench.size(); i++) { if (std::fabs(result_eigen3[i] - result_lapack[i]) > 1e-6) { std::cout << "Determinant differ between Eigen3 and Lapack: " << result_eigen3[i] << " " << result_lapack[i] - << std::endl; + << std::endl; ret = EXIT_FAILURE; } } @@ -383,7 +387,8 @@ int main(int argc, const char *argv[]) if (ret == EXIT_SUCCESS) { std::cout << "Test succeed" << std::endl; - } else { + } + else { std::cout << "Test failed" << std::endl; } @@ -394,8 +399,9 @@ int main(int argc, const char *argv[]) std::cout << "Test does nothing since you dont't have Lapack, Eigen3 or OpenCV 3rd party" << std::endl; return EXIT_SUCCESS; #endif - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } -} + } diff --git a/modules/core/test/math/testMatrixException.cpp b/modules/core/test/math/testMatrixException.cpp index afb00f30b8..5da0509f34 100644 --- a/modules/core/test/math/testMatrixException.cpp +++ b/modules/core/test/math/testMatrixException.cpp @@ -45,6 +45,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpMatrix M; vpMatrix M1(2, 3); vpMatrix M3(2, 2); @@ -53,7 +56,8 @@ int main() try { M = M1 * M3; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } @@ -61,7 +65,8 @@ int main() try { M = M1 + M3; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } diff --git a/modules/core/test/math/testMatrixInitialization.cpp b/modules/core/test/math/testMatrixInitialization.cpp index a4f0f4dd53..11127a34a0 100644 --- a/modules/core/test/math/testMatrixInitialization.cpp +++ b/modules/core/test/math/testMatrixInitialization.cpp @@ -41,6 +41,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool equal(const vpArray2D &a1, const vpArray2D &a2, double epsilon) { if (a1.size() != a2.size()) { diff --git a/modules/core/test/math/testMatrixInverse.cpp b/modules/core/test/math/testMatrixInverse.cpp index 745fc88c98..509ddd1bc3 100644 --- a/modules/core/test/math/testMatrixInverse.cpp +++ b/modules/core/test/math/testMatrixInverse.cpp @@ -53,6 +53,10 @@ // List of allowed command line options #define GETOPTARGS "cdn:i:pf:R:C:vh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -248,7 +252,7 @@ void create_bench_symmetric_positive_matrix(unsigned int nb_matrices, unsigned i { if (verbose) std::cout << "Create a bench of " << nb_matrices << " " << n << " by " << n << " symmetric positive matrices" - << std::endl; + << std::endl; bench.clear(); for (unsigned int i = 0; i < nb_matrices; i++) { vpMatrix M; @@ -260,8 +264,8 @@ void create_bench_symmetric_positive_matrix(unsigned int nb_matrices, unsigned i if (verbose) { std::cout << " Generated random symmetric positive matrix A=" << std::endl << M << std::endl; std::cout << " Generated random symmetric positive matrix not " - "invertibleL: det=" - << det << ". Retrying..." << std::endl; + "invertibleL: det=" + << det << ". Retrying..." << std::endl; } } #else @@ -286,8 +290,8 @@ void create_bench_random_triangular_matrix(unsigned int nb_matrices, unsigned in if (verbose) { std::cout << " Generated random symmetric positive matrix A=" << std::endl << M << std::endl; std::cout << " Generated random symmetric positive matrix not " - "invertibleL: det=" - << det << ". Retrying..." << std::endl; + "invertibleL: det=" + << det << ". Retrying..." << std::endl; } } #else @@ -304,7 +308,7 @@ int test_inverse(const std::vector &bench, const std::vector vpMatrix I = bench[i] * result[i]; if (std::fabs(I.frobeniusNorm() - sqrt(static_cast(bench[0].AtA().getRows()))) > epsilon) { std::cout << "Bad inverse[" << i << "]: " << I.frobeniusNorm() << " " << sqrt((double)bench[0].AtA().getRows()) - << std::endl; + << std::endl; return EXIT_FAILURE; } } @@ -337,7 +341,7 @@ int test_inverse_lu_eigen3(bool verbose, const std::vector &bench, dou // Compute inverse if (verbose) std::cout << " Inverting " << bench[0].AtA().getRows() << "x" << bench[0].AtA().getCols() - << " matrix using LU decomposition (Eigen3)." << std::endl; + << " matrix using LU decomposition (Eigen3)." << std::endl; std::vector result(bench.size()); double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { @@ -358,7 +362,7 @@ int test_inverse_lu_lapack(bool verbose, const std::vector &bench, dou // Compute inverse if (verbose) std::cout << " Inverting " << bench[0].AtA().getRows() << "x" << bench[0].AtA().getCols() - << " matrix using LU decomposition (Lapack)." << std::endl; + << " matrix using LU decomposition (Lapack)." << std::endl; std::vector result(bench.size()); double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { @@ -377,7 +381,7 @@ int test_inverse_cholesky_lapack(bool verbose, const std::vector &benc // Compute inverse if (verbose) std::cout << " Inverting " << bench[0].AtA().getRows() << "x" << bench[0].AtA().getCols() - << " matrix using cholesky decomposition (Lapack)." << std::endl; + << " matrix using cholesky decomposition (Lapack)." << std::endl; std::vector result(bench.size()); double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { @@ -396,7 +400,7 @@ int test_inverse_qr_lapack(bool verbose, const std::vector &bench, dou // Compute inverse if (verbose) std::cout << " Inverting " << bench[0].AtA().getRows() << "x" << bench[0].AtA().getCols() - << " matrix using QR decomposition (Lapack)" << std::endl; + << " matrix using QR decomposition (Lapack)" << std::endl; std::vector result(bench.size()); double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { @@ -417,7 +421,7 @@ int test_inverse_lu_opencv(bool verbose, const std::vector &bench, dou // Compute inverse if (verbose) std::cout << " Inverting " << bench[0].AtA().getRows() << "x" << bench[0].AtA().getCols() - << " matrix using LU decomposition (OpenCV)" << std::endl; + << " matrix using LU decomposition (OpenCV)" << std::endl; std::vector result(bench.size()); double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { @@ -436,7 +440,7 @@ int test_inverse_cholesky_opencv(bool verbose, const std::vector &benc // Compute inverse if (verbose) std::cout << " Inverting " << bench[0].AtA().getRows() << "x" << bench[0].AtA().getCols() - << " matrix using Cholesky decomposition (OpenCV)" << std::endl; + << " matrix using Cholesky decomposition (OpenCV)" << std::endl; std::vector result(bench.size()); double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { @@ -458,7 +462,7 @@ int test_pseudo_inverse(bool verbose, const std::vector &bench, double // Compute inverse if (verbose) std::cout << " Pseudo inverting " << bench[0].AtA().getRows() << "x" << bench[0].AtA().getCols() << " matrix" - << std::endl; + << std::endl; std::vector result(bench.size()); double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { @@ -519,39 +523,39 @@ int main(int argc, const char *argv[]) if (use_plot_file) { of.open(plotfile.c_str()); of << "iter" - << "\t"; + << "\t"; #if defined(VISP_HAVE_LAPACK) of << "\"LU Lapack\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_EIGEN3) of << "\"LU Eigen3\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_OPENCV) of << "\"LU OpenCV\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_LAPACK) of << "\"Cholesky Lapack\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_OPENCV) of << "\"Cholesky OpenCV\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_LAPACK) of << "\"QR Lapack\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV) of << "\"Pseudo inverse (Lapack, Eigen3 or OpenCV)\"" - << "\t"; + << "\t"; #endif of << std::endl; } @@ -643,12 +647,14 @@ int main(int argc, const char *argv[]) if (ret == EXIT_SUCCESS) { std::cout << "Test succeed" << std::endl; - } else { + } + else { std::cout << "Test failed" << std::endl; } return ret; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/math/testMatrixPseudoInverse.cpp b/modules/core/test/math/testMatrixPseudoInverse.cpp index 914af147e7..ec5f195b56 100644 --- a/modules/core/test/math/testMatrixPseudoInverse.cpp +++ b/modules/core/test/math/testMatrixPseudoInverse.cpp @@ -51,6 +51,10 @@ // List of allowed command line options #define GETOPTARGS "cdn:i:pf:R:C:vh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/modules/core/test/math/testMomentAlpha.cpp b/modules/core/test/math/testMomentAlpha.cpp index a4fe42ef1e..5123e070ae 100644 --- a/modules/core/test/math/testMomentAlpha.cpp +++ b/modules/core/test/math/testMomentAlpha.cpp @@ -48,6 +48,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + int test_moment_alpha(const std::string &name, bool symmetry, const std::vector &vec_angle, double tolerance_deg, double symmetry_threshold = 1e-6) { @@ -155,8 +159,9 @@ int test_moment_alpha(const std::string &name, bool symmetry, const std::vector< std::cout << "Error: result is not in the tolerance: " << tolerance_deg << std::endl; return EXIT_FAILURE; } - } else { - // Tranform input angle from [0; 360] to [0; 180] range + } + else { + // Tranform input angle from [0; 360] to [0; 180] range double angle_des1 = vec_angle[i]; double angle_des2 = vec_angle[i] - 180; @@ -164,7 +169,7 @@ int test_moment_alpha(const std::string &name, bool symmetry, const std::vector< double alpha = vpMath::deg(malpha.get()); std::cout << "alpha expected " << angle_des1 << " or " << angle_des2 << " computed " << alpha << " deg" - << std::endl; + << std::endl; if (!vpMath::equal(angle_des1, alpha, tolerance_deg) && !vpMath::equal(angle_des2, alpha, tolerance_deg)) { // 0.5 deg of tolerance diff --git a/modules/core/test/math/testPoseVector.cpp b/modules/core/test/math/testPoseVector.cpp index bfe0126b0e..68602ebd22 100644 --- a/modules/core/test/math/testPoseVector.cpp +++ b/modules/core/test/math/testPoseVector.cpp @@ -49,6 +49,10 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void checkSize(const vpPoseVector &pose, const std::vector &ref) @@ -112,7 +116,7 @@ TEST_CASE("vpPoseVector constructor", "[vpColVector]") TEST_CASE("vpPoseVector copy constructor", "[vpColVector]") { - std::vector ref = {0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)}; + std::vector ref = { 0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30) }; vpPoseVector pose1(ref[0], ref[1], ref[2], ref[3], ref[4], ref[5]); vpPoseVector pose2(pose1); @@ -123,7 +127,7 @@ TEST_CASE("vpPoseVector copy constructor", "[vpColVector]") TEST_CASE("vpPoseVector object assignment", "[vpColVector]") { - std::vector ref = {0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)}; + std::vector ref = { 0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30) }; vpPoseVector pose1(ref[0], ref[1], ref[2], ref[3], ref[4], ref[5]); vpPoseVector pose2 = pose1; @@ -134,7 +138,7 @@ TEST_CASE("vpPoseVector object assignment", "[vpColVector]") TEST_CASE("vpPoseVector set", "[vpColVector]") { - std::vector ref = {0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)}; + std::vector ref = { 0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30) }; vpPoseVector pose1(ref[0], ref[1], ref[2], ref[3], ref[4], ref[5]); vpPoseVector pose2; @@ -146,7 +150,7 @@ TEST_CASE("vpPoseVector set", "[vpColVector]") TEST_CASE("vpPoseVector constructor t, tu", "[vpColVector]") { - std::vector ref = {0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)}; + std::vector ref = { 0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30) }; vpTranslationVector t(ref[0], ref[1], ref[2]); vpThetaUVector tu(ref[3], ref[4], ref[5]); @@ -158,7 +162,7 @@ TEST_CASE("vpPoseVector constructor t, tu", "[vpColVector]") TEST_CASE("vpPoseVector build t, tu", "[vpColVector]") { - std::vector ref = {0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)}; + std::vector ref = { 0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30) }; vpTranslationVector t(ref[0], ref[1], ref[2]); vpThetaUVector tu(ref[3], ref[4], ref[5]); @@ -171,7 +175,7 @@ TEST_CASE("vpPoseVector build t, tu", "[vpColVector]") TEST_CASE("vpPoseVector constructor vpHomogeneousMatrix", "[vpColVector]") { - std::vector ref = {0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)}; + std::vector ref = { 0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30) }; vpTranslationVector t(ref[0], ref[1], ref[2]); vpThetaUVector tu(ref[3], ref[4], ref[5]); vpHomogeneousMatrix M(t, tu); @@ -184,7 +188,7 @@ TEST_CASE("vpPoseVector constructor vpHomogeneousMatrix", "[vpColVector]") TEST_CASE("vpPoseVector build vpHomogeneousMatrix", "[vpColVector]") { - std::vector ref = {0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)}; + std::vector ref = { 0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30) }; vpTranslationVector t(ref[0], ref[1], ref[2]); vpThetaUVector tu(ref[3], ref[4], ref[5]); vpHomogeneousMatrix M(t, tu); @@ -198,7 +202,7 @@ TEST_CASE("vpPoseVector build vpHomogeneousMatrix", "[vpColVector]") TEST_CASE("vpPoseVector constructor t, R", "[vpColVector]") { - std::vector ref = {0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)}; + std::vector ref = { 0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30) }; vpTranslationVector t(ref[0], ref[1], ref[2]); vpThetaUVector tu(ref[3], ref[4], ref[5]); vpRotationMatrix R(tu); @@ -211,7 +215,7 @@ TEST_CASE("vpPoseVector constructor t, R", "[vpColVector]") TEST_CASE("vpPoseVector build t, R", "[vpColVector]") { - std::vector ref = {0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)}; + std::vector ref = { 0.1, 0.2, 0.3, vpMath::rad(10), vpMath::rad(20), vpMath::rad(30) }; vpTranslationVector t(ref[0], ref[1], ref[2]); vpThetaUVector tu(ref[3], ref[4], ref[5]); vpRotationMatrix R(tu); diff --git a/modules/core/test/math/testQuaternion.cpp b/modules/core/test/math/testQuaternion.cpp index 0993377aae..347fc32c92 100644 --- a/modules/core/test/math/testQuaternion.cpp +++ b/modules/core/test/math/testQuaternion.cpp @@ -46,6 +46,10 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + TEST_CASE("Quaternion interpolation", "[quaternion]") { const double angle0 = vpMath::rad(-37.14); diff --git a/modules/core/test/math/testRand.cpp b/modules/core/test/math/testRand.cpp index 3b9427b945..9943689b7e 100644 --- a/modules/core/test/math/testRand.cpp +++ b/modules/core/test/math/testRand.cpp @@ -43,6 +43,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { class vpUniRandOld @@ -106,11 +110,10 @@ class vpUniRandOld //! Default constructor. explicit vpUniRandOld(const long seed = 0) : a(16807), m(2147483647), q(127773), r(2836), normalizer(2147484721.0), x((seed) ? seed : 739806647) - { - } + { } //! Default destructor. - virtual ~vpUniRandOld(){}; + virtual ~vpUniRandOld() { }; //! Operator that allows to get a random value. double operator()() { return draw1(); } @@ -249,7 +252,7 @@ TEST_CASE("Check uniform draw", "[visp_rand]") double pi_error = pi - M_PI; std::cout << "Old ViSP vpUniRand implementation calculated pi: " << pi << " in " << chrono.getDurationMs() << " ms" - << std::endl; + << std::endl; std::cout << "pi error: " << pi_error << std::endl; CHECK(pi == Approx(M_PI).margin(0.005)); diff --git a/modules/core/test/math/testRobust.cpp b/modules/core/test/math/testRobust.cpp index 86697b5640..e043f8e442 100644 --- a/modules/core/test/math/testRobust.cpp +++ b/modules/core/test/math/testRobust.cpp @@ -50,6 +50,10 @@ // List of allowed command line options #define GETOPTARGS "cdho:" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ofilename); bool getOptions(int argc, const char **argv, std::string &ofilename); @@ -162,7 +166,8 @@ int main(int argc, const char **argv) try { // Create the dirname vpIoTools::makeDirectory(ofilename); - } catch (...) { + } + catch (...) { usage(argv[0], nullptr, ofilename); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << ofilename << std::endl; @@ -196,14 +201,16 @@ int main(int argc, const char **argv) while (x < 10) { if (fabs(x / sig) <= (4.6851)) { w = vpMath::sqr(1 - vpMath::sqr(x / (sig * 4.6851))); - } else { + } + else { w = 0; } f << x << " " << w << std::endl; x += 0.01; } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/math/testRotation.cpp b/modules/core/test/math/testRotation.cpp index db2202956e..58665da2ce 100644 --- a/modules/core/test/math/testRotation.cpp +++ b/modules/core/test/math/testRotation.cpp @@ -47,6 +47,10 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { vpThetaUVector generateThetaU(vpUniRand &rng) diff --git a/modules/core/test/math/testRowVector.cpp b/modules/core/test/math/testRowVector.cpp index 20731459c6..55fa99fa92 100644 --- a/modules/core/test/math/testRowVector.cpp +++ b/modules/core/test/math/testRowVector.cpp @@ -45,6 +45,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool test(const std::string &s, const vpRowVector &v, const std::vector &bench) { static unsigned int cpt = 0; diff --git a/modules/core/test/math/testSPC.cpp b/modules/core/test/math/testSPC.cpp index 7d8e3140f8..9ac1f22f10 100644 --- a/modules/core/test/math/testSPC.cpp +++ b/modules/core/test/math/testSPC.cpp @@ -46,6 +46,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool initializeShewhartTest(const float &mean, const float &stdev, const bool &verbose, const std::string &testName, vpStatisticalTestShewhart &tester) { const bool activateWECOrules = true; diff --git a/modules/core/test/math/testSvd.cpp b/modules/core/test/math/testSvd.cpp index 69dc066c56..1806a12691 100644 --- a/modules/core/test/math/testSvd.cpp +++ b/modules/core/test/math/testSvd.cpp @@ -50,6 +50,10 @@ // List of allowed command line options #define GETOPTARGS "cdn:i:pf:R:C:vh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -541,9 +545,9 @@ int main(int argc, const char *argv[]) std::cout << "Test does nothing since you dont't have Lapack, Eigen3 or OpenCV 3rd party" << std::endl; return EXIT_SUCCESS; #endif - } + } catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } -} + } diff --git a/modules/core/test/math/testTranslationVector.cpp b/modules/core/test/math/testTranslationVector.cpp index 1a6d1b436a..5a17acb31d 100644 --- a/modules/core/test/math/testTranslationVector.cpp +++ b/modules/core/test/math/testTranslationVector.cpp @@ -40,11 +40,14 @@ */ #include -#include #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool test(const std::string &s, const vpArray2D &A, const std::vector &bench) { static unsigned int cpt = 0; diff --git a/modules/core/test/math/testTwistMatrix.cpp b/modules/core/test/math/testTwistMatrix.cpp index 1437fe5ff8..105ccd356a 100644 --- a/modules/core/test/math/testTwistMatrix.cpp +++ b/modules/core/test/math/testTwistMatrix.cpp @@ -55,6 +55,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { vpTRACE("--------------------------"); vpTRACE("--- TEST vpVelocityTwistMatrix ---"); @@ -102,7 +105,8 @@ int main() vpTRACE("cv = cVe * ev:"); cv.print(std::cout, 6); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/math/testXmlParserHomogeneousMatrix.cpp b/modules/core/test/math/testXmlParserHomogeneousMatrix.cpp index ffc21d3a3d..d273d997b9 100644 --- a/modules/core/test/math/testXmlParserHomogeneousMatrix.cpp +++ b/modules/core/test/math/testXmlParserHomogeneousMatrix.cpp @@ -44,6 +44,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if defined(VISP_HAVE_PUGIXML) #if defined(_WIN32) std::string tmp_dir = "C:/temp/"; diff --git a/modules/core/test/munkres/testMunkres.cpp b/modules/core/test/munkres/testMunkres.cpp index 9256e48a21..af5e2ac723 100644 --- a/modules/core/test/munkres/testMunkres.cpp +++ b/modules/core/test/munkres/testMunkres.cpp @@ -63,6 +63,10 @@ ostream &operator<<(ostream &os, const pair &val) #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + TEST_CASE("Check Munkres-based assignment", "[visp_munkres]") { auto testMunkres = [](const std::vector > &cost_matrix, @@ -231,7 +235,7 @@ int main() if (not testHorMat()) { return EXIT_FAILURE; - } +} return EXIT_SUCCESS; } diff --git a/modules/core/test/network/testClient.cpp b/modules/core/test/network/testClient.cpp index 099ed19642..67cb120c23 100644 --- a/modules/core/test/network/testClient.cpp +++ b/modules/core/test/network/testClient.cpp @@ -47,6 +47,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif // inet_ntop() used in vpClient is not supported on win XP #ifdef VISP_HAVE_FUNC_INET_NTOP try { @@ -71,7 +74,8 @@ int main() std::cout << "Received : " << val << std::endl; } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -79,4 +83,4 @@ int main() std::cout << "This test doesn't work on win XP where inet_ntop() is not available" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/modules/core/test/network/testServer.cpp b/modules/core/test/network/testServer.cpp index 1d03c142fb..e165e3f601 100644 --- a/modules/core/test/network/testServer.cpp +++ b/modules/core/test/network/testServer.cpp @@ -47,6 +47,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #ifdef VISP_HAVE_FUNC_INET_NTOP try { int port = 35000; @@ -73,7 +76,8 @@ int main() } } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -81,4 +85,4 @@ int main() std::cout << "This test doesn't work on win XP where inet_ntop() is not available" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/modules/core/test/network/testUDPClient.cpp b/modules/core/test/network/testUDPClient.cpp index de36ca400b..ca0b9ba582 100644 --- a/modules/core/test/network/testUDPClient.cpp +++ b/modules/core/test/network/testUDPClient.cpp @@ -46,17 +46,21 @@ namespace { -struct vpDataType_t { +struct vpDataType_t +{ double double_val; int int_val; - vpDataType_t() : double_val(0.0), int_val(0) {} - vpDataType_t(double dbl, int i) : double_val(dbl), int_val(i) {} + vpDataType_t() : double_val(0.0), int_val(0) { } + vpDataType_t(double dbl, int i) : double_val(dbl), int_val(i) { } }; } // namespace int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif // inet_ntop() used in vpUDPClient is not supported on win XP #ifdef VISP_HAVE_FUNC_INET_NTOP try { @@ -65,9 +69,10 @@ int main(int argc, char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { servername = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip
(default: 127.0.0.1)] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -89,7 +94,7 @@ int main(int argc, char **argv) data_type.int_val = *reinterpret_cast(msg.c_str() + sizeof(data_type.double_val)); std::cout << "Receive from the server double_val: " << data_type.double_val << " ; int_val: " << data_type.int_val - << std::endl; + << std::endl; } // Send user message @@ -104,7 +109,8 @@ int main(int argc, char **argv) } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -114,4 +120,4 @@ int main(int argc, char **argv) (void)argv; return EXIT_SUCCESS; #endif -} + } diff --git a/modules/core/test/network/testUDPServer.cpp b/modules/core/test/network/testUDPServer.cpp index c5afecf488..21d1e56d36 100644 --- a/modules/core/test/network/testUDPServer.cpp +++ b/modules/core/test/network/testUDPServer.cpp @@ -49,17 +49,21 @@ namespace { -struct vpDataType_t { +struct vpDataType_t +{ double double_val; int int_val; - vpDataType_t() : double_val(0.0), int_val(0) {} - vpDataType_t(double dbl, int i) : double_val(dbl), int_val(i) {} + vpDataType_t() : double_val(0.0), int_val(0) { } + vpDataType_t(double dbl, int i) : double_val(dbl), int_val(i) { } }; } // namespace int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif // inet_ntop() used in vpUDPClient is not supported on win XP #ifdef VISP_HAVE_FUNC_INET_NTOP try { @@ -74,9 +78,9 @@ int main() memcpy(&data_type.double_val, msg.c_str(), sizeof(data_type.double_val)); memcpy(&data_type.int_val, msg.c_str() + sizeof(data_type.double_val), sizeof(data_type.int_val)); std::cout << "Server received double_val: " << data_type.double_val << " ; int_val: " << data_type.int_val - << " from: " << hostInfo << std::endl; + << " from: " << hostInfo << std::endl; - // Get address and port +// Get address and port std::istringstream iss(hostInfo); std::vector tokens; std::copy(std::istream_iterator(iss), std::istream_iterator(), @@ -104,15 +108,18 @@ int main() std::copy(std::istream_iterator(iss), std::istream_iterator(), std::back_inserter(tokens)); server.send("Echo: " + msg, tokens[1], atoi(tokens[2].c_str())); - } else if (res == 0) { + } + else if (res == 0) { std::cout << "Receive timeout" << std::endl; - } else { + } + else { std::cerr << "Error server.receive()!" << std::endl; } } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -120,4 +127,4 @@ int main() std::cout << "This test doesn't work on win XP where inet_ntop() is not available" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/modules/core/test/tools/convert/testConvert.cpp b/modules/core/test/tools/convert/testConvert.cpp index f3573925ab..eea81ef634 100644 --- a/modules/core/test/tools/convert/testConvert.cpp +++ b/modules/core/test/tools/convert/testConvert.cpp @@ -48,6 +48,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool areSame(double a, double b) { return fabs(a - b) < std::numeric_limits::epsilon(); } void testConvertFromImagePointToPoint2f() diff --git a/modules/core/test/tools/cpu-features/testCPUFeatures.cpp b/modules/core/test/tools/cpu-features/testCPUFeatures.cpp index ea52c13617..94e973e1b0 100644 --- a/modules/core/test/tools/cpu-features/testCPUFeatures.cpp +++ b/modules/core/test/tools/cpu-features/testCPUFeatures.cpp @@ -64,13 +64,16 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpCPUFeatures::printCPUInfo(); std::cout << "checkSSE2: " << vpCPUFeatures::checkSSE2() << " ; VISP_HAVE_SSE2: " << VALUE(VISP_HAVE_SSE2) - << std::endl; + << std::endl; std::cout << "checkSSE3: " << vpCPUFeatures::checkSSE3() << " ; VISP_HAVE_SSE3: " << VALUE(VISP_HAVE_SSE3) - << std::endl; + << std::endl; std::cout << "checkSSSE3: " << vpCPUFeatures::checkSSSE3() << " ; VISP_HAVE_SSSE3: " << VALUE(VISP_HAVE_SSSE3) - << std::endl; + << std::endl; return EXIT_SUCCESS; } diff --git a/modules/core/test/tools/endian/testEndian.cpp b/modules/core/test/tools/endian/testEndian.cpp index 32b1c18053..100e9c15e6 100644 --- a/modules/core/test/tools/endian/testEndian.cpp +++ b/modules/core/test/tools/endian/testEndian.cpp @@ -41,9 +41,13 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + TEST_CASE("Test reinterpret_cast_uchar_to_uint16_LE", "[vpEndian_test]") { - unsigned char bitmap[] = {100, 110, 120, 130}; + unsigned char bitmap[] = { 100, 110, 120, 130 }; uint16_t val01 = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap); uint16_t val12 = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + 2); diff --git a/modules/core/test/tools/geometry/testImageCircle.cpp b/modules/core/test/tools/geometry/testImageCircle.cpp index 757172fc86..394a79a1fe 100644 --- a/modules/core/test/tools/geometry/testImageCircle.cpp +++ b/modules/core/test/tools/geometry/testImageCircle.cpp @@ -45,6 +45,9 @@ bool equal(const float &actualVal, const float &theoreticalVal) int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif const float OFFSET = 5.f; const float WIDTH = 640.f; const float HEIGHT = 480.f; diff --git a/modules/core/test/tools/geometry/testPolygon.cpp b/modules/core/test/tools/geometry/testPolygon.cpp index 268106d49e..000cece60b 100644 --- a/modules/core/test/tools/geometry/testPolygon.cpp +++ b/modules/core/test/tools/geometry/testPolygon.cpp @@ -103,6 +103,9 @@ OPTIONS: \n\ */ bool getOptions(int argc, const char **argv, bool &opt_display, bool &opt_click, int &method) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif const char *optarg_; int c; while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg_)) > 1) { @@ -148,6 +151,9 @@ bool getOptions(int argc, const char **argv, bool &opt_display, bool &opt_click, int main(int argc, const char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { bool opt_display = true; bool opt_click = true; diff --git a/modules/core/test/tools/geometry/testPolygon2.cpp b/modules/core/test/tools/geometry/testPolygon2.cpp index d21c68bde1..97577f8e7f 100644 --- a/modules/core/test/tools/geometry/testPolygon2.cpp +++ b/modules/core/test/tools/geometry/testPolygon2.cpp @@ -50,6 +50,10 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #ifdef VISP_HAVE_OPENCV TEST_CASE("Check OpenCV-bsed convex hull") { diff --git a/modules/core/test/tools/geometry/testRect.cpp b/modules/core/test/tools/geometry/testRect.cpp index 2f8dde3291..1c782f3832 100644 --- a/modules/core/test/tools/geometry/testRect.cpp +++ b/modules/core/test/tools/geometry/testRect.cpp @@ -39,6 +39,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpRect c(10.1, 15.05, 19.63, 7.84); vpRect a(c.getLeft() - 12.456, c.getTop() - 7.75, c.getWidth() + 12.456, c.getHeight() + 7.75); vpRect b(c.getLeft(), c.getTop(), c.getWidth() + 8.81, c.getHeight() + 14.57); diff --git a/modules/core/test/tools/geometry/testXmlParserRectOriented.cpp b/modules/core/test/tools/geometry/testXmlParserRectOriented.cpp index 17b5c4b7e5..e25f8bc8e1 100644 --- a/modules/core/test/tools/geometry/testXmlParserRectOriented.cpp +++ b/modules/core/test/tools/geometry/testXmlParserRectOriented.cpp @@ -44,6 +44,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if defined(VISP_HAVE_PUGIXML) #if defined(_WIN32) std::string tmp_dir = "C:/temp/"; diff --git a/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp b/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp index 1c818c46ea..c04bbb799f 100644 --- a/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp +++ b/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp @@ -54,6 +54,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:t:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /* Print the program options. diff --git a/modules/core/test/tools/io-with-dataset/testIoTools.cpp b/modules/core/test/tools/io-with-dataset/testIoTools.cpp index c31c4e36f3..bc46bf9874 100644 --- a/modules/core/test/tools/io-with-dataset/testIoTools.cpp +++ b/modules/core/test/tools/io-with-dataset/testIoTools.cpp @@ -43,6 +43,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { template void checkReadBinaryValue(std::ifstream &file, const T checkValue) @@ -84,7 +88,8 @@ int main(int argc, const char **argv) const char c = vpIoTools::separator; if (c == '\\') { std::cout << "The directory separator character is '" << c << "' (Windows platform)." << std::endl; - } else { + } + else { std::cout << "The directory separator character is '" << c << "' (Unix like platform)." << std::endl; } @@ -104,13 +109,13 @@ int main(int argc, const char **argv) std::string windowsPathnameStyle = "\\usr\\bin\\java"; std::cout << "Parent of " << windowsPathnameStyle << " is " << vpIoTools::getParent(windowsPathnameStyle) - << std::endl; + << std::endl; std::cout << "Name of " << windowsPathnameStyle << " is " << vpIoTools::getName(windowsPathnameStyle) << std::endl; std::string parent = "/usr/toto/", child = "\\blabla\\java"; std::cout << "parent=" << vpIoTools::path(parent) << " ; child=" << vpIoTools::path(child) << std::endl; std::cout << "Create file path from parent=" << parent << " and child=" << child << " is " - << vpIoTools::createFilePath(parent, child) << std::endl; + << vpIoTools::createFilePath(parent, child) << std::endl; std::string expandPath = "~/Documents/fictional directory/fictional file"; std::cout << "Path for " << expandPath << " is " << vpIoTools::path(expandPath) << std::endl; @@ -120,13 +125,13 @@ int main(int argc, const char **argv) std::cout << "Get parent with a filename=" << vpIoTools::getParent("my_file.txt") << std::endl; expandPath = "~/Documents/fictional dir/fictional file.txt"; std::cout << "Get name with a unix expand pathname " << expandPath << "=" << vpIoTools::getName(expandPath) - << std::endl; + << std::endl; std::cout << "Get parent with a unix expand pathname " << expandPath << "=" << vpIoTools::getParent(expandPath) - << std::endl; + << std::endl; pathname = "c:/dir"; std::cout << "pathname=" << vpIoTools::splitDrive(pathname).first << " ; " << vpIoTools::splitDrive(pathname).second - << std::endl; + << std::endl; std::cout << "isAbsolutePath of " << pathname << "=" << vpIoTools::isAbsolutePathname(pathname) << std::endl; @@ -147,118 +152,134 @@ int main(int argc, const char **argv) #if defined(_WIN32) if (strcmp(vpIoTools::splitDrive("c:\\foo\\bar").first.c_str(), "c:") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("c:\\foo\\bar").first << " should be=c:" << std::endl; } if (strcmp(vpIoTools::splitDrive("c:\\foo\\bar").second.c_str(), "\\foo\\bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("c:\\foo\\bar").second << " should be=\\foo\\bar" << std::endl; } if (strcmp(vpIoTools::splitDrive("c:/foo/bar").first.c_str(), "c:") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("c:/foo/bar").first << " should be=c:" << std::endl; } if (strcmp(vpIoTools::splitDrive("c:/foo/bar").second.c_str(), "/foo/bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("c:/foo/bar").second << " should be=/foo/bar" << std::endl; } if (strcmp(vpIoTools::splitDrive("\\\\conky\\mountpoint\\foo\\bar").first.c_str(), "\\\\conky\\mountpoint") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("\\\\conky\\mountpoint\\foo\\bar").first - << " should be=\\\\conky\\mountpoint" << std::endl; + << " should be=\\\\conky\\mountpoint" << std::endl; } if (strcmp(vpIoTools::splitDrive("\\\\conky\\mountpoint\\foo\\bar").second.c_str(), "\\foo\\bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("\\\\conky\\mountpoint\\foo\\bar").second << " should be=\\foo\\bar" - << std::endl; + << std::endl; } if (strcmp(vpIoTools::splitDrive("//conky/mountpoint/foo/bar").first.c_str(), "//conky/mountpoint") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("//conky/mountpoint/foo/bar").first << " should be=//conky/mountpoint" - << std::endl; + << std::endl; } if (strcmp(vpIoTools::splitDrive("//conky/mountpoint/foo/bar").second.c_str(), "/foo/bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("//conky/mountpoint/foo/bar").second << " should be=/foo/bar" - << std::endl; + << std::endl; } if (strcmp(vpIoTools::splitDrive("\\\\\\conky\\mountpoint\\foo\\bar").first.c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("\\\\\\conky\\mountpoint\\foo\\bar").first - << " should be=" << std::endl; + << " should be=" << std::endl; } if (strcmp(vpIoTools::splitDrive("\\\\\\conky\\mountpoint\\foo\\bar").second.c_str(), "\\\\\\conky\\mountpoint\\foo\\bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("\\\\\\conky\\mountpoint\\foo\\bar").second - << " should be=\\\\\\conky\\mountpoint\\foo\\bar" << std::endl; + << " should be=\\\\\\conky\\mountpoint\\foo\\bar" << std::endl; } if (strcmp(vpIoTools::splitDrive("///conky/mountpoint/foo/bar").first.c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("///conky/mountpoint/foo/bar").first << " should be=" << std::endl; } if (strcmp(vpIoTools::splitDrive("///conky/mountpoint/foo/bar").second.c_str(), "///conky/mountpoint/foo/bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("///conky/mountpoint/foo/bar").second - << " should be=///conky/mountpoint/foo/bar" << std::endl; + << " should be=///conky/mountpoint/foo/bar" << std::endl; } if (strcmp(vpIoTools::splitDrive("\\\\conky\\\\mountpoint\\foo\\bar").first.c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("\\\\conky\\\\mountpoint\\foo\\bar").first - << " should be=" << std::endl; + << " should be=" << std::endl; } if (strcmp(vpIoTools::splitDrive("\\\\conky\\\\mountpoint\\foo\\bar").second.c_str(), "\\\\conky\\\\mountpoint\\foo\\bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("\\\\conky\\\\mountpoint\\foo\\bar").second - << " should be=\\\\conky\\\\mountpoint\\foo\\bar" << std::endl; + << " should be=\\\\conky\\\\mountpoint\\foo\\bar" << std::endl; } if (strcmp(vpIoTools::splitDrive("//conky//mountpoint/foo/bar").first.c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("//conky//mountpoint/foo/bar").first << " should be=" << std::endl; } if (strcmp(vpIoTools::splitDrive("//conky//mountpoint/foo/bar").second.c_str(), "//conky//mountpoint/foo/bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::splitDrive("//conky//mountpoint/foo/bar").second - << " should be=//conky//mountpoint/foo/bar" << std::endl; + << " should be=//conky//mountpoint/foo/bar" << std::endl; } std::cout << "Test vpIoTools::splitDrive (Win32) - passed: " << nbOk << "/" << (nbOk + nbFail) << std::endl; @@ -266,7 +287,7 @@ int main(int argc, const char **argv) if (nbFail) { std::cerr << "Failed test: vpIoTools::splitDrive (Win32)" << std::endl; return EXIT_FAILURE; - } +} #endif // Test vpIoTools::getFileExtension @@ -276,76 +297,86 @@ int main(int argc, const char **argv) if (strcmp(vpIoTools::getFileExtension("foo.ext").c_str(), ".ext") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("foo.ext") << " should be=.ext" << std::endl; } if (strcmp(vpIoTools::getFileExtension("/foo/foo.ext").c_str(), ".ext") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("/foo/foo.ext") << " should be=.ext" << std::endl; } if (strcmp(vpIoTools::getFileExtension(".ext").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension(".ext") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension("\\foo.ext\\foo").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("\\foo.ext\\foo") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension("foo.ext\\").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("foo.ext\\") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension("").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension("foo.bar.ext").c_str(), ".ext") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("foo.bar.ext") << " should be=.ext" << std::endl; } if (strcmp(vpIoTools::getFileExtension("xx/foo.bar.ext").c_str(), ".ext") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("xx/foo.bar.ext") << " should be=.ext" << std::endl; } if (strcmp(vpIoTools::getFileExtension("xx\\foo.bar.ext").c_str(), ".ext") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("xx\\foo.bar.ext") << " should be=.ext" << std::endl; } if (strcmp(vpIoTools::getFileExtension("c:a/b\\c.d").c_str(), ".d") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("c:a/b\\c.d") << " should be=.d" << std::endl; } std::cout << "Test vpIoTools::getFileExtension (WIN32 platform) - passed: " << nbOk << "/" << (nbOk + nbFail) - << std::endl; + << std::endl; if (nbFail) { std::cerr << "Failed test: vpIoTools::getFileExtension (WIN32 platform)" << std::endl; @@ -357,90 +388,102 @@ int main(int argc, const char **argv) if (strcmp(vpIoTools::getFileExtension("foo.bar").c_str(), ".bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("foo.bar") << " should be=.bar" << std::endl; } if (strcmp(vpIoTools::getFileExtension("foo.boo.bar").c_str(), ".bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("foo.boo.bar") << " should be=.bar" << std::endl; } if (strcmp(vpIoTools::getFileExtension("foo.boo.biff.bar").c_str(), ".bar") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("foo.boo.biff.bar") << " should be=.bar" << std::endl; } if (strcmp(vpIoTools::getFileExtension(".csh.rc").c_str(), ".rc") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension(".csh.rc") << " should be=.rc" << std::endl; } if (strcmp(vpIoTools::getFileExtension("nodots").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("nodots") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension(".cshrc").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension(".cshrc") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension("...manydots").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("...manydots") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension("...manydots.ext").c_str(), ".ext") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("...manydots.ext") << " should be=.ext" << std::endl; } if (strcmp(vpIoTools::getFileExtension(".").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension(".") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension("..").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("..") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension("........").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("........") << " should be=" << std::endl; } if (strcmp(vpIoTools::getFileExtension("").c_str(), "") == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" << vpIoTools::getFileExtension("") << " should be=" << std::endl; } std::cout << "Test vpIoTools::getFileExtension (Unix-like platform) - passed: " << nbOk << "/" << (nbOk + nbFail) - << std::endl; + << std::endl; #endif // Test makeDirectory() @@ -511,7 +554,8 @@ int main(int argc, const char **argv) std::cerr << "Error: cannot remove directory: " << tmp_dir << "/test_directory1" << std::endl; return EXIT_FAILURE; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -548,7 +592,8 @@ int main(int argc, const char **argv) return EXIT_FAILURE; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -596,7 +641,8 @@ int main(int argc, const char **argv) return EXIT_FAILURE; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -639,7 +685,7 @@ int main(int argc, const char **argv) nbFail = res ? nbFail + 1 : nbFail; std::cout << "Test vpIoTools::isSamePathname (WIN32 platform) - passed: " << nbOk << "/" << (nbOk + nbFail) - << std::endl; + << std::endl; if (nbFail) { std::cerr << "Failed test: vpIoTools::isSamePathname (WIN32 platform)" << std::endl; return EXIT_FAILURE; @@ -692,16 +738,16 @@ int main(int argc, const char **argv) nbFail = res ? nbFail : nbFail + 1; std::cout << "Test vpIoTools::isSamePathname (Unix platform) - passed: " << nbOk << "/" << (nbOk + nbFail) - << std::endl; + << std::endl; - // Delete test directory +// Delete test directory if (!vpIoTools::remove("/tmp/" + username + "/test")) { std::cerr << "Cannot remove directory: " - << "/tmp/" << username << "/test" << std::endl; + << "/tmp/" << username << "/test" << std::endl; } if (!vpIoTools::remove("/tmp/" + username + "/dummy dir")) { std::cerr << "Cannot remove directory: " - << "/tmp/" << username << "/dummy dir" << std::endl; + << "/tmp/" << username << "/dummy dir" << std::endl; } if (nbFail) { @@ -727,8 +773,8 @@ int main(int argc, const char **argv) // Test checkFilename() vpIoTools::makeDirectory("/tmp/" + username + "/directory (1) with ' quote and spaces"); path1 = "/tmp/" + username + - "/directory (1) with ' quote and spaces/file with ' quote (1) and " - "spaces.txt"; + "/directory (1) with ' quote and spaces/file with ' quote (1) and " + "spaces.txt"; dummy_file.open(path1.c_str()); if (!dummy_file.is_open()) { return EXIT_SUCCESS; @@ -744,13 +790,13 @@ int main(int argc, const char **argv) // Delete test directory if (!vpIoTools::remove("/tmp/" + username + "/directory (1) with ' quote and spaces")) { std::cerr << "Cannot remove directory: " - << "/tmp/" << username << "/directory (1) with ' quote and spaces" << std::endl; + << "/tmp/" << username << "/directory (1) with ' quote and spaces" << std::endl; } // Test endianness { std::string filename_endianness = - vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "endianness/test_endianness_little_endian.bin"); + vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "endianness/test_endianness_little_endian.bin"); std::ifstream file_endianness(filename_endianness.c_str(), std::ios::in | std::ios::binary); if (file_endianness.is_open()) { checkReadBinaryValue(file_endianness, std::numeric_limits::min()); @@ -772,7 +818,8 @@ int main(int argc, const char **argv) checkReadBinaryValue(file_endianness, std::numeric_limits::max()); std::cout << "Test endianness is ok." << std::endl; - } else { + } + else { std::cout << "Cannot open file: " << filename_endianness << std::endl; } } @@ -784,52 +831,56 @@ int main(int argc, const char **argv) std::string testString = std::string("Yolo-V3"); std::string expectedLower = std::string("yolo-v3"); std::string expectedUpper = std::string("YOLO-V3"); - #if defined(_WIN32) +#if defined(_WIN32) if (strcmp(vpIoTools::toLowerCase(testString).c_str(), expectedLower.c_str()) == 0) { nbOk++; - } else { + } + else { nbFail++; std::cout << "Fail=" < @@ -47,6 +47,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { std::string createTmpDir() diff --git a/modules/core/test/tools/serial/testSerialRead.cpp b/modules/core/test/tools/serial/testSerialRead.cpp index 1253e5a1b6..48c4bf434a 100644 --- a/modules/core/test/tools/serial/testSerialRead.cpp +++ b/modules/core/test/tools/serial/testSerialRead.cpp @@ -46,6 +46,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if !defined(_WIN32) std::string port; @@ -55,7 +58,8 @@ int main(int argc, char **argv) port = std::string(argv[i + 1]); else if (std::string(argv[i]) == "--baud") { baud = (unsigned long)atol(argv[i + 1]); - } else if (std::string(argv[i]) == "--help") { + } + else if (std::string(argv[i]) == "--help") { std::cout << "\nUsage: " << argv[0] << " [--port ] [--baud ] [--help]\n" << std::endl; return EXIT_SUCCESS; } @@ -84,4 +88,4 @@ int main(int argc, char **argv) std::cout << "Serial test is only working on unix-like OS." << std::endl; #endif return EXIT_SUCCESS; -} + } diff --git a/modules/core/test/tools/serial/testSerialWrite.cpp b/modules/core/test/tools/serial/testSerialWrite.cpp index 6698fc8649..9b12439afc 100644 --- a/modules/core/test/tools/serial/testSerialWrite.cpp +++ b/modules/core/test/tools/serial/testSerialWrite.cpp @@ -44,6 +44,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if !defined(_WIN32) std::string port; @@ -53,7 +56,8 @@ int main(int argc, char **argv) port = std::string(argv[i + 1]); else if (std::string(argv[i]) == "--baud") { baud = (unsigned long)atol(argv[i + 1]); - } else if (std::string(argv[i]) == "--help") { + } + else if (std::string(argv[i]) == "--help") { std::cout << "\nUsage: " << argv[0] << " [--port ] [--baud ] [--help]\n" << std::endl; return EXIT_SUCCESS; } diff --git a/modules/core/test/tools/time/testTime.cpp b/modules/core/test/tools/time/testTime.cpp index cdf8d9f4ae..c58fef4fb5 100644 --- a/modules/core/test/tools/time/testTime.cpp +++ b/modules/core/test/tools/time/testTime.cpp @@ -58,6 +58,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if !defined(WINRT) try { double v = 0; @@ -123,7 +126,8 @@ int main() std::cout << "t8-t6: ; chrono: " << chrono.getDurationMs() << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/tools/xml/testXmlParser.cpp b/modules/core/test/tools/xml/testXmlParser.cpp index 5c667d327d..23fbfb868e 100644 --- a/modules/core/test/tools/xml/testXmlParser.cpp +++ b/modules/core/test/tools/xml/testXmlParser.cpp @@ -62,6 +62,10 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! * \class vpExampleDataParser * \brief Class example used to show how to implement a xml parser based on the diff --git a/modules/detection/include/visp3/detection/vpDetectorAprilTag.h b/modules/detection/include/visp3/detection/vpDetectorAprilTag.h index 7169c5007b..929c6563be 100644 --- a/modules/detection/include/visp3/detection/vpDetectorAprilTag.h +++ b/modules/detection/include/visp3/detection/vpDetectorAprilTag.h @@ -46,6 +46,14 @@ #include #include +BEGIN_VISP_NAMESPACE +class vpDetectorAprilTag; +END_VISP_NAMESPACE + +// Forward declaration to have the operator in the global namespace +VISP_EXPORT void swap(VISP_NAMESPACE_ADDRESSING vpDetectorAprilTag &o1, VISP_NAMESPACE_ADDRESSING vpDetectorAprilTag &o2); + +BEGIN_VISP_NAMESPACE /*! * \class vpDetectorAprilTag * \ingroup group_detection_tag @@ -213,7 +221,7 @@ * Other examples are also provided in tutorial-apriltag-detector.cpp and * tutorial-apriltag-detector-live.cpp */ -class VISP_EXPORT vpDetectorAprilTag : public vpDetectorBase + class VISP_EXPORT vpDetectorAprilTag : public vpDetectorBase { public: enum vpAprilTagFamily @@ -300,7 +308,7 @@ class VISP_EXPORT vpDetectorAprilTag : public vpDetectorBase m_displayTagThickness = thickness; } - friend void swap(vpDetectorAprilTag &o1, vpDetectorAprilTag &o2); + VISP_EXPORT friend void ::swap(vpDetectorAprilTag &o1, vpDetectorAprilTag &o2); void setZAlignedWithCameraAxis(bool zAlignedWithCameraFrame); @@ -418,5 +426,7 @@ inline std::ostream &operator<<(std::ostream &os, const vpDetectorAprilTag::vpAp return os; } +END_VISP_NAMESPACE + #endif #endif diff --git a/modules/detection/include/visp3/detection/vpDetectorBase.h b/modules/detection/include/visp3/detection/vpDetectorBase.h index ceb1496a7c..2fcdf054d1 100644 --- a/modules/detection/include/visp3/detection/vpDetectorBase.h +++ b/modules/detection/include/visp3/detection/vpDetectorBase.h @@ -45,6 +45,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpDetectorBase * \ingroup group_detection_barcode group_detection_face @@ -131,4 +133,6 @@ class VISP_EXPORT vpDetectorBase //@} }; +END_VISP_NAMESPACE + #endif diff --git a/modules/detection/include/visp3/detection/vpDetectorDNNOpenCV.h b/modules/detection/include/visp3/detection/vpDetectorDNNOpenCV.h index fa20745bef..2da8aafe2d 100644 --- a/modules/detection/include/visp3/detection/vpDetectorDNNOpenCV.h +++ b/modules/detection/include/visp3/detection/vpDetectorDNNOpenCV.h @@ -52,10 +52,12 @@ #include #include + #ifdef VISP_HAVE_NLOHMANN_JSON #include #endif +BEGIN_VISP_NAMESPACE /*! * \class vpDetectorDNNOpenCV * \ingroup group_detection_dnn @@ -77,7 +79,7 @@ * Examples of such JSON files can be found in the tutorial folder. * * \sa \ref tutorial-detection-dnn - */ +*/ class VISP_EXPORT vpDetectorDNNOpenCV { public: @@ -615,5 +617,6 @@ vpDetectorDNNOpenCV::DetectedFeatures2D::display(const vpImage< Type > &img, con ss << "(" << std::setprecision(4) << m_score * 100. << "%)"; vpDisplay::displayText(img, m_bbox.getTopRight(), ss.str(), color); } +END_VISP_NAMESPACE #endif #endif diff --git a/modules/detection/include/visp3/detection/vpDetectorDataMatrixCode.h b/modules/detection/include/visp3/detection/vpDetectorDataMatrixCode.h index 89b814aaa3..2bee838e0a 100644 --- a/modules/detection/include/visp3/detection/vpDetectorDataMatrixCode.h +++ b/modules/detection/include/visp3/detection/vpDetectorDataMatrixCode.h @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpDetectorDataMatrixCode * \ingroup group_detection_barcode @@ -112,6 +113,6 @@ class VISP_EXPORT vpDetectorDataMatrixCode : public vpDetectorBase vpDetectorDataMatrixCode(); bool detect(const vpImage &I) vp_override; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/detection/include/visp3/detection/vpDetectorFace.h b/modules/detection/include/visp3/detection/vpDetectorFace.h index 392e67ff73..7aee7d6543 100644 --- a/modules/detection/include/visp3/detection/vpDetectorFace.h +++ b/modules/detection/include/visp3/detection/vpDetectorFace.h @@ -46,6 +46,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * \class vpDetectorFace * \ingroup group_detection_face @@ -81,7 +82,7 @@ * * A more complete example that works with images acquired from a camera is * provided in tutorial-face-detector-live.cpp. - */ +*/ class VISP_EXPORT vpDetectorFace : public vpDetectorBase { protected: @@ -96,6 +97,6 @@ class VISP_EXPORT vpDetectorFace : public vpDetectorBase bool detect(const cv::Mat &frame_gray); void setCascadeClassifierFile(const std::string &filename); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/detection/include/visp3/detection/vpDetectorQRCode.h b/modules/detection/include/visp3/detection/vpDetectorQRCode.h index 654283a1d8..1fa5b37e57 100644 --- a/modules/detection/include/visp3/detection/vpDetectorQRCode.h +++ b/modules/detection/include/visp3/detection/vpDetectorQRCode.h @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpDetectorQRCode * \ingroup group_detection_barcode @@ -105,7 +106,7 @@ * * Other examples are also provided in tutorial-barcode-detector.cpp and * tutorial-barcode-detector-live.cpp - */ +*/ class VISP_EXPORT vpDetectorQRCode : public vpDetectorBase { protected: @@ -115,6 +116,6 @@ class VISP_EXPORT vpDetectorQRCode : public vpDetectorBase vpDetectorQRCode(); bool detect(const vpImage &I) vp_override; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/detection/src/barcode/vpDetectorDataMatrixCode.cpp b/modules/detection/src/barcode/vpDetectorDataMatrixCode.cpp index c71573fe15..601bed4cdf 100644 --- a/modules/detection/src/barcode/vpDetectorDataMatrixCode.cpp +++ b/modules/detection/src/barcode/vpDetectorDataMatrixCode.cpp @@ -43,6 +43,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Default constructor that does nothing except setting detection timeout to 50ms. This value could be changed using setTimeout(). @@ -109,11 +110,13 @@ bool vpDetectorDataMatrixCode::detect(const vpImage &I) m_message.push_back((const char *)msg->output); m_nb_objects++; - } else { + } + else { end = true; } dmtxMessageDestroy(&msg); - } else { + } + else { end = true; } dmtxRegionDestroy(®); @@ -127,9 +130,9 @@ bool vpDetectorDataMatrixCode::detect(const vpImage &I) } return detected; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: // libvisp_core.a(vpDetectorDataMatrixCode.cpp.o) has no symbols -void dummy_vpDetectorDataMatrixCode(){}; +void dummy_vpDetectorDataMatrixCode() { }; #endif diff --git a/modules/detection/src/barcode/vpDetectorQRCode.cpp b/modules/detection/src/barcode/vpDetectorQRCode.cpp index 81c904b6fd..a37f5d4095 100644 --- a/modules/detection/src/barcode/vpDetectorQRCode.cpp +++ b/modules/detection/src/barcode/vpDetectorQRCode.cpp @@ -39,6 +39,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Default constructor. */ @@ -88,8 +89,9 @@ bool vpDetectorQRCode::detect(const vpImage &I) return detected; } +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpDetectorQRCode.cpp.o) has // no symbols -void dummy_vpDetectorQRCode(){}; +void dummy_vpDetectorQRCode() { }; #endif diff --git a/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp b/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp index f9ad489009..d3846019e1 100644 --- a/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp +++ b/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp @@ -43,6 +43,8 @@ #include #include + +BEGIN_VISP_NAMESPACE /** * \brief Get the list of the parsing methods / types of DNNs supported by the \b vpDetectorDNNOpenCV class. * @@ -1181,6 +1183,7 @@ void vpDetectorDNNOpenCV::setParsingMethod(const DNNResultsParsingType &typePars #endif } +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpDetectorDNNOpenCV.cpp.o) has no symbols void dummy_vpDetectorDNN() { }; diff --git a/modules/detection/src/face/vpDetectorFace.cpp b/modules/detection/src/face/vpDetectorFace.cpp index be790f1cb7..1cccd1f4a1 100644 --- a/modules/detection/src/face/vpDetectorFace.cpp +++ b/modules/detection/src/face/vpDetectorFace.cpp @@ -43,6 +43,7 @@ bool vpSortLargestFace(cv::Rect rect1, cv::Rect rect2) { return (rect1.area() > rect2.area()); } +BEGIN_VISP_NAMESPACE /*! Default constructor. */ @@ -139,7 +140,7 @@ bool vpDetectorFace::detect(const cv::Mat &frame_gray) return detected; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpDetectorFace.cpp.o) has no symbols void dummy_vpDetectorFace() { }; diff --git a/modules/detection/src/tag/vpDetectorAprilTag.cpp b/modules/detection/src/tag/vpDetectorAprilTag.cpp index eeea0d89b8..08581ad5de 100644 --- a/modules/detection/src/tag/vpDetectorAprilTag.cpp +++ b/modules/detection/src/tag/vpDetectorAprilTag.cpp @@ -60,6 +60,8 @@ #include #include +BEGIN_VISP_NAMESPACE + #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpDetectorAprilTag::Impl { @@ -1186,13 +1188,6 @@ void vpDetectorAprilTag::setAprilTagRefineEdges(bool refineEdges) { m_impl->setR void vpDetectorAprilTag::setAprilTagRefinePose(bool refinePose) { m_impl->setRefinePose(refinePose); } #endif -void swap(vpDetectorAprilTag &o1, vpDetectorAprilTag &o2) -{ - using std::swap; - - swap(o1.m_impl, o2.m_impl); -} - /*! * Modify the resulting tag pose returned by getPose() in order to get * a pose where z-axis is aligned when the camera plane is parallel to the tag. @@ -1203,6 +1198,15 @@ void vpDetectorAprilTag::setZAlignedWithCameraAxis(bool zAlignedWithCameraFrame) m_impl->setZAlignedWithCameraAxis(zAlignedWithCameraFrame); } +END_VISP_NAMESPACE + +VISP_EXPORT void swap(VISP_NAMESPACE_ADDRESSING vpDetectorAprilTag &o1, VISP_NAMESPACE_ADDRESSING vpDetectorAprilTag &o2) +{ + using std::swap; + + swap(o1.m_impl, o2.m_impl); +} + #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpDetectorAprilTag.cpp.o) has // no symbols diff --git a/modules/detection/src/vpDetectorBase.cpp b/modules/detection/src/vpDetectorBase.cpp index f69d44149f..03801c7abf 100644 --- a/modules/detection/src/vpDetectorBase.cpp +++ b/modules/detection/src/vpDetectorBase.cpp @@ -35,9 +35,10 @@ #include #include +BEGIN_VISP_NAMESPACE /*! - Default constructor. + Default constructor. */ vpDetectorBase::vpDetectorBase() : m_polygon(), m_message(), m_nb_objects(0), m_timeout_ms(0) { } @@ -120,3 +121,5 @@ vpRect vpDetectorBase::getBBox(size_t i) const vpRect roi(vpImagePoint(top, left), vpImagePoint(bottom, right)); return roi; } + +END_VISP_NAMESPACE diff --git a/modules/detection/test/apriltag-with-dataset/perfApriltagDetection.cpp b/modules/detection/test/apriltag-with-dataset/perfApriltagDetection.cpp index 9bc86f8244..63c0903edd 100644 --- a/modules/detection/test/apriltag-with-dataset/perfApriltagDetection.cpp +++ b/modules/detection/test/apriltag-with-dataset/perfApriltagDetection.cpp @@ -44,6 +44,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + TEST_CASE("Benchmark Apriltag detection 1920x1080", "[benchmark]") { const double tagSize = 0.25; @@ -502,11 +506,11 @@ int main(int argc, char *argv[]) // Build a new parser on top of Catch's using namespace Catch::clara; auto cli = session.cli() // Get Catch's composite command line parser - | Opt(runBenchmark) // bind variable to a new option, with a hint string - ["--benchmark"] // the option names it will respond to - ("run benchmark?"); // description string for the help output + | Opt(runBenchmark) // bind variable to a new option, with a hint string + ["--benchmark"] // the option names it will respond to + ("run benchmark?"); // description string for the help output - // Now pass the new composite back to Catch so it uses that +// Now pass the new composite back to Catch so it uses that session.cli(cli); // Let Catch (using Clara) parse the command line diff --git a/modules/detection/test/apriltag-with-dataset/testAprilTag.cpp b/modules/detection/test/apriltag-with-dataset/testAprilTag.cpp index 286d54e63e..64ad274b6d 100644 --- a/modules/detection/test/apriltag-with-dataset/testAprilTag.cpp +++ b/modules/detection/test/apriltag-with-dataset/testAprilTag.cpp @@ -52,6 +52,10 @@ #include #include #include + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif namespace { struct TagGroundTruth diff --git a/modules/gui/CMakeLists.txt b/modules/gui/CMakeLists.txt index 406893195e..67d27e5ccf 100644 --- a/modules/gui/CMakeLists.txt +++ b/modules/gui/CMakeLists.txt @@ -98,3 +98,7 @@ endif() if(USE_GTK2) vp_set_source_file_compile_flag(src/display/vpDisplayGTK.cpp -Wno-deprecated-declarations) endif() +if(USE_PCL) + vp_set_source_file_compile_flag(src/pointcloud/vpDisplayPCL.cpp -Wno-unused-parameter) + vp_set_source_file_compile_flag(src/pointcloud/vpPclViewer.cpp -Wno-unused-parameter) +endif() diff --git a/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h b/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h index 55b8e091b5..4ef1d6b19a 100644 --- a/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h +++ b/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h @@ -37,14 +37,17 @@ #ifndef _vpColorBlindFliendlyPalette_h_ #define _vpColorBlindFliendlyPalette_h_ -#include -#include +#include + +#include +#include #if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) /** * \brief Class that furnishes a set of colors that color blind people * should be able to distinguish one from another. */ +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpColorBlindFriendlyPalette { public: @@ -172,6 +175,7 @@ class VISP_EXPORT vpColorBlindFriendlyPalette Palette m_colorID; /*!< The ID of the color in the \b vpColorBlindFriendlyPalette::Palette.*/ }; +END_VISP_NAMESPACE /** * \brief Permit to display in a \b std::ostream the name of the \b color. @@ -180,17 +184,17 @@ class VISP_EXPORT vpColorBlindFriendlyPalette * \param color The color we are interested in displaying the name. * \return std::ostream& The stream, in which the name of the \b color has been written. */ -std::ostream &operator<<(std::ostream &os, const vpColorBlindFriendlyPalette &color); + std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpColorBlindFriendlyPalette &color); -/** - * \brief Permits to initialize a \b vpColorBlindFriendlyPalette by reading its name in - * an \b std::istream. - * - * \param is A stream from which we will read the name of \b color in order to initialized it. - * \param color The color we want to initialized. - * \return std::istream& The \b is input, from which we have read the name of \b color. - */ -std::istream &operator>>(std::istream &is, vpColorBlindFriendlyPalette &color); + /** + * \brief Permits to initialize a \b vpColorBlindFriendlyPalette by reading its name in + * an \b std::istream. + * + * \param is A stream from which we will read the name of \b color in order to initialized it. + * \param color The color we want to initialized. + * \return std::istream& The \b is input, from which we have read the name of \b color. + */ +std::istream &operator>>(std::istream &is, VISP_NAMESPACE_ADDRESSING vpColorBlindFriendlyPalette &color); #endif #endif // _vpColorBlindFliendlyPalette_h_ diff --git a/modules/gui/include/visp3/gui/vpD3DRenderer.h b/modules/gui/include/visp3/gui/vpD3DRenderer.h index e3629d060c..b1b6b5d6a0 100644 --- a/modules/gui/include/visp3/gui/vpD3DRenderer.h +++ b/modules/gui/include/visp3/gui/vpD3DRenderer.h @@ -31,15 +31,14 @@ * D3D renderer for windows 32 display */ -#ifndef DOXYGEN_SHOULD_SKIP_THIS +#ifndef VPD3DRENDERER_HH +#define VPD3DRENDERER_HH #include +#ifndef DOXYGEN_SHOULD_SKIP_THIS #if (defined(VISP_HAVE_D3D9)) -#ifndef VPD3DRENDERER_HH -#define VPD3DRENDERER_HH - // 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 @@ -50,12 +49,14 @@ #include +BEGIN_VISP_NAMESPACE + /*! * \class vpD3DRenderer.h * * \brief Display under windows using Direct3D9. * Is used by vpDisplayD3D to do the drawing. - */ +*/ class VISP_EXPORT vpD3DRenderer : public vpWin32Renderer { IDirect3D9 *pD3D; @@ -189,5 +190,8 @@ class VISP_EXPORT vpD3DRenderer : public vpWin32Renderer unsigned int supPowerOf2(unsigned int n); }; #endif + +END_VISP_NAMESPACE + #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayD3D.h b/modules/gui/include/visp3/gui/vpDisplayD3D.h index b2cde98f8b..5e3b8bb001 100644 --- a/modules/gui/include/visp3/gui/vpDisplayD3D.h +++ b/modules/gui/include/visp3/gui/vpDisplayD3D.h @@ -31,15 +31,16 @@ * Windows 32 display using D3D */ -#include -#include -#if (defined(VISP_HAVE_D3D9)) - #ifndef VPDISPLAYD3D_HH #define VPDISPLAYD3D_HH +#include +#include +#if (defined(VISP_HAVE_D3D9)) #include +BEGIN_VISP_NAMESPACE + /*! * \class vpDisplayD3D * @@ -96,7 +97,7 @@ * #endif * } * \endcode - */ +*/ class VISP_EXPORT vpDisplayD3D : public vpDisplayWin32 { public: @@ -110,5 +111,7 @@ class VISP_EXPORT vpDisplayD3D : public vpDisplayWin32 vpScaleType type = SCALE_DEFAULT); }; + +END_VISP_NAMESPACE #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayFactory.h b/modules/gui/include/visp3/gui/vpDisplayFactory.h index 5413adc70e..508c3d6acb 100644 --- a/modules/gui/include/visp3/gui/vpDisplayFactory.h +++ b/modules/gui/include/visp3/gui/vpDisplayFactory.h @@ -36,15 +36,17 @@ #define vpDisplayFactory_h #include +#include #include #include #include #include #include +BEGIN_VISP_NAMESPACE /** * \ingroup group_gui_display - */ +*/ namespace vpDisplayFactory { /** @@ -140,5 +142,5 @@ vpDisplay *displayFactory(vpImage &I, vpDisplay::vpScaleType scale_type) #endif } } - +END_VISP_NAMESPACE #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayGDI.h b/modules/gui/include/visp3/gui/vpDisplayGDI.h index 83477dd799..cae289c385 100644 --- a/modules/gui/include/visp3/gui/vpDisplayGDI.h +++ b/modules/gui/include/visp3/gui/vpDisplayGDI.h @@ -35,16 +35,20 @@ * Bruno Renier * *****************************************************************************/ -#include -#include -#if (defined(VISP_HAVE_GDI)) #ifndef vpDisplayGDI_HH #define vpDisplayGDI_HH +#include +#include + +#if (defined(VISP_HAVE_GDI)) + #include +BEGIN_VISP_NAMESPACE + /*! * \class vpDisplayGDI * @@ -137,5 +141,6 @@ class VISP_EXPORT vpDisplayGDI : public vpDisplayWin32 vpScaleType type = SCALE_DEFAULT); }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayGTK.h b/modules/gui/include/visp3/gui/vpDisplayGTK.h index ea4b093bc7..de6ae7e297 100644 --- a/modules/gui/include/visp3/gui/vpDisplayGTK.h +++ b/modules/gui/include/visp3/gui/vpDisplayGTK.h @@ -35,11 +35,12 @@ #define vpDisplayGTK_h #include -#if (defined(VISP_HAVE_GTK)) - #include +#if (defined(VISP_HAVE_GTK)) #include +BEGIN_VISP_NAMESPACE + /*! * \file vpDisplayGTK.h * \brief Define the GTK console to display images. @@ -123,7 +124,7 @@ * #endif * } * \endcode - */ +*/ class VISP_EXPORT vpDisplayGTK : public vpDisplay { private: @@ -228,5 +229,6 @@ class VISP_EXPORT vpDisplayGTK : public vpDisplay Impl *m_impl; }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h index 30d552c592..b45b81c416 100644 --- a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h +++ b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h @@ -35,18 +35,20 @@ #define _vpDisplayOpenCV_h_ #include +#include #if defined(HAVE_OPENCV_HIGHGUI) #include -#include #include #include #include #include +BEGIN_VISP_NAMESPACE + /*! * \file vpDisplayOpenCV.h * \brief Define the OpenCV console to display images. @@ -131,7 +133,7 @@ * #endif * } * \endcode - */ +*/ class VISP_EXPORT vpDisplayOpenCV : public vpDisplay { private: @@ -262,5 +264,6 @@ class VISP_EXPORT vpDisplayOpenCV : public vpDisplay void overlay(std::function overlay_function, double opacity); }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayPCL.h b/modules/gui/include/visp3/gui/vpDisplayPCL.h index 0d97c9aa51..734f6cdc87 100644 --- a/modules/gui/include/visp3/gui/vpDisplayPCL.h +++ b/modules/gui/include/visp3/gui/vpDisplayPCL.h @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpDisplayPCL \ingroup group_gui_plotter @@ -80,7 +81,7 @@ class VISP_EXPORT vpDisplayPCL std::string m_window_name; pcl::visualization::PCLVisualizer::Ptr m_viewer; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayWin32.h b/modules/gui/include/visp3/gui/vpDisplayWin32.h index 958a3fbd96..490b24db82 100644 --- a/modules/gui/include/visp3/gui/vpDisplayWin32.h +++ b/modules/gui/include/visp3/gui/vpDisplayWin32.h @@ -31,16 +31,17 @@ * Windows 32 display base class */ -#include - -#if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) #ifndef vpDisplayWin32_hh #define vpDisplayWin32_hh +#include +#include + +#if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) + #include -#include #include // 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 @@ -51,10 +52,12 @@ #include #include +BEGIN_VISP_NAMESPACE + #ifndef DOXYGEN_SHOULD_SKIP_THIS /*! * Used to pass parameters to the window's thread. - */ +*/ struct threadParam { //! Pointer to the display associated with the window. @@ -86,7 +89,7 @@ struct threadParam * Windows 32 displays. * Uses calls to a renderer to do some display. * (i.e. all display methods are implemented in the renderer) - */ +*/ class VISP_EXPORT vpDisplayWin32 : public vpDisplay { protected: @@ -187,5 +190,7 @@ class VISP_EXPORT vpDisplayWin32 : public vpDisplay void waitForInit(); }; + +END_VISP_NAMESPACE #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayX.h b/modules/gui/include/visp3/gui/vpDisplayX.h index b7582422da..d94e9b728e 100644 --- a/modules/gui/include/visp3/gui/vpDisplayX.h +++ b/modules/gui/include/visp3/gui/vpDisplayX.h @@ -31,19 +31,22 @@ * Image display. */ +/*! + * \file vpDisplayX.h + * \brief Define the X11 console to display images. + */ + #ifndef vpDisplayX_h #define vpDisplayX_h #include -#ifdef VISP_HAVE_X11 #include + +#ifdef VISP_HAVE_X11 #include #include -/*! - * \file vpDisplayX.h - * \brief Define the X11 console to display images. - */ +BEGIN_VISP_NAMESPACE /*! * \class vpDisplayX @@ -123,7 +126,7 @@ * vpDisplay::getClick(I); * } * \endcode - */ +*/ class VISP_EXPORT vpDisplayX : public vpDisplay { // private: @@ -224,5 +227,6 @@ class VISP_EXPORT vpDisplayX : public vpDisplay Impl *m_impl; }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/gui/include/visp3/gui/vpGDIRenderer.h b/modules/gui/include/visp3/gui/vpGDIRenderer.h index ea195e1e9f..ad372d31e9 100644 --- a/modules/gui/include/visp3/gui/vpGDIRenderer.h +++ b/modules/gui/include/visp3/gui/vpGDIRenderer.h @@ -36,12 +36,14 @@ * *****************************************************************************/ -#include -#if (defined(VISP_HAVE_GDI)) #ifndef vpGDIRenderer_HH #define vpGDIRenderer_HH +#include + +#if (defined(VISP_HAVE_GDI)) + #ifndef DOXYGEN_SHOULD_SKIP_THIS // Include WinSock2.h before windows.h to ensure that winsock.h is not @@ -56,6 +58,8 @@ #include +BEGIN_VISP_NAMESPACE + class VISP_EXPORT vpGDIRenderer : public vpWin32Renderer { // the handle of the associated window @@ -130,6 +134,8 @@ class VISP_EXPORT vpGDIRenderer : public vpWin32Renderer // converst a vpImage into a HBITMAP . void convertROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height); }; + +END_VISP_NAMESPACE #endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpPclViewer.h b/modules/gui/include/visp3/gui/vpPclViewer.h index 37d51ec5d9..6122d9a005 100644 --- a/modules/gui/include/visp3/gui/vpPclViewer.h +++ b/modules/gui/include/visp3/gui/vpPclViewer.h @@ -48,6 +48,7 @@ // PCL #include +BEGIN_VISP_NAMESPACE /*! \class vpPclViewer \ingroup group_gui_plotter @@ -256,5 +257,6 @@ class VISP_EXPORT vpPclViewer 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.*/ }; +END_VISP_NAMESPACE #endif // #if defined(VISP_HAVE_PCL) #endif // _vpPclVisualizer_h_ diff --git a/modules/gui/include/visp3/gui/vpPlot.h b/modules/gui/include/visp3/gui/vpPlot.h index 1124417aeb..9a4661eb48 100644 --- a/modules/gui/include/visp3/gui/vpPlot.h +++ b/modules/gui/include/visp3/gui/vpPlot.h @@ -44,6 +44,9 @@ #include #if defined(VISP_HAVE_DISPLAY) + +BEGIN_VISP_NAMESPACE + /*! * \class vpPlot * \ingroup group_gui_plotter @@ -104,7 +107,7 @@ * #endif * } * \endcode - */ +*/ class VISP_EXPORT vpPlot { public: @@ -192,6 +195,8 @@ class VISP_EXPORT vpPlot void initNbGraph(unsigned int nbGraph); void displayGrid(); }; + +END_VISP_NAMESPACE #endif #endif diff --git a/modules/gui/include/visp3/gui/vpPlotCurve.h b/modules/gui/include/visp3/gui/vpPlotCurve.h index 51f2a868a8..f9ce399718 100644 --- a/modules/gui/include/visp3/gui/vpPlotCurve.h +++ b/modules/gui/include/visp3/gui/vpPlotCurve.h @@ -51,6 +51,8 @@ #if defined(VISP_HAVE_DISPLAY) +BEGIN_VISP_NAMESPACE + class vpPlotCurve { public: @@ -80,6 +82,8 @@ class vpPlotCurve void plotList(const vpImage &I, double xorg, double yorg, double zoomx, double zoomy); }; + +END_VISP_NAMESPACE #endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpPlotGraph.h b/modules/gui/include/visp3/gui/vpPlotGraph.h index 935e4c15f9..c2605fa4b3 100644 --- a/modules/gui/include/visp3/gui/vpPlotGraph.h +++ b/modules/gui/include/visp3/gui/vpPlotGraph.h @@ -33,11 +33,13 @@ * *****************************************************************************/ -#ifndef DOXYGEN_SHOULD_SKIP_THIS - #ifndef vpPlotGraph_H #define vpPlotGraph_H +#include + +#ifndef DOXYGEN_SHOULD_SKIP_THIS + #include #include @@ -52,6 +54,8 @@ #if defined(VISP_HAVE_DISPLAY) +BEGIN_VISP_NAMESPACE + class vpPlotGraph { public: @@ -216,6 +220,8 @@ class vpPlotGraph void setUnitZ(const std::string &unitz); }; + +END_VISP_NAMESPACE #endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpProjectionDisplay.h b/modules/gui/include/visp3/gui/vpProjectionDisplay.h index 77adced801..84240bf39b 100644 --- a/modules/gui/include/visp3/gui/vpProjectionDisplay.h +++ b/modules/gui/include/visp3/gui/vpProjectionDisplay.h @@ -57,6 +57,8 @@ #include +BEGIN_VISP_NAMESPACE + /*! \class vpProjectionDisplay \ingroup group_gui_projection @@ -95,18 +97,18 @@ class VISP_EXPORT vpProjectionDisplay vpProjectionDisplay() : Icam(), Iext(), #if defined(VISP_HAVE_DISPLAY) - dIcam(), dIext(), + dIcam(), dIext(), #endif - listFp(), o(), x(), y(), z(), traj() + listFp(), o(), x(), y(), z(), traj() { init(); } explicit vpProjectionDisplay(int select) : Icam(), Iext(), #if defined(VISP_HAVE_DISPLAY) - dIcam(), dIext(), + dIcam(), dIext(), #endif - listFp(), o(), x(), y(), z(), traj() + listFp(), o(), x(), y(), z(), traj() { init(select); } @@ -127,11 +129,7 @@ class VISP_EXPORT vpProjectionDisplay vpMatrix traj; }; + +END_VISP_NAMESPACE #endif #endif - -/* - * Local variables: - * c-basic-offset: 2 - * End: - */ diff --git a/modules/gui/include/visp3/gui/vpWin32API.h b/modules/gui/include/visp3/gui/vpWin32API.h index fa11987a69..060a56bac0 100644 --- a/modules/gui/include/visp3/gui/vpWin32API.h +++ b/modules/gui/include/visp3/gui/vpWin32API.h @@ -49,6 +49,8 @@ #include #include +BEGIN_VISP_NAMESPACE + DWORD vpProcessErrors(const std::string &api_name); void vpSelectObject(HWND hWnd, HDC hDC, HDC hDCMem, HGDIOBJ h); void vpPrepareImageWithPen(CRITICAL_SECTION *CriticalSection, HWND hWnd, HBITMAP bmp, COLORREF color, @@ -63,5 +65,7 @@ BOOL vpBitBlt(HDC hdcDest, int nXDest, int nYDest, int nWidth, int nHeight, HDC BOOL vpInvalidateRect(HWND hWnd, const RECT *lpRect, BOOL bErase); COLORREF vpSetPixel(HDC hdc, int X, int Y, COLORREF crColor); HBITMAP vpCreateBitmap(int nWidth, int nHeight, UINT cPlanes, UINT cBitsPerPel, const VOID *lpvBits); + +END_VISP_NAMESPACE #endif #endif diff --git a/modules/gui/include/visp3/gui/vpWin32Renderer.h b/modules/gui/include/visp3/gui/vpWin32Renderer.h index b169c57b4f..70f6cac00b 100644 --- a/modules/gui/include/visp3/gui/vpWin32Renderer.h +++ b/modules/gui/include/visp3/gui/vpWin32Renderer.h @@ -36,13 +36,14 @@ * *****************************************************************************/ -#include - -#if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) #ifndef vpWin32Renderer_HH #define vpWin32Renderer_HH +#include + +#if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) + #ifndef DOXYGEN_SHOULD_SKIP_THIS #include @@ -53,6 +54,8 @@ #include #include +BEGIN_VISP_NAMESPACE + class VISP_EXPORT vpWin32Renderer { @@ -63,9 +66,9 @@ class VISP_EXPORT vpWin32Renderer unsigned int m_rscale; public: - vpWin32Renderer() : m_rwidth(0), m_rheight(0), m_rscale(1){}; + vpWin32Renderer() : m_rwidth(0), m_rheight(0), m_rscale(1) { }; //! Destructor. - virtual ~vpWin32Renderer(){}; + virtual ~vpWin32Renderer() { }; //! Inits the display . virtual bool init(HWND hWnd, unsigned int w, unsigned int h) = 0; @@ -171,6 +174,8 @@ class VISP_EXPORT vpWin32Renderer virtual void getImage(vpImage &I) = 0; }; + +END_VISP_NAMESPACE #endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpWin32Window.h b/modules/gui/include/visp3/gui/vpWin32Window.h index 1e97ad6e0f..8cc48ad774 100644 --- a/modules/gui/include/visp3/gui/vpWin32Window.h +++ b/modules/gui/include/visp3/gui/vpWin32Window.h @@ -37,11 +37,12 @@ * *****************************************************************************/ +#ifndef vpWin32Window_HH +#define vpWin32Window_HH + #include #if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) -#ifndef vpWin32Window_HH -#define vpWin32Window_HH #ifndef DOXYGEN_SHOULD_SKIP_THIS @@ -54,6 +55,8 @@ #include #include +BEGIN_VISP_NAMESPACE + // ViSP-defined messages for window's callback function #define vpWM_GETCLICK WM_USER + 1 #define vpWM_DISPLAY WM_USER + 2 @@ -134,6 +137,7 @@ class VISP_EXPORT vpWin32Window friend LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam); }; +END_VISP_NAMESPACE #endif #endif #endif diff --git a/modules/gui/src/display/vpDisplayGTK.cpp b/modules/gui/src/display/vpDisplayGTK.cpp index 8ce48e314b..677f2c260f 100644 --- a/modules/gui/src/display/vpDisplayGTK.cpp +++ b/modules/gui/src/display/vpDisplayGTK.cpp @@ -68,6 +68,8 @@ #include #include +BEGIN_VISP_NAMESPACE + class vpDisplayGTK::Impl { public: @@ -1588,7 +1590,9 @@ unsigned int vpDisplayGTK::getScreenHeight() return height; } +END_VISP_NAMESPACE + #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_gui.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 73f3a52d91..e6e850bc47 100644 --- a/modules/gui/src/display/vpDisplayOpenCV.cpp +++ b/modules/gui/src/display/vpDisplayOpenCV.cpp @@ -75,6 +75,8 @@ #include #endif +BEGIN_VISP_NAMESPACE + std::vector vpDisplayOpenCV::m_listTitles = std::vector(); unsigned int vpDisplayOpenCV::m_nbWindows = 0; @@ -1789,7 +1791,9 @@ void vpDisplayOpenCV::overlay(std::function overlay_function, d } } +END_VISP_NAMESPACE + #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_gui.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 8f4517c4a0..ee979b50be 100644 --- a/modules/gui/src/display/vpDisplayX.cpp +++ b/modules/gui/src/display/vpDisplayX.cpp @@ -66,6 +66,8 @@ #include #include +BEGIN_VISP_NAMESPACE + // Work around to use this class with Eigen3 #ifdef Success #undef Success // See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=253 @@ -2660,7 +2662,9 @@ bool vpDisplayX::getPointerPosition(vpImagePoint &ip) return ret; } +END_VISP_NAMESPACE + #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_gui.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 0ab06eb0e1..e8a1fc1134 100644 --- a/modules/gui/src/display/windows/vpD3DRenderer.cpp +++ b/modules/gui/src/display/windows/vpD3DRenderer.cpp @@ -35,17 +35,20 @@ * Bruno Renier * *****************************************************************************/ -#ifndef DOXYGEN_SHOULD_SKIP_THIS #include #include + #if (defined(_WIN32) & defined(VISP_HAVE_D3D9)) +#ifndef DOXYGEN_SHOULD_SKIP_THIS #include #include #include +BEGIN_VISP_NAMESPACE + /* Be careful, when using : @@ -1190,8 +1193,10 @@ void vpD3DRenderer::getImage(vpImage &I) } } +END_VISP_NAMESPACE + #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_gui.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 2d13fb9151..6932f1b755 100644 --- a/modules/gui/src/display/windows/vpDisplayD3D.cpp +++ b/modules/gui/src/display/windows/vpDisplayD3D.cpp @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \brief Basic constructor. */ @@ -188,7 +189,9 @@ vpDisplayD3D::vpDisplayD3D(vpImage &I, int winx, int winy, const init(I, winx, winy, title); } +END_VISP_NAMESPACE + #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_gui.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 b96086d321..0110450efc 100644 --- a/modules/gui/src/display/windows/vpDisplayGDI.cpp +++ b/modules/gui/src/display/windows/vpDisplayGDI.cpp @@ -46,6 +46,8 @@ #include +BEGIN_VISP_NAMESPACE + // A vpDisplayGDI is just a vpDisplayWin32 which uses a vpGDIRenderer to do // the drawing. @@ -188,7 +190,9 @@ vpDisplayGDI::vpDisplayGDI(vpImage &I, int winx, int winy, const init(I, winx, winy, title); } +END_VISP_NAMESPACE + #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_gui.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 551fe65770..16616395fb 100644 --- a/modules/gui/src/display/windows/vpDisplayWin32.cpp +++ b/modules/gui/src/display/windows/vpDisplayWin32.cpp @@ -43,6 +43,8 @@ #include #include +BEGIN_VISP_NAMESPACE + const int vpDisplayWin32::MAX_INIT_DELAY = 5000; /*! @@ -919,7 +921,10 @@ unsigned int vpDisplayWin32::getScreenHeight() getScreenSize(width, height); return height; } + +END_VISP_NAMESPACE + #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_gui.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 cea70d073f..3610f4e284 100644 --- a/modules/gui/src/display/windows/vpGDIRenderer.cpp +++ b/modules/gui/src/display/windows/vpGDIRenderer.cpp @@ -44,6 +44,8 @@ #include +BEGIN_VISP_NAMESPACE + /*! Constructor. */ @@ -1027,8 +1029,10 @@ void vpGDIRenderer::getImage(vpImage &I) delete[] imBuffer; } + +END_VISP_NAMESPACE #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_gui.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 ca65e445bd..5e3cdf8adf 100644 --- a/modules/gui/src/display/windows/vpWin32API.cpp +++ b/modules/gui/src/display/windows/vpWin32API.cpp @@ -42,6 +42,9 @@ #if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) #include #include + +BEGIN_VISP_NAMESPACE + DWORD vpProcessErrors(const std::string &api_name) { LPVOID lpMsgBuf; @@ -135,7 +138,9 @@ HBITMAP vpCreateBitmap(int nWidth, int nHeight, UINT cPlanes, UINT cBitsPerPel, return ret; } +END_VISP_NAMESPACE + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpWin32API.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.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 2dd7d3c0d4..34aca6be34 100644 --- a/modules/gui/src/display/windows/vpWin32Window.cpp +++ b/modules/gui/src/display/windows/vpWin32Window.cpp @@ -48,6 +48,8 @@ #include +BEGIN_VISP_NAMESPACE + // Should be already defined ... #ifndef GET_X_LPARAM #define GET_X_LPARAM(lp) ((int)(short)LOWORD(lp)) @@ -311,8 +313,10 @@ void vpWin32Window::initWindow(const char *title, int posx, int posy, unsigned i } } +END_VISP_NAMESPACE + #endif #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpWin32Window.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpWin32Window.cpp.o) has no symbols void dummy_vpWin32Window() { }; #endif diff --git a/modules/gui/src/forward-projection/vpProjectionDisplay.cpp b/modules/gui/src/forward-projection/vpProjectionDisplay.cpp index 39d0db1553..266c3895bf 100644 --- a/modules/gui/src/forward-projection/vpProjectionDisplay.cpp +++ b/modules/gui/src/forward-projection/vpProjectionDisplay.cpp @@ -57,6 +57,8 @@ //#include +BEGIN_VISP_NAMESPACE + void vpProjectionDisplay::insert(vpForwardProjection &fp) { // vpForwardProjection *f ; @@ -88,7 +90,7 @@ void vpProjectionDisplay::init(const int select) init(); } -void vpProjectionDisplay::close() {} +void vpProjectionDisplay::close() { } void vpProjectionDisplay::display(vpImage &I, const vpHomogeneousMatrix &cextMo, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &color, @@ -145,8 +147,10 @@ void vpProjectionDisplay::displayCamera(vpImage &I, const vpHomog vpDisplay::displayArrow(I, ipo, ip, vpColor::blue, 4 + thickness, 2 + thickness, thickness); } +END_VISP_NAMESPACE + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpProjectionDisplay.cpp.o) +// Work around to avoid warning: libvisp_gui.a(vpProjectionDisplay.cpp.o) // has no symbols -void dummy_vpProjectionDisplay(){}; +void dummy_vpProjectionDisplay() { }; #endif diff --git a/modules/gui/src/plot/vpPlot.cpp b/modules/gui/src/plot/vpPlot.cpp index da074c1a12..cf6cd58779 100644 --- a/modules/gui/src/plot/vpPlot.cpp +++ b/modules/gui/src/plot/vpPlot.cpp @@ -49,6 +49,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! Default constructor. @@ -727,7 +729,9 @@ void vpPlot::saveData(unsigned int graphNum, const std::string &dataFile, const fichier.close(); } +END_VISP_NAMESPACE + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpPlot.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpPlot.cpp.o) has no symbols void dummy_vpPlot() { }; #endif diff --git a/modules/gui/src/plot/vpPlotCurve.cpp b/modules/gui/src/plot/vpPlotCurve.cpp index ea4c221f73..0690f9eb33 100644 --- a/modules/gui/src/plot/vpPlotCurve.cpp +++ b/modules/gui/src/plot/vpPlotCurve.cpp @@ -44,6 +44,9 @@ #include #if defined(VISP_HAVE_DISPLAY) + +BEGIN_VISP_NAMESPACE + vpPlotCurve::vpPlotCurve() : color(vpColor::red), curveStyle(point), thickness(1), nbPoint(0), lastPoint(), pointListx(), pointListy(), pointListz(), legend(), xmin(0), xmax(0), ymin(0), ymax(0) @@ -114,8 +117,10 @@ void vpPlotCurve::plotList(const vpImage &I, double xorg, double } } +END_VISP_NAMESPACE + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpPlotCurve.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.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 40f68ff083..607ad5250e 100644 --- a/modules/gui/src/plot/vpPlotGraph.cpp +++ b/modules/gui/src/plot/vpPlotGraph.cpp @@ -54,6 +54,8 @@ #if defined(VISP_HAVE_DISPLAY) +BEGIN_VISP_NAMESPACE + int laFonctionSansNom(double delta); void getGrid3DPoint(double pente, vpImagePoint &iPunit, vpImagePoint &ip1, vpImagePoint &ip2, vpImagePoint &ip3); @@ -1338,8 +1340,10 @@ vpHomogeneousMatrix vpPlotGraph::navigation(const vpImage &I, boo return mov; } +END_VISP_NAMESPACE + #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_gui.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 index a28a934eba..b21575b4cc 100644 --- a/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp +++ b/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp @@ -37,6 +37,7 @@ #if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) +BEGIN_VISP_NAMESPACE std::vector vpColorBlindFriendlyPalette::s_paletteNames = { "black" , @@ -193,20 +194,21 @@ std::string vpColorBlindFriendlyPalette::to_string(const vpColorBlindFriendlyPal return nameColor; } -std::ostream &operator<<(std::ostream &os, const vpColorBlindFriendlyPalette &color) +END_VISP_NAMESPACE + +std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpColorBlindFriendlyPalette &color) { os << color.to_string(); return os; } -std::istream &operator>>(std::istream &is, vpColorBlindFriendlyPalette &color) +std::istream &operator>>(std::istream &is, VISP_NAMESPACE_ADDRESSING vpColorBlindFriendlyPalette &color) { std::string nameColor; is >> nameColor; color.set_fromString(nameColor); return is; } - #else void dummy_vpColorBlindFriendlyPalette() { } #endif diff --git a/modules/gui/src/pointcloud/vpDisplayPCL.cpp b/modules/gui/src/pointcloud/vpDisplayPCL.cpp index 64a2e5bbbc..1dca89965f 100644 --- a/modules/gui/src/pointcloud/vpDisplayPCL.cpp +++ b/modules/gui/src/pointcloud/vpDisplayPCL.cpp @@ -37,6 +37,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * Default constructor. * By default, viewer size is set to 640 x 480. @@ -226,7 +227,7 @@ void vpDisplayPCL::setVerbose(bool verbose) { m_verbose = verbose; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_gui.a(vpDisplayPCL.cpp.o) has no symbols void dummy_vpDisplayPCL() { }; diff --git a/modules/gui/src/pointcloud/vpPclViewer.cpp b/modules/gui/src/pointcloud/vpPclViewer.cpp index 89794b04f8..94adb3c48a 100644 --- a/modules/gui/src/pointcloud/vpPclViewer.cpp +++ b/modules/gui/src/pointcloud/vpPclViewer.cpp @@ -44,6 +44,7 @@ #include #include +BEGIN_VISP_NAMESPACE const std::vector gcolor = { vpColorBlindFriendlyPalette::Palette::Green, vpColorBlindFriendlyPalette::Palette::Vermillon,vpColorBlindFriendlyPalette::Palette::Blue, vpColorBlindFriendlyPalette::Palette::Black, vpColorBlindFriendlyPalette::Palette::Orange, vpColorBlindFriendlyPalette::Palette::Purple, vpColorBlindFriendlyPalette::Palette::Yellow }; @@ -485,7 +486,7 @@ void vpPclViewer::threadUpdateSurfaceOriginalColor(const pclPointCloudPointXYZRG m_vpmutex[id]->unlock(); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no symbols void dummy_vpPCLPointCLoudVisualization() { }; diff --git a/modules/gui/test/display-with-dataset/testClick.cpp b/modules/gui/test/display-with-dataset/testClick.cpp index 4417c1cd1f..48c0ce5d0e 100644 --- a/modules/gui/test/display-with-dataset/testClick.cpp +++ b/modules/gui/test/display-with-dataset/testClick.cpp @@ -64,6 +64,10 @@ // List of allowed command line options #define GETOPTARGS "i:hlt:dc" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + typedef enum { vpX11, vpGTK, vpGDI, vpD3D, vpCV } vpDisplayType; void usage(const char *name, const char *badparam, std::string ipath, vpDisplayType &dtype); @@ -89,7 +93,7 @@ SYNOPSIS\n\ %s [-i ] \n\ [-t ] [-l] [-c] [-d] [-h]\n\ ", - name); +name); std::string display; switch (dtype) { @@ -185,13 +189,17 @@ bool getOptions(int argc, const char **argv, std::string &ipath, vpDisplayType & // Parse the display type option if (sDisplayType.compare("X11") == 0) { dtype = vpX11; - } else if (sDisplayType.compare("GTK") == 0) { + } + else if (sDisplayType.compare("GTK") == 0) { dtype = vpGTK; - } else if (sDisplayType.compare("GDI") == 0) { + } + else if (sDisplayType.compare("GDI") == 0) { dtype = vpGDI; - } else if (sDisplayType.compare("D3D") == 0) { + } + else if (sDisplayType.compare("D3D") == 0) { dtype = vpD3D; - } else if (sDisplayType.compare("CV") == 0) { + } + else if (sDisplayType.compare("CV") == 0) { dtype = vpCV; } @@ -292,9 +300,9 @@ int main(int argc, const char **argv) std::cout << " No display is available\n"; } return EXIT_FAILURE; - } + } - // Get the option values + // Get the option values if (!opt_ipath.empty()) ipath = opt_ipath; @@ -304,8 +312,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; } } @@ -314,9 +322,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_dtype); 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; } @@ -440,11 +448,12 @@ int main(int argc, const char **argv) } } delete display; - } catch (...) { +} + catch (...) { vpERROR_TRACE("Error while displaying the image"); return EXIT_FAILURE; } -} + } #else int main() { vpERROR_TRACE("You do not have display functionalities..."); } diff --git a/modules/gui/test/display-with-dataset/testDisplayScaled.cpp b/modules/gui/test/display-with-dataset/testDisplayScaled.cpp index 2c7457371a..687fed7a53 100644 --- a/modules/gui/test/display-with-dataset/testDisplayScaled.cpp +++ b/modules/gui/test/display-with-dataset/testDisplayScaled.cpp @@ -35,6 +35,7 @@ #include +#include #include #include #include @@ -44,6 +45,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + template bool test(const std::string &display, vpImage &I, unsigned int scale, bool click) { bool success = true; @@ -66,19 +71,23 @@ template bool test(const std::string &display, vpImage &I, #ifdef VISP_HAVE_GDI d = new vpDisplayGDI; #endif - } else if (display == "GTK") { + } + else if (display == "GTK") { #ifdef VISP_HAVE_GTK d = new vpDisplayGTK; #endif - } else if (display == "X") { + } + else if (display == "X") { #ifdef VISP_HAVE_X11 d = new vpDisplayX; #endif - } else if (display == "OpenCV") { + } + else if (display == "OpenCV") { #ifdef HAVE_OPENCV_HIGHGUI d = new vpDisplayOpenCV; #endif - } else if (display == "D3D9") { + } + else if (display == "D3D9") { #ifdef VISP_HAVE_D3D9 d = new vpDisplayD3D; #endif @@ -145,10 +154,12 @@ template bool test(const std::string &display, vpImage &I, #endif vpImageIo::write(Idiff, ss.str()); - } else { + } + else { std::cout << " ++ Test width scale= " << scale << " type= " << itype << ": succeed" << std::endl; } - } else { + } + else { itype = "rgba"; vpImage Iinsert = I; vpImage Isampled; // vpRGBa necessary @@ -197,7 +208,8 @@ template bool test(const std::string &display, vpImage &I, vpImageIo::write(Idiff, ss.str()); - } else { + } + else { std::cout << " ++ Test width scale= " << scale << " type= " << itype << ": succeed" << std::endl; } } @@ -277,10 +289,10 @@ int main(int argc, const char *argv[]) std::cout << "\nUsage: " << argv[0] << " [-i ] [-c] [-d] [--help]\n" << std::endl; std::cout << "\nOptions: " << std::endl; std::cout << " -i : set image input path.\n" - << " From this path read \"Klimt/Klimt.pgm\" image.\n" - << " Setting the VISP_INPUT_IMAGE_PATH environment\n" - << " variable produces the same behaviour than using\n" - << " this option." << std::endl; + << " From this path read \"Klimt/Klimt.pgm\" image.\n" + << " Setting the VISP_INPUT_IMAGE_PATH environment\n" + << " variable produces the same behaviour than using\n" + << " this option." << std::endl; std::cout << " -c : disable mouse click" << std::endl; std::cout << " -d : disable display" << std::endl; std::cout << " -h, --help : print this help\n" << std::endl; diff --git a/modules/gui/test/display-with-dataset/testMouseEvent.cpp b/modules/gui/test/display-with-dataset/testMouseEvent.cpp index 863ab1c87d..dec8c89a33 100644 --- a/modules/gui/test/display-with-dataset/testMouseEvent.cpp +++ b/modules/gui/test/display-with-dataset/testMouseEvent.cpp @@ -77,7 +77,13 @@ // List of allowed command line options #define GETOPTARGS "cdi:Lp:ht:f:l:s:w" -typedef enum { + +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + +typedef enum +{ vpX11, vpGTK, vpGDI, @@ -238,11 +244,14 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &pp // Parse the display type option if (sDisplayType.compare("X11") == 0) { dtype = vpX11; - } else if (sDisplayType.compare("GTK") == 0) { + } + else if (sDisplayType.compare("GTK") == 0) { dtype = vpGTK; - } else if (sDisplayType.compare("GDI") == 0) { + } + else if (sDisplayType.compare("GDI") == 0) { dtype = vpGDI; - } else if (sDisplayType.compare("D3D") == 0) { + } + else if (sDisplayType.compare("D3D") == 0) { dtype = vpD3D; } @@ -363,7 +372,7 @@ int main(int argc, const char **argv) std::cout << " No display is available\n"; } return EXIT_FAILURE; - } +} if (!opt_display) opt_click_blocking = false; // turn off the waiting @@ -378,8 +387,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; } } @@ -388,11 +397,11 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_ppath, opt_first, opt_last, opt_step, opt_dtype); 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 - << " Use -p option if you want to " << std::endl - << " use personal images." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << " Use -p option if you want to " << std::endl + << " use personal images." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -414,7 +423,8 @@ int main(int argc, const char **argv) s.setf(std::ios::right, std::ios::adjustfield); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; @@ -422,12 +432,13 @@ int main(int argc, const char **argv) // Read image named "filename" and put the bitmap in I try { vpImageIo::read(I, filename); - } catch (...) { + } + catch (...) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot read " << filename << std::endl; std::cerr << " Check your -i " << ipath << " option, " << std::endl - << " or your -p " << opt_ppath << " option " << std::endl - << " or VISP_INPUT_IMAGE_PATH environment variable" << std::endl; + << " or your -p " << opt_ppath << " option " << std::endl + << " or VISP_INPUT_IMAGE_PATH environment variable" << std::endl; return EXIT_FAILURE; } // Create a display for the image @@ -490,7 +501,8 @@ int main(int argc, const char **argv) // display variable. vpDisplay::display(I); vpDisplay::flush(I); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error while displaying the image"); delete display; return EXIT_FAILURE; @@ -507,7 +519,8 @@ int main(int argc, const char **argv) s.str(""); s << "image." << std::setw(4) << std::setfill('0') << iter << "." << ext; filename = vpIoTools::createFilePath(dirname, s.str()); - } else { + } + else { snprintf(cfilename, FILENAME_MAX, opt_ppath.c_str(), iter); filename = cfilename; } @@ -548,11 +561,13 @@ int main(int argc, const char **argv) } } vpTime::wait(tms, 1000); - } else { - // Synchronise the loop to 40 ms + } + else { + // Synchronise the loop to 40 ms vpTime::wait(tms, 40); } - } catch (...) { + } + catch (...) { delete display; return EXIT_FAILURE; } diff --git a/modules/gui/test/display-with-dataset/testVideoDevice.cpp b/modules/gui/test/display-with-dataset/testVideoDevice.cpp index e5ed80be5c..45429ff34b 100644 --- a/modules/gui/test/display-with-dataset/testVideoDevice.cpp +++ b/modules/gui/test/display-with-dataset/testVideoDevice.cpp @@ -66,6 +66,10 @@ // List of allowed command line options #define GETOPTARGS "i:hlt:dc" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + typedef enum { vpX11, vpGTK, vpGDI, vpD3D, vpCV } vpDisplayType; void usage(const char *name, const char *badparam, std::string ipath, vpDisplayType &dtype); @@ -91,7 +95,7 @@ SYNOPSIS\n\ %s [-i ] \n\ [-t ] [-l] [-c] [-d] [-h]\n\ ", - name); +name); std::string display; switch (dtype) { @@ -183,13 +187,17 @@ bool getOptions(int argc, const char **argv, std::string &ipath, vpDisplayType & // Parse the display type option if (sDisplayType.compare("X11") == 0) { dtype = vpX11; - } else if (sDisplayType.compare("GTK") == 0) { + } + else if (sDisplayType.compare("GTK") == 0) { dtype = vpGTK; - } else if (sDisplayType.compare("GDI") == 0) { + } + else if (sDisplayType.compare("GDI") == 0) { dtype = vpGDI; - } else if (sDisplayType.compare("D3D") == 0) { + } + else if (sDisplayType.compare("D3D") == 0) { dtype = vpD3D; - } else if (sDisplayType.compare("CV") == 0) { + } + else if (sDisplayType.compare("CV") == 0) { dtype = vpCV; } @@ -290,9 +298,9 @@ int main(int argc, const char **argv) std::cout << " No display is available\n"; } return EXIT_FAILURE; - } + } - // Get the option values + // Get the option values if (!opt_ipath.empty()) ipath = opt_ipath; @@ -302,8 +310,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; } } @@ -312,9 +320,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_dtype); 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; } @@ -469,11 +477,12 @@ int main(int argc, const char **argv) vpDisplay::getClick(Irgba); } delete display; - } catch (...) { +} + catch (...) { vpERROR_TRACE("Error while displaying the image"); return EXIT_FAILURE; } -} + } #else int main() { vpERROR_TRACE("You do not have display functionalities..."); } diff --git a/modules/gui/test/display/testDisplayPolygonLines.cpp b/modules/gui/test/display/testDisplayPolygonLines.cpp index 6b1d96c849..d19cc90001 100644 --- a/modules/gui/test/display/testDisplayPolygonLines.cpp +++ b/modules/gui/test/display/testDisplayPolygonLines.cpp @@ -55,6 +55,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); diff --git a/modules/gui/test/display/testDisplayRoi.cpp b/modules/gui/test/display/testDisplayRoi.cpp index 78d780cf7a..052fe857ea 100644 --- a/modules/gui/test/display/testDisplayRoi.cpp +++ b/modules/gui/test/display/testDisplayRoi.cpp @@ -54,6 +54,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -203,10 +207,10 @@ int main(int argc, const char **argv) std::cout << "A click in the image to exit..." << std::endl; vpDisplay::getClick(C); } - } + } #else (void)argc; (void)argv; #endif return EXIT_SUCCESS; -} + } diff --git a/modules/gui/test/display/testDisplays.cpp b/modules/gui/test/display/testDisplays.cpp index b277a39edf..75b81698ac 100644 --- a/modules/gui/test/display/testDisplays.cpp +++ b/modules/gui/test/display/testDisplays.cpp @@ -66,6 +66,10 @@ // List of allowed command line options #define GETOPTARGS "hldc" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. @@ -415,16 +419,16 @@ int main(int argc, const char **argv) std::cout << " No display is available\n"; } return EXIT_FAILURE; - } + } - // Create a color image for each display. + // Create a color image for each display. runTest(opt_display, opt_click_allowed); // Create a grayscale image for each display. runTest(opt_display, opt_click_allowed); return EXIT_SUCCESS; - } +} catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; return EXIT_FAILURE; diff --git a/modules/gui/test/display/testVideoDeviceDual.cpp b/modules/gui/test/display/testVideoDeviceDual.cpp index ea2a4e710d..5fa5dd5a6c 100644 --- a/modules/gui/test/display/testVideoDeviceDual.cpp +++ b/modules/gui/test/display/testVideoDeviceDual.cpp @@ -57,6 +57,10 @@ // List of allowed command line options #define GETOPTARGS "hlt:dc" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + typedef enum { vpX11, vpGTK, vpGDI, vpD3D, vpCV } vpDisplayType; void usage(const char *name, const char *badparam, vpDisplayType &dtype); @@ -79,7 +83,7 @@ Test to open video devices or display.\n\ SYNOPSIS\n\ %s [-t ] [-l] [-c] [-d] [-h]\n\ ", - name); +name); std::string display; switch (dtype) { @@ -158,13 +162,17 @@ bool getOptions(int argc, const char **argv, vpDisplayType &dtype, bool &list, b // Parse the display type option if (sDisplayType.compare("X11") == 0) { dtype = vpX11; - } else if (sDisplayType.compare("GTK") == 0) { + } + else if (sDisplayType.compare("GTK") == 0) { dtype = vpGTK; - } else if (sDisplayType.compare("GDI") == 0) { + } + else if (sDisplayType.compare("GDI") == 0) { dtype = vpGDI; - } else if (sDisplayType.compare("D3D") == 0) { + } + else if (sDisplayType.compare("D3D") == 0) { dtype = vpD3D; - } else if (sDisplayType.compare("CV") == 0) { + } + else if (sDisplayType.compare("CV") == 0) { dtype = vpCV; } @@ -253,9 +261,9 @@ int main(int argc, const char **argv) std::cout << " No display is available\n"; } return EXIT_FAILURE; - } + } - // Create 2 images + // Create 2 images vpImage I1(240, 320), I2(240, 320); I1 = 128; I2 = 255; @@ -344,11 +352,12 @@ int main(int argc, const char **argv) delete d1; delete d2; return EXIT_SUCCESS; - } catch (const vpException &e) { +} + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } -} + } #else int main() { vpERROR_TRACE("You do not have display functionalities..."); } diff --git a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h index d006d836c4..171d5ec6fd 100644 --- a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h +++ b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h @@ -51,6 +51,8 @@ #include #endif +BEGIN_VISP_NAMESPACE + /** * \ingroup group_hough_transform * \brief Class that permits to detect 2D circles in a image using @@ -58,7 +60,7 @@ * Please find more information on the algorithm * [here](https://theailearner.com/tag/hough-gradient-method-opencv/) * - */ +*/ class VISP_EXPORT vpCircleHoughTransform { public: @@ -1281,4 +1283,7 @@ class VISP_EXPORT vpCircleHoughTransform std::vector m_finalCircleVotes; /*!< Number of votes for the final circles.*/ std::vector > > m_finalCirclesVotingPoints; /*!< Points that voted for each final circle.*/ }; + +END_VISP_NAMESPACE + #endif diff --git a/modules/imgproc/include/visp3/imgproc/vpContours.h b/modules/imgproc/include/visp3/imgproc/vpContours.h index 0f1c1783f9..fa60f10c9e 100644 --- a/modules/imgproc/include/visp3/imgproc/vpContours.h +++ b/modules/imgproc/include/visp3/imgproc/vpContours.h @@ -74,9 +74,9 @@ #include #include - -namespace +namespace VISP_NAMESPACE_NAME { + /*! * Possible directions to find a contour. */ @@ -154,7 +154,7 @@ struct vpDirection { vpDirection direction; int directionSize = static_cast(LAST_DIRECTION); - int idx = vpMath::modulo(static_cast(m_direction) - 1, directionSize); + int idx = VISP_NAMESPACE_ADDRESSING vpMath::modulo(static_cast(m_direction) - 1, directionSize); direction.m_direction = vpDirectionType(idx); return direction; @@ -166,23 +166,20 @@ struct vpDirection * @param point Current point coordinate. * @return Next point coordinate along the contour. */ - vpImagePoint active(const vpImage &I, const vpImagePoint &point) + VISP_NAMESPACE_ADDRESSING vpImagePoint active(const VISP_NAMESPACE_ADDRESSING vpImage &I, const VISP_NAMESPACE_ADDRESSING vpImagePoint &point) { int yy = static_cast(point.get_i() + m_diry[static_cast(m_direction)]); int xx = static_cast(point.get_j() + m_dirx[static_cast(m_direction)]); if ((xx < 0) || (xx >= static_cast(I.getWidth())) || (yy < 0) || (yy >= static_cast(I.getHeight()))) { - return vpImagePoint(-1, -1); + return VISP_NAMESPACE_ADDRESSING vpImagePoint(-1, -1); } int pixel = I[yy][xx]; - return pixel != 0 ? vpImagePoint(yy, xx) : vpImagePoint(-1, -1); + return pixel != 0 ? VISP_NAMESPACE_ADDRESSING vpImagePoint(yy, xx) : VISP_NAMESPACE_ADDRESSING vpImagePoint(-1, -1); } }; -} // namespace -namespace vp -{ /*! * Type of contour. */ @@ -215,12 +212,12 @@ struct vpContour //! Parent contour vpContour *m_parent; //! Vector of points belonging to the contour - std::vector m_points; + std::vector m_points; /*! * Default constructor. */ - vpContour() : m_children(), m_contourType(vp::CONTOUR_HOLE), m_parent(nullptr), m_points() { } + vpContour() : m_children(), m_contourType(CONTOUR_HOLE), m_parent(nullptr), m_points() { } /*! * Constructor of a given contour type. @@ -316,7 +313,7 @@ struct vpContour * \param contours : Detected contours. * \param grayValue : Drawing grayscale color. */ -VISP_EXPORT void drawContours(vpImage &I, const std::vector > &contours, +VISP_EXPORT void drawContours(VISP_NAMESPACE_ADDRESSING vpImage &I, const std::vector > &contours, unsigned char grayValue = 255); /*! @@ -328,8 +325,8 @@ VISP_EXPORT void drawContours(vpImage &I, const std::vector &I, const std::vector > &contours, - const vpColor &color); +VISP_EXPORT void drawContours(VISP_NAMESPACE_ADDRESSING vpImage &I, const std::vector > &contours, + const VISP_NAMESPACE_ADDRESSING vpColor &color); /*! * \ingroup group_imgproc_contours @@ -342,9 +339,10 @@ VISP_EXPORT void drawContours(vpImage &I, const std::vector &I_original, vpContour &contours, - std::vector > &contourPts, - const vpContourRetrievalType &retrievalMode = vp::CONTOUR_RETR_TREE); -} // namespace vp +VISP_EXPORT void findContours(const VISP_NAMESPACE_ADDRESSING vpImage &I_original, vpContour &contours, + std::vector > &contourPts, + const vpContourRetrievalType &retrievalMode = CONTOUR_RETR_TREE); + +} // namespace #endif diff --git a/modules/imgproc/include/visp3/imgproc/vpImgproc.h b/modules/imgproc/include/visp3/imgproc/vpImgproc.h index 45997739fe..c476fc4608 100644 --- a/modules/imgproc/include/visp3/imgproc/vpImgproc.h +++ b/modules/imgproc/include/visp3/imgproc/vpImgproc.h @@ -45,10 +45,11 @@ #include #include +namespace VISP_NAMESPACE_NAME +{ + #define USE_OLD_FILL_HOLE 0 -namespace vp -{ /*! * Retinex level that allows to specifies distribution * of the Gaussian blurring kernel sizes for scale division values > 2. @@ -126,7 +127,7 @@ VISP_EXPORT std::string vpGammaMethodList(const std::string &pref = "<", const s const std::string &suf = ">"); /** - * \brief Cast a \b vp::vpGammaMethod into a string, to know its name. + * \brief Cast a \b vpGammaMethod into a string, to know its name. * * \param[in] type The type that must be casted into a string. * \return std::string The corresponding name. @@ -134,10 +135,10 @@ VISP_EXPORT std::string vpGammaMethodList(const std::string &pref = "<", const s VISP_EXPORT std::string vpGammaMethodToString(const vpGammaMethod &type); /** - * \brief Cast a string into a \b vp::vpGammaMethod. + * \brief Cast a string into a \b vpGammaMethod. * * \param[in] name The name of the backend. - * \return vp::vpGammaMethod The corresponding enumeration value. + * \return vpGammaMethod The corresponding enumeration value. */ VISP_EXPORT vpGammaMethod vpGammaMethodFromString(const std::string &name); @@ -164,7 +165,7 @@ VISP_EXPORT std::string vpGammaColorHandlingList(const std::string &pref = "<", const std::string &suf = ">"); /** - * \brief Cast a \b vp::vpGammaColorHandling into a string, to know its name. + * \brief Cast a \b vpGammaColorHandling into a string, to know its name. * * \param[in] type The type that must be casted into a string. * \return std::string The corresponding name. @@ -172,10 +173,10 @@ VISP_EXPORT std::string vpGammaColorHandlingList(const std::string &pref = "<", VISP_EXPORT std::string vpGammaColorHandlingToString(const vpGammaColorHandling &type); /** - * \brief Cast a string into a \b vp::vpGammaColorHandling. + * \brief Cast a string into a \b vpGammaColorHandling. * * \param[in] name The name of the backend. - * \return vp::vpGammaColorHandling The corresponding enumeration value. + * \return vpGammaColorHandling The corresponding enumeration value. */ VISP_EXPORT vpGammaColorHandling vpGammaColorHandlingFromString(const std::string &name); @@ -189,7 +190,7 @@ VISP_EXPORT vpGammaColorHandling vpGammaColorHandlingFromString(const std::strin * \param alpha : Multiplication coefficient. * \param beta : Constant value added to the old intensity. */ -VISP_EXPORT void adjust(vpImage &I, double alpha, double beta); +VISP_EXPORT void adjust(VISP_NAMESPACE_ADDRESSING vpImage &I, double alpha, double beta); /*! * \ingroup group_imgproc_brightness @@ -202,7 +203,7 @@ VISP_EXPORT void adjust(vpImage &I, double alpha, double beta); * \param alpha : Multiplication coefficient. * \param beta : Constant value added to the old intensity. */ -VISP_EXPORT void adjust(const vpImage &I1, vpImage &I2, double alpha, double beta); +VISP_EXPORT void adjust(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2, double alpha, double beta); /*! * \ingroup group_imgproc_brightness @@ -214,7 +215,7 @@ VISP_EXPORT void adjust(const vpImage &I1, vpImage * \param alpha : Multiplication coefficient. * \param beta : Constant value added to the old intensity. */ -VISP_EXPORT void adjust(vpImage &I, const double alpha, double beta); +VISP_EXPORT void adjust(VISP_NAMESPACE_ADDRESSING vpImage &I, const double alpha, double beta); /*! * \ingroup group_imgproc_brightness @@ -227,7 +228,7 @@ VISP_EXPORT void adjust(vpImage &I, const double alpha, double beta); * \param alpha : Multiplication coefficient. * \param beta : Constant value added to the old intensity. */ -VISP_EXPORT void adjust(const vpImage &I1, vpImage &I2, double alpha, double beta); +VISP_EXPORT void adjust(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2, double alpha, double beta); /*! * \ingroup group_imgproc_brightness @@ -258,7 +259,7 @@ VISP_EXPORT void adjust(const vpImage &I1, vpImage &I2, double a * boxes of the given block size only and interpolates for locations in * between. */ -VISP_EXPORT void clahe(const vpImage &I1, vpImage &I2, int blockRadius = 150, +VISP_EXPORT void clahe(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2, int blockRadius = 150, int bins = 256, float slope = 3.0f, bool fast = true); /*! @@ -288,7 +289,7 @@ VISP_EXPORT void clahe(const vpImage &I1, vpImage * boxes of the given block size only and interpolates for locations in * between. */ -VISP_EXPORT void clahe(const vpImage &I1, vpImage &I2, int blockRadius = 150, int bins = 256, +VISP_EXPORT void clahe(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2, int blockRadius = 150, int bins = 256, float slope = 3.0f, bool fast = true); /*! @@ -301,7 +302,7 @@ VISP_EXPORT void clahe(const vpImage &I1, vpImage &I2, int block * \param I : The grayscale image to apply histogram equalization. * \param p_mask : If set, a boolean mask to take into account only the points for which the mask is true. */ -VISP_EXPORT void equalizeHistogram(vpImage &I, const vpImage *p_mask = nullptr); +VISP_EXPORT void equalizeHistogram(VISP_NAMESPACE_ADDRESSING vpImage &I, const VISP_NAMESPACE_ADDRESSING vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_histogram @@ -314,8 +315,8 @@ VISP_EXPORT void equalizeHistogram(vpImage &I, const vpImage &I1, vpImage &I2, - const vpImage *p_mask = nullptr); +VISP_EXPORT void equalizeHistogram(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2, + const VISP_NAMESPACE_ADDRESSING vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_histogram @@ -330,7 +331,7 @@ VISP_EXPORT void equalizeHistogram(const vpImage &I1, vpImage &I, bool useHSV = false); +VISP_EXPORT void equalizeHistogram(VISP_NAMESPACE_ADDRESSING vpImage &I, bool useHSV = false); /*! * \ingroup group_imgproc_histogram @@ -346,7 +347,7 @@ VISP_EXPORT void equalizeHistogram(vpImage &I, bool useHSV = false); * value channel (in HSV space), otherwise the histogram equalization is * performed independently on the RGB channels. */ -VISP_EXPORT void equalizeHistogram(const vpImage &I1, vpImage &I2, bool useHSV = false); +VISP_EXPORT void equalizeHistogram(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2, bool useHSV = false); /*! * \ingroup group_imgproc_gamma @@ -363,8 +364,8 @@ VISP_EXPORT void equalizeHistogram(const vpImage &I1, vpImage &I * \param[in] p_mask : If different from nullptr, permits to indicate which points must be taken into account by setting * them to true. */ -VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const vpGammaMethod &method = vp::GAMMA_MANUAL, - const vpImage *p_mask = nullptr); +VISP_EXPORT void gammaCorrection(VISP_NAMESPACE_ADDRESSING vpImage &I, const float &gamma, const vpGammaMethod &method = GAMMA_MANUAL, + const VISP_NAMESPACE_ADDRESSING vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma @@ -382,8 +383,8 @@ VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, * \param[in] p_mask : If different from nullptr, permits to indicate which points must be taken into account by setting * them to true. */ -VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, - const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); +VISP_EXPORT void gammaCorrection(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2, const float &gamma, + const vpGammaMethod &method = GAMMA_MANUAL, const VISP_NAMESPACE_ADDRESSING vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma @@ -398,8 +399,8 @@ VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I, const float &gamma, const vpGammaColorHandling &colorHandling = vp::GAMMA_RGB, - const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); +VISP_EXPORT void gammaCorrection(VISP_NAMESPACE_ADDRESSING vpImage &I, const float &gamma, const vpGammaColorHandling &colorHandling = GAMMA_RGB, + const vpGammaMethod &method = GAMMA_MANUAL, const VISP_NAMESPACE_ADDRESSING vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma @@ -415,9 +416,9 @@ VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const v * \param[in] p_mask : If different from nullptr, permits to indicate which points must be taken into account by setting * them to true. */ -VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, - const vpGammaColorHandling &colorHandling = vp::GAMMA_RGB, - const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); +VISP_EXPORT void gammaCorrection(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2, const float &gamma, + const vpGammaColorHandling &colorHandling = GAMMA_RGB, + const vpGammaMethod &method = GAMMA_MANUAL, const VISP_NAMESPACE_ADDRESSING vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_retinex @@ -440,7 +441,7 @@ VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I2, * \param kernelSize : Kernel size for the gaussian blur * operation. If -1, the kernel size is calculated from the image size. */ -VISP_EXPORT void retinex(vpImage &I, int scale = 240, int scaleDiv = 3, int level = RETINEX_UNIFORM, +VISP_EXPORT void retinex(VISP_NAMESPACE_ADDRESSING vpImage &I, int scale = 240, int scaleDiv = 3, int level = RETINEX_UNIFORM, double dynamic = 1.2, int kernelSize = -1); /*! @@ -465,7 +466,7 @@ VISP_EXPORT void retinex(vpImage &I, int scale = 240, int scaleDiv = 3, * \param kernelSize : Kernel size for the gaussian blur * operation. If -1, the kernel size is calculated from the image size. */ -VISP_EXPORT void retinex(const vpImage &I1, vpImage &I2, int scale = 240, int scaleDiv = 3, +VISP_EXPORT void retinex(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2, int scale = 240, int scaleDiv = 3, int level = RETINEX_UNIFORM, double dynamic = 1.2, int kernelSize = -1); /*! @@ -475,7 +476,7 @@ VISP_EXPORT void retinex(const vpImage &I1, vpImage &I2, int sca * * \param I : The grayscale image to stretch the contrast. */ -VISP_EXPORT void stretchContrast(vpImage &I); +VISP_EXPORT void stretchContrast(VISP_NAMESPACE_ADDRESSING vpImage &I); /*! * \ingroup group_imgproc_contrast @@ -485,7 +486,7 @@ VISP_EXPORT void stretchContrast(vpImage &I); * \param I1 : The first input grayscale image. * \param I2 : The second output grayscale image. */ -VISP_EXPORT void stretchContrast(const vpImage &I1, vpImage &I2); +VISP_EXPORT void stretchContrast(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2); /*! * \ingroup group_imgproc_contrast @@ -494,7 +495,7 @@ VISP_EXPORT void stretchContrast(const vpImage &I1, vpImage &I); +VISP_EXPORT void stretchContrast(VISP_NAMESPACE_ADDRESSING vpImage &I); /*! * \ingroup group_imgproc_contrast @@ -504,7 +505,7 @@ VISP_EXPORT void stretchContrast(vpImage &I); * \param I1 : The first input color image. * \param I2 : The second output color image. */ -VISP_EXPORT void stretchContrast(const vpImage &I1, vpImage &I2); +VISP_EXPORT void stretchContrast(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2); /*! * \ingroup group_imgproc_contrast @@ -514,7 +515,7 @@ VISP_EXPORT void stretchContrast(const vpImage &I1, vpImage &I2) * * \param I : The color image to stretch the contrast in the HSV color space. */ -VISP_EXPORT void stretchContrastHSV(vpImage &I); +VISP_EXPORT void stretchContrastHSV(VISP_NAMESPACE_ADDRESSING vpImage &I); /*! * \ingroup group_imgproc_contrast @@ -525,7 +526,7 @@ VISP_EXPORT void stretchContrastHSV(vpImage &I); * \param I1 : The first input color image. * \param I2 : The second output color image. */ -VISP_EXPORT void stretchContrastHSV(const vpImage &I1, vpImage &I2); +VISP_EXPORT void stretchContrastHSV(const VISP_NAMESPACE_ADDRESSING vpImage &I1, VISP_NAMESPACE_ADDRESSING vpImage &I2); /*! * \ingroup group_imgproc_sharpening @@ -536,7 +537,7 @@ VISP_EXPORT void stretchContrastHSV(const vpImage &I1, vpImage & * \param sigma : Standard deviation for Gaussian kernel. * \param weight : Weight (between [0 - 1[) for the sharpening process. */ -VISP_EXPORT void unsharpMask(vpImage &I, float sigma, double weight = 0.6); +VISP_EXPORT void unsharpMask(VISP_NAMESPACE_ADDRESSING vpImage &I, float sigma, double weight = 0.6); /*! * \ingroup group_imgproc_sharpening @@ -548,7 +549,7 @@ VISP_EXPORT void unsharpMask(vpImage &I, float sigma, double weig * \param sigma : Standard deviation for Gaussian kernel. * \param weight : Weight (between [0 - 1[) for the sharpening process. */ -VISP_EXPORT void unsharpMask(const vpImage &I, vpImage &Ires, float sigma, +VISP_EXPORT void unsharpMask(const VISP_NAMESPACE_ADDRESSING vpImage &I, VISP_NAMESPACE_ADDRESSING vpImage &Ires, float sigma, double weight = 0.6); /*! @@ -560,7 +561,7 @@ VISP_EXPORT void unsharpMask(const vpImage &I, vpImage &I, float sigma, double weight = 0.6); +VISP_EXPORT void unsharpMask(VISP_NAMESPACE_ADDRESSING vpImage &I, float sigma, double weight = 0.6); /*! * \ingroup group_imgproc_sharpening @@ -572,7 +573,7 @@ VISP_EXPORT void unsharpMask(vpImage &I, float sigma, double weight = 0. * \param sigma : Standard deviation for Gaussian kernel. * \param weight : Weight (between [0 - 1[) for the sharpening process. */ -VISP_EXPORT void unsharpMask(const vpImage &I, vpImage &Ires, float sigma, double weight = 0.6); +VISP_EXPORT void unsharpMask(const VISP_NAMESPACE_ADDRESSING vpImage &I, VISP_NAMESPACE_ADDRESSING vpImage &Ires, float sigma, double weight = 0.6); /*! * \ingroup group_imgproc_connected_components @@ -584,8 +585,8 @@ VISP_EXPORT void unsharpMask(const vpImage &I, vpImage &Ires, fl * \param nbComponents : Number of connected components. * \param connexity : Type of connexity. */ -VISP_EXPORT void connectedComponents(const vpImage &I, vpImage &labels, int &nbComponents, - const vpImageMorphology::vpConnexityType &connexity = vpImageMorphology::CONNEXITY_4); +VISP_EXPORT void connectedComponents(const VISP_NAMESPACE_ADDRESSING vpImage &I, VISP_NAMESPACE_ADDRESSING vpImage &labels, int &nbComponents, + const VISP_NAMESPACE_ADDRESSING vpImageMorphology::vpConnexityType &connexity = VISP_NAMESPACE_ADDRESSING vpImageMorphology::CONNEXITY_4); /*! * \ingroup group_imgproc_morph @@ -594,10 +595,10 @@ VISP_EXPORT void connectedComponents(const vpImage &I, vpImage &I +VISP_EXPORT void fillHoles(VISP_NAMESPACE_ADDRESSING vpImage &I #if USE_OLD_FILL_HOLE , - const vpImageMorphology::vpConnexityType &connexity = vpImageMorphology::CONNEXITY_4 + const VISP_NAMESPACE_ADDRESSING vpImageMorphology::vpConnexityType &connexity = VISP_NAMESPACE_ADDRESSING vpImageMorphology::CONNEXITY_4 #endif ); @@ -612,9 +613,9 @@ VISP_EXPORT void fillHoles(vpImage &I * \param newValue : New value to flood fill. * \param connexity : Type of connexity. */ -VISP_EXPORT void floodFill(vpImage &I, const vpImagePoint &seedPoint, const unsigned char oldValue, +VISP_EXPORT void floodFill(VISP_NAMESPACE_ADDRESSING vpImage &I, const VISP_NAMESPACE_ADDRESSING vpImagePoint &seedPoint, const unsigned char oldValue, const unsigned char newValue, - const vpImageMorphology::vpConnexityType &connexity = vpImageMorphology::CONNEXITY_4); + const VISP_NAMESPACE_ADDRESSING vpImageMorphology::vpConnexityType &connexity = VISP_NAMESPACE_ADDRESSING vpImageMorphology::CONNEXITY_4); /*! * \ingroup group_imgproc_morph @@ -634,9 +635,9 @@ VISP_EXPORT void floodFill(vpImage &I, const vpImagePoint &seedPo * \param h_kp1 : Image morphologically reconstructed. * \param connexity : Type of connexity. */ -VISP_EXPORT void reconstruct(const vpImage &marker, const vpImage &mask, - vpImage &h_kp1 /*alias I */, - const vpImageMorphology::vpConnexityType &connexity = vpImageMorphology::CONNEXITY_4); +VISP_EXPORT void reconstruct(const VISP_NAMESPACE_ADDRESSING vpImage &marker, const VISP_NAMESPACE_ADDRESSING vpImage &mask, + VISP_NAMESPACE_ADDRESSING vpImage &h_kp1 /*alias I */, + const VISP_NAMESPACE_ADDRESSING vpImageMorphology::vpConnexityType &connexity = VISP_NAMESPACE_ADDRESSING vpImageMorphology::CONNEXITY_4); /*! * \ingroup group_imgproc_threshold @@ -648,9 +649,10 @@ VISP_EXPORT void reconstruct(const vpImage &marker, const vpImage * \param backgroundValue : Value to set to the background. * \param foregroundValue : Value to set to the foreground. */ -VISP_EXPORT unsigned char autoThreshold(vpImage &I, const vp::vpAutoThresholdMethod &method, +VISP_EXPORT unsigned char autoThreshold(VISP_NAMESPACE_ADDRESSING vpImage &I, const vpAutoThresholdMethod &method, const unsigned char backgroundValue = 0, const unsigned char foregroundValue = 255); -} // namespace vp + +} // namespace #endif diff --git a/modules/imgproc/src/vpCLAHE.cpp b/modules/imgproc/src/vpCLAHE.cpp index 5bea19d052..1a9aeaa484 100644 --- a/modules/imgproc/src/vpCLAHE.cpp +++ b/modules/imgproc/src/vpCLAHE.cpp @@ -79,8 +79,9 @@ #include #include -namespace +namespace VISP_NAMESPACE_NAME { + int fastRound(float value) { return static_cast(value + 0.5f); } void clipHistogram(const std::vector &hist, std::vector &clippedHist, int limit) @@ -137,10 +138,15 @@ std::vector createTransfer(const std::vector &hist, int limit, std:: clipHistogram(hist, cdfs, limit); int hMin = static_cast(hist.size()) - 1; - for (int i = 0; i < hMin; ++i) { + int stopIdx = hMin; + bool hasNotFoundFirstNotZero = true; + int i = 0; + while ((i < stopIdx) && hasNotFoundFirstNotZero) { if (cdfs[i] != 0) { hMin = i; + hasNotFoundFirstNotZero = false; } + ++i; } int cdf = 0; int hist_size = static_cast(hist.size()); @@ -165,10 +171,15 @@ float transferValue(int v, std::vector &clippedHist) { int clippedHistLength = static_cast(clippedHist.size()); int hMin = clippedHistLength - 1; - for (int i = 0; i &hist, std::vector &clipp return transferValue(v, clippedHist); } -} // namespace -namespace vp -{ void clahe(const vpImage &I1, vpImage &I2, int blockRadius, int bins, float slope, bool fast) { if (blockRadius < 0) { @@ -389,7 +397,7 @@ void clahe(const vpImage &I1, vpImage &I2, int blo ++hist[fastRound((I1[yi][xi] / 255.0f) * bins)]; } } - } + } else { hist = prev_hist; @@ -438,9 +446,9 @@ void clahe(const vpImage &I1, vpImage &I2, int blo int limit = static_cast(((slope * n) / bins) + 0.5f); I2[y][x] = fastRound(transferValue(v, hist, clippedHist, limit) * 255.0f); } + } } } -} void clahe(const vpImage &I1, vpImage &I2, int blockRadius, int bins, float slope, bool fast) { @@ -481,4 +489,5 @@ void clahe(const vpImage &I1, vpImage &I2, int blockRadius, int ++cpt; } } -}; + +} // namespace diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index e88fa70ff7..d146c1a146 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -33,13 +33,16 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +namespace visp +{ +#endif + // Static variables const unsigned char vpCircleHoughTransform::edgeMapOn = 255; const unsigned char vpCircleHoughTransform::edgeMapOff = 0; #if (VISP_CXX_STANDARD == VISP_CXX_STANDARD_98) -namespace -{ // Sorting by decreasing probabilities bool hasBetterProba(std::pair a, std::pair b) { @@ -92,7 +95,6 @@ scaleFilter(vpArray2D &filter, const float &scale) } } } -}; #endif vpCircleHoughTransform::vpCircleHoughTransform() @@ -1203,3 +1205,5 @@ operator<<(std::ostream &os, const vpCircleHoughTransform &detector) os << detector.toString(); return os; } + +END_VISP_NAMESPACE diff --git a/modules/imgproc/src/vpConnectedComponents.cpp b/modules/imgproc/src/vpConnectedComponents.cpp index be93d2e98e..0eaff447f8 100644 --- a/modules/imgproc/src/vpConnectedComponents.cpp +++ b/modules/imgproc/src/vpConnectedComponents.cpp @@ -39,8 +39,9 @@ #include #include -namespace +namespace VISP_NAMESPACE_NAME { + void getNeighbors(const vpImage &I, std::queue &listOfNeighbors, unsigned int i, unsigned int j, const vpImageMorphology::vpConnexityType &connexity) { @@ -100,10 +101,7 @@ void visitNeighbors(vpImage &I_copy, std::queue &li } } } -} // namespace -namespace vp -{ void connectedComponents(const vpImage &I, vpImage &labels, int &nbComponents, const vpImageMorphology::vpConnexityType &connexity) { if (I.getSize() == 0) { @@ -161,4 +159,5 @@ void connectedComponents(const vpImage &I, vpImage &labels, nbComponents = current_label - 1; } -}; + +} // namespace diff --git a/modules/imgproc/src/vpContours.cpp b/modules/imgproc/src/vpContours.cpp index b982b3669b..aed9cc035e 100644 --- a/modules/imgproc/src/vpContours.cpp +++ b/modules/imgproc/src/vpContours.cpp @@ -70,8 +70,12 @@ #include #include -namespace +namespace VISP_NAMESPACE_NAME { +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) && defined(ENABLE_VISP_NAMESPACE) +using namespace VISP_NAMESPACE_NAME; +#endif + bool fromTo(const vpImagePoint &from, const vpImagePoint &to, vpDirection &direction) { if (from == to) { @@ -131,7 +135,7 @@ bool crossesEastBorder(const vpImage &I, bool checked[8], const vpImagePoin return (I[i][j] != 0) && ((static_cast(point.get_j()) == (I.getWidth() - 1)) || b); } -void addContourPoint(vpImage &I, vp::vpContour *border, const vpImagePoint &point, bool checked[8], int nbd) +void addContourPoint(vpImage &I, vpContour *border, const vpImagePoint &point, bool checked[8], int nbd) { border->m_points.push_back(vpImagePoint(point.get_i() - 1, point.get_j() - 1)); // remove 1-pixel padding @@ -147,7 +151,7 @@ void addContourPoint(vpImage &I, vp::vpContour *border, const vpImagePoint } // Otherwise leave it alone } -void followBorder(vpImage &I, const vpImagePoint &ij, vpImagePoint &i2j2, vp::vpContour *border, int nbd) +void followBorder(vpImage &I, const vpImagePoint &ij, vpImagePoint &i2j2, vpContour *border, int nbd) { vpDirection dir; if (!fromTo(ij, i2j2, dir)) { @@ -234,25 +238,22 @@ bool isHoleBorderStart(const vpImage &I, unsigned int i, unsigned int j) return ((I[i][j] >= 1) && ((j == (I.getWidth() - 1)) || (I[i][j + 1] == 0))); } -void getContoursList(const vp::vpContour &root, int level, vp::vpContour &contour_list) +void getContoursList(const vpContour &root, int level, vpContour &contour_list) { if ((level > 0) && (level < std::numeric_limits::max())) { - vp::vpContour *contour_node = new vp::vpContour; + vpContour *contour_node = new vpContour; contour_node->m_contourType = root.m_contourType; contour_node->m_points = root.m_points; contour_list.m_children.push_back(contour_node); } - std::vector::const_iterator root_m_children_end = root.m_children.end(); - for (std::vector::const_iterator it = root.m_children.begin(); it != root_m_children_end; ++it) { + std::vector::const_iterator root_m_children_end = root.m_children.end(); + for (std::vector::const_iterator it = root.m_children.begin(); it != root_m_children_end; ++it) { getContoursList(**it, level + 1, contour_list); } } -} // namespace -namespace vp -{ void drawContours(vpImage &I, const std::vector > &contours, unsigned char grayValue) { if (I.getSize() == 0) { @@ -325,7 +326,7 @@ void findContours(const vpImage &I_original, vpContour &contours, // Background contour // By default the root contour is a hole contour - vpContour *root = new vpContour(vp::CONTOUR_HOLE); + vpContour *root = new vpContour(CONTOUR_HOLE); std::map borderMap; borderMap[lnbd] = root; @@ -348,16 +349,16 @@ void findContours(const vpImage &I_original, vpContour &contours, //(1) (a) ++nbd; from.set_j(from.get_j() - 1); - border->m_contourType = vp::CONTOUR_OUTER; + border->m_contourType = CONTOUR_OUTER; borderPrime = borderMap[lnbd]; // Table 1 switch (borderPrime->m_contourType) { - case vp::CONTOUR_OUTER: + case CONTOUR_OUTER: border->setParent(borderPrime->m_parent); break; - case vp::CONTOUR_HOLE: + case CONTOUR_HOLE: border->setParent(borderPrime); break; @@ -375,15 +376,15 @@ void findContours(const vpImage &I_original, vpContour &contours, borderPrime = borderMap[lnbd]; from.set_j(from.get_j() + 1); - border->m_contourType = vp::CONTOUR_HOLE; + border->m_contourType = CONTOUR_HOLE; // Table 1 switch (borderPrime->m_contourType) { - case vp::CONTOUR_OUTER: + case CONTOUR_OUTER: border->setParent(borderPrime); break; - case vp::CONTOUR_HOLE: + case CONTOUR_HOLE: border->setParent(borderPrime->m_parent); break; @@ -469,4 +470,5 @@ void findContours(const vpImage &I_original, vpContour &contours, delete root; root = nullptr; } -}; + +} // namespace diff --git a/modules/imgproc/src/vpFloodFill.cpp b/modules/imgproc/src/vpFloodFill.cpp index 34cf9c037f..e89bbc6510 100644 --- a/modules/imgproc/src/vpFloodFill.cpp +++ b/modules/imgproc/src/vpFloodFill.cpp @@ -66,8 +66,9 @@ #include #include -namespace vp +namespace VISP_NAMESPACE_NAME { + void floodFill(vpImage &I, const vpImagePoint &seedPoint, const unsigned char oldValue, const unsigned char newValue, const vpImageMorphology::vpConnexityType &connexity) { @@ -159,4 +160,5 @@ void floodFill(vpImage &I, const vpImagePoint &seedPoint, const u } } } -}; + +} // namespace diff --git a/modules/imgproc/src/vpImgproc.cpp b/modules/imgproc/src/vpImgproc.cpp index ff25389262..5a82a3ace3 100644 --- a/modules/imgproc/src/vpImgproc.cpp +++ b/modules/imgproc/src/vpImgproc.cpp @@ -64,8 +64,12 @@ #include #include -namespace vp +namespace VISP_NAMESPACE_NAME { +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) && defined(ENABLE_VISP_NAMESPACE) +using namespace VISP_NAMESPACE_NAME; +#endif + std::string vpGammaMethodList(const std::string &pref, const std::string &sep, const std::string &suf) { std::string list(pref); @@ -87,22 +91,22 @@ std::string vpGammaMethodToString(const vpGammaMethod &type) case GAMMA_MANUAL: name = "gamma_manual"; break; - case GAMMA_LOG_BASED: + case GAMMA_LOG_BASED: name = "gamma_log"; break; - case GAMMA_NONLINEAR_BASED: + case GAMMA_NONLINEAR_BASED: name = "gamma_nonlinear"; break; - case GAMMA_CDF_BASED: + case GAMMA_CDF_BASED: name = "gamma_cdf"; break; - case GAMMA_CLASSIFICATION_BASED: + case GAMMA_CLASSIFICATION_BASED: name = "gamma_classification"; break; - case GAMMA_SPATIAL_VARIANT_BASED: + case GAMMA_SPATIAL_VARIANT_BASED: name = "gamma_spatial_variant"; break; - case GAMMA_METHOD_COUNT: + case GAMMA_METHOD_COUNT: default: name = "gamma_method_unknown"; } @@ -144,13 +148,13 @@ std::string vpGammaColorHandlingToString(const vpGammaColorHandling &type) { std::string name; switch (type) { - case GAMMA_RGB: + case GAMMA_RGB: name = "gamma_color_rgb"; break; - case GAMMA_HSV: + case GAMMA_HSV: name = "gamma_color_hsv"; break; - case GAMMA_COLOR_HANDLING_COUNT: + case GAMMA_COLOR_HANDLING_COUNT: default: name = "gamma_color_unknown"; } @@ -191,7 +195,7 @@ void adjust(const vpImage &I1, vpImage &I2, double // Copy I1 to I2 I2 = I1; - vp::adjust(I2, alpha, beta); + adjust(I2, alpha, beta); } void adjust(vpImage &I, double alpha, double beta) @@ -214,13 +218,13 @@ void adjust(const vpImage &I1, vpImage &I2, double alpha, double // Copy I1 to I2 I2 = I1; - vp::adjust(I2, alpha, beta); + adjust(I2, alpha, beta); } void equalizeHistogram(vpImage &I, const vpImage *p_mask) { vpImage Icpy = I; - vp::equalizeHistogram(Icpy, I, p_mask); + equalizeHistogram(Icpy, I, p_mask); } void equalizeHistogram(const vpImage &I1, vpImage &I2, @@ -252,11 +256,11 @@ void equalizeHistogram(vpImage &I, bool useHSV) vpImageConvert::split(I, &pR, &pG, &pB, &pa); // Apply histogram equalization for each channel - vp::equalizeHistogram(pR); - vp::equalizeHistogram(pG); - vp::equalizeHistogram(pB); + equalizeHistogram(pR); + equalizeHistogram(pG); + equalizeHistogram(pB); - // Merge the result in I + // Merge the result in I unsigned int size = I.getWidth() * I.getHeight(); unsigned char *ptrStart = reinterpret_cast(I.bitmap); unsigned char *ptrEnd = ptrStart + (size * 4); @@ -290,9 +294,9 @@ void equalizeHistogram(vpImage &I, bool useHSV) reinterpret_cast(saturation.bitmap), reinterpret_cast(value.bitmap), size); // Histogram equalization on the value plane - vp::equalizeHistogram(value); + equalizeHistogram(value); - // Convert from HSV to RGBa + // Convert from HSV to RGBa vpImageConvert::HSVToRGBa(reinterpret_cast(hue.bitmap), reinterpret_cast(saturation.bitmap), reinterpret_cast(value.bitmap), reinterpret_cast(I.bitmap), size); } @@ -301,11 +305,9 @@ void equalizeHistogram(vpImage &I, bool useHSV) void equalizeHistogram(const vpImage &I1, vpImage &I2, bool useHSV) { I2 = I1; - vp::equalizeHistogram(I2, useHSV); + equalizeHistogram(I2, useHSV); } -namespace -{ /** * \brief This method is an implementation of the article "Towards Real-time Hardware Gamma Correction * for Dynamic Contrast Enhancement" by Jesse Scott, Michael Pusateri, IEEE Applied Imagery Pattern Recognition @@ -596,12 +598,11 @@ void gammaCorrectionSpatialBased(vpImage &I, const vpImage *p_mask } } } -} void gammaCorrection(vpImage &I, const float &gamma, const vpGammaMethod &method, const vpImage *p_mask) { float inverse_gamma = 1.0; - if ((gamma > 0) && (method == GAMMA_MANUAL)) { + if ((gamma > 0) && (method == GAMMA_MANUAL)) { inverse_gamma = 1.0f / gamma; // Construct the look-up table unsigned char lut[256]; @@ -611,7 +612,7 @@ void gammaCorrection(vpImage &I, const float &gamma, const vpGamm I.performLut(lut); } - else if (method == GAMMA_MANUAL) { + else if (method == GAMMA_MANUAL) { std::stringstream errMsg; errMsg << "ERROR: gamma correction factor ("; errMsg << gamma << ") cannot be negative when using a constant user-defined factor." << std::endl; @@ -623,19 +624,19 @@ void gammaCorrection(vpImage &I, const float &gamma, const vpGamm throw(vpException(vpException::badValue, errMsg.str())); } else { - if (method == GAMMA_NONLINEAR_BASED) { + if (method == GAMMA_NONLINEAR_BASED) { gammaCorrectionNonLinearMethod(I, p_mask); } - else if (method == GAMMA_LOG_BASED) { + else if (method == GAMMA_LOG_BASED) { gammaCorrectionLogMethod(I, p_mask); } - else if (method == GAMMA_CLASSIFICATION_BASED) { + else if (method == GAMMA_CLASSIFICATION_BASED) { gammaCorrectionClassBasedMethod(I, p_mask); } - else if (method == GAMMA_CDF_BASED) { + else if (method == GAMMA_CDF_BASED) { gammaCorrectionProbBasedMethod(I, p_mask); } - else if (method == GAMMA_SPATIAL_VARIANT_BASED) { + else if (method == GAMMA_SPATIAL_VARIANT_BASED) { gammaCorrectionSpatialBased(I, p_mask); } else { @@ -650,17 +651,17 @@ void gammaCorrection(const vpImage &I1, vpImage &I const vpGammaMethod &method, const vpImage *p_mask) { I2 = I1; - vp::gammaCorrection(I2, gamma, method, p_mask); + gammaCorrection(I2, gamma, method, p_mask); } void gammaCorrection(vpImage &I, const float &gamma, const vpGammaColorHandling &colorHandling, const vpGammaMethod &method, const vpImage *p_mask) { - if (method == GAMMA_SPATIAL_VARIANT_BASED) { + if (method == GAMMA_SPATIAL_VARIANT_BASED) { gammaCorrectionSpatialBased(I, p_mask); } else { - if (colorHandling == GAMMA_HSV) { + if (colorHandling == GAMMA_HSV) { const unsigned int height = I.getHeight(), width = I.getWidth(); unsigned int size = height * width; std::vector hue(size); @@ -676,7 +677,7 @@ void gammaCorrection(vpImage &I, const float &gamma, const vpGammaColorH vpImageConvert::HSVToRGBa(I_hue.bitmap, I_saturation.bitmap, I_value.bitmap, reinterpret_cast(I.bitmap), size); } - else if (colorHandling == GAMMA_RGB) { + else if (colorHandling == GAMMA_RGB) { vpImage pR, pG, pB, pa; vpImageConvert::split(I, &pR, &pG, &pB, &pa); gammaCorrection(pR, gamma, method, p_mask); @@ -699,7 +700,7 @@ void gammaCorrection(const vpImage &I1, vpImage &I2, const float const vpImage *p_mask) { I2 = I1; - vp::gammaCorrection(I2, gamma, colorHandling, method, p_mask); + gammaCorrection(I2, gamma, colorHandling, method, p_mask); } void stretchContrast(vpImage &I) @@ -728,7 +729,7 @@ void stretchContrast(const vpImage &I1, vpImage &I { // Copy I1 to I2 I2 = I1; - vp::stretchContrast(I2); + stretchContrast(I2); } void stretchContrast(vpImage &I) @@ -810,7 +811,7 @@ void stretchContrast(const vpImage &I1, vpImage &I2) { // Copy I1 to I2 I2 = I1; - vp::stretchContrast(I2); + stretchContrast(I2); } void stretchContrastHSV(vpImage &I) @@ -861,7 +862,7 @@ void stretchContrastHSV(const vpImage &I1, vpImage &I2) { // Copy I1 to I2 I2 = I1; - vp::stretchContrastHSV(I2); + stretchContrastHSV(I2); } void unsharpMask(vpImage &I, float sigma, double weight) @@ -893,7 +894,7 @@ void unsharpMask(const vpImage &I, vpImage &Ires, { // Copy I to Ires Ires = I; - vp::unsharpMask(Ires, sigma, weight); + unsharpMask(Ires, sigma, weight); } void unsharpMask(vpImage &I, float sigma, double weight) @@ -940,7 +941,7 @@ void unsharpMask(const vpImage &I, vpImage &Ires, float sigma, d { // Copy I to Ires Ires = I; - vp::unsharpMask(Ires, sigma, weight); + unsharpMask(Ires, sigma, weight); } -}; +} // namespace diff --git a/modules/imgproc/src/vpMorph.cpp b/modules/imgproc/src/vpMorph.cpp index f00b686d31..500563f593 100644 --- a/modules/imgproc/src/vpMorph.cpp +++ b/modules/imgproc/src/vpMorph.cpp @@ -39,7 +39,7 @@ #include #include -namespace vp +namespace VISP_NAMESPACE_NAME { void fillHoles(vpImage &I @@ -102,7 +102,7 @@ void fillHoles(vpImage &I } // Perform flood fill - vp::floodFill(flood_fill_mask, vpImagePoint(0, 0), 0, 255); + floodFill(flood_fill_mask, vpImagePoint(0, 0), 0, 255); // Get current mask vpImage mask(I.getHeight(), I.getWidth()); @@ -159,4 +159,5 @@ void reconstruct(const vpImage &marker, const vpImage - *Developed at Birmingham University, School of Dentistry. Supervised by - *Gabriel Landini - *@version 1.0 + * @author Jimenez-Hernandez Francisco + * Developed at Birmingham University, School of Dentistry. Supervised by + * Gabriel Landini + * @version 1.0 * * 8 July 2010 * @@ -88,6 +88,9 @@ #include #include +namespace VISP_NAMESPACE_NAME +{ + #define MAX_RETINEX_SCALES 8 std::vector retinexScalesDistribution(int scaleDiv, int level, int scale) @@ -106,20 +109,20 @@ std::vector retinexScalesDistribution(int scaleDiv, int level, int scale int i; switch (level) { - case vp::RETINEX_UNIFORM: + case RETINEX_UNIFORM: for (i = 0; i < scaleDiv; ++i) { scales[static_cast(i)] = 2.0 + (i * size_step); } break; - case vp::RETINEX_LOW: + case RETINEX_LOW: size_step = std::log(scale - 2.0) / static_cast(scaleDiv); for (i = 0; i < scaleDiv; ++i) { scales[static_cast(i)] = 2.0 + std::pow(10.0, (i * size_step) / std::log(10.0)); } break; - case vp::RETINEX_HIGH: + case RETINEX_HIGH: size_step = std::log(scale - 2.0) / static_cast(scaleDiv); for (i = 0; i < scaleDiv; ++i) { scales[static_cast(i)] = scale - std::pow(10.0, (i * size_step) / std::log(10.0)); @@ -239,8 +242,6 @@ void MSRCR(vpImage &I, int v_scale, int scaleDiv, int level, double dyna } } -namespace vp -{ void retinex(vpImage &I, int scale, int scaleDiv, int level, const double dynamic, int kernelSize) { // Assert scale @@ -266,6 +267,7 @@ void retinex(const vpImage &I1, vpImage &I2, int scale, int scal int kernelSize) { I2 = I1; - vp::retinex(I2, scale, scaleDiv, level, dynamic, kernelSize); + retinex(I2, scale, scaleDiv, level, dynamic, kernelSize); } -}; + +} // namespace diff --git a/modules/imgproc/src/vpThreshold.cpp b/modules/imgproc/src/vpThreshold.cpp index 6633127d3d..d8365d0f22 100644 --- a/modules/imgproc/src/vpThreshold.cpp +++ b/modules/imgproc/src/vpThreshold.cpp @@ -40,8 +40,9 @@ #include #include -namespace +namespace VISP_NAMESPACE_NAME { + bool isBimodal(const std::vector &hist_float) { int modes = 0; @@ -265,14 +266,15 @@ int computeThresholdOtsu(const vpHistogram &hist, unsigned int imageSize) int threshold = 0; bool w_f_eq_nul = false; - for (int cpt = 0; (cpt < 256) && (w_f_eq_nul == false); ++cpt) { + int cpt = 0; + while ((cpt < 256) && (!w_f_eq_nul)) { w_B += hist[cpt]; bool w_b_eq_nul = vpMath::nul(w_B, std::numeric_limits::epsilon()); - if (w_b_eq_nul == false) { + if (!w_b_eq_nul) { w_F = static_cast(imageSize) - w_B; w_f_eq_nul = vpMath::nul(w_F, std::numeric_limits::epsilon()); - if (w_f_eq_nul == false) { + if (!w_f_eq_nul) { // Mean Background / Foreground float mu_B = sum_ip_all[cpt] / static_cast(w_B); @@ -288,6 +290,7 @@ int computeThresholdOtsu(const vpHistogram &hist, unsigned int imageSize) } // else exit the loop } + ++cpt; } return threshold; @@ -368,10 +371,7 @@ int computeThresholdTriangle(vpHistogram &hist) return threshold; } -} // namespace -namespace vp -{ unsigned char autoThreshold(vpImage &I, const vpAutoThresholdMethod &method, const unsigned char backgroundValue, const unsigned char foregroundValue) { @@ -420,4 +420,5 @@ unsigned char autoThreshold(vpImage &I, const vpAutoThresholdMeth return threshold; } -}; + +} // namespace diff --git a/modules/imgproc/test/with-dataset/testAutoThreshold.cpp b/modules/imgproc/test/with-dataset/testAutoThreshold.cpp index 2de7a84f55..f9aba1768c 100644 --- a/modules/imgproc/test/with-dataset/testAutoThreshold.cpp +++ b/modules/imgproc/test/with-dataset/testAutoThreshold.cpp @@ -31,21 +31,25 @@ * Test automatic thresholding. */ -#include -#include -#include -#include -#include - /*! \example testAutoThreshold.cpp \brief Test automatic thresholding. */ +#include +#include +#include +#include +#include + // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); @@ -61,9 +65,9 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user) { #if VISP_HAVE_DATASET_VERSION >= 0x030600 - std::string ext("png"); + std::string ext("png"); #else - std::string ext("pgm"); + std::string ext("pgm"); #endif fprintf(stdout, "\n\ Test automatic thresholding.\n\ @@ -72,7 +76,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n \ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -203,7 +207,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; @@ -218,8 +223,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; } } @@ -228,9 +233,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; exit(EXIT_FAILURE); } @@ -247,7 +252,7 @@ int main(int argc, const char **argv) // Huang double t = vpTime::measureTimeMs(); - double threshold = vp::autoThreshold(I_thresh, vp::AUTO_THRESHOLD_HUANG); + double threshold = VISP_NAMESPACE_NAME::autoThreshold(I_thresh, VISP_NAMESPACE_NAME::AUTO_THRESHOLD_HUANG); t = vpTime::measureTimeMs() - t; std::cout << "\nAutomatic thresholding (Huang): " << threshold << " ; t=" << t << " ms" << std::endl; @@ -258,7 +263,7 @@ int main(int argc, const char **argv) // Intermodes I_thresh = I; t = vpTime::measureTimeMs(); - threshold = vp::autoThreshold(I_thresh, vp::AUTO_THRESHOLD_INTERMODES); + threshold = VISP_NAMESPACE_NAME::autoThreshold(I_thresh, VISP_NAMESPACE_NAME::AUTO_THRESHOLD_INTERMODES); t = vpTime::measureTimeMs() - t; std::cout << "\nAutomatic thresholding (Intermodes): " << threshold << " ; t=" << t << " ms" << std::endl; @@ -269,7 +274,7 @@ int main(int argc, const char **argv) // IsoData I_thresh = I; t = vpTime::measureTimeMs(); - threshold = vp::autoThreshold(I_thresh, vp::AUTO_THRESHOLD_ISODATA); + threshold = VISP_NAMESPACE_NAME::autoThreshold(I_thresh, VISP_NAMESPACE_NAME::AUTO_THRESHOLD_ISODATA); t = vpTime::measureTimeMs() - t; std::cout << "\nAutomatic thresholding (IsoData): " << threshold << " ; t=" << t << " ms" << std::endl; @@ -280,7 +285,7 @@ int main(int argc, const char **argv) // Mean I_thresh = I; t = vpTime::measureTimeMs(); - threshold = vp::autoThreshold(I_thresh, vp::AUTO_THRESHOLD_MEAN); + threshold = VISP_NAMESPACE_NAME::autoThreshold(I_thresh, VISP_NAMESPACE_NAME::AUTO_THRESHOLD_MEAN); t = vpTime::measureTimeMs() - t; std::cout << "\nAutomatic thresholding (Mean): " << threshold << " ; t=" << t << " ms" << std::endl; @@ -291,7 +296,7 @@ int main(int argc, const char **argv) // Otsu I_thresh = I; t = vpTime::measureTimeMs(); - threshold = vp::autoThreshold(I_thresh, vp::AUTO_THRESHOLD_OTSU); + threshold = VISP_NAMESPACE_NAME::autoThreshold(I_thresh, VISP_NAMESPACE_NAME::AUTO_THRESHOLD_OTSU); t = vpTime::measureTimeMs() - t; std::cout << "\nAutomatic thresholding (Otsu): " << threshold << " ; t=" << t << " ms" << std::endl; @@ -302,7 +307,7 @@ int main(int argc, const char **argv) // Triangle I_thresh = I; t = vpTime::measureTimeMs(); - threshold = vp::autoThreshold(I_thresh, vp::AUTO_THRESHOLD_TRIANGLE); + threshold = VISP_NAMESPACE_NAME::autoThreshold(I_thresh, VISP_NAMESPACE_NAME::AUTO_THRESHOLD_TRIANGLE); t = vpTime::measureTimeMs() - t; std::cout << "\nAutomatic thresholding (Triangle): " << threshold << " ; t=" << t << " ms" << std::endl; @@ -311,7 +316,8 @@ int main(int argc, const char **argv) std::cout << "Write: " << filename << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/imgproc/test/with-dataset/testConnectedComponents.cpp b/modules/imgproc/test/with-dataset/testConnectedComponents.cpp index de888663c9..d0c8ac64d2 100644 --- a/modules/imgproc/test/with-dataset/testConnectedComponents.cpp +++ b/modules/imgproc/test/with-dataset/testConnectedComponents.cpp @@ -30,6 +30,13 @@ * Description: * Test connected components. */ + +/*! + \example testConnectedComponents.cpp + + \brief Test connected components. +*/ + #include #include #include @@ -38,15 +45,13 @@ #include #include -/*! - \example testConnectedComponents.cpp - - \brief Test connected components. -*/ - // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); bool checkLabels(const vpImage &label1, const vpImage &label2); @@ -69,7 +74,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n \ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -156,8 +161,8 @@ bool checkLabels(const vpImage &label1, const vpImage &label2) for (unsigned int j = 0; j < label1.getWidth(); j++) { if ((label1[i][j] > 0 && label2[i][j] == 0) || (label1[i][j] == 0 && label2[i][j] > 0)) { std::cerr << "label1[i][j] > 0 && label2[i][j] == 0 || label1[i][j] " - "== 0 && label2[i][j] > 0" - << std::endl; + "== 0 && label2[i][j] > 0" + << std::endl; return false; } @@ -242,7 +247,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; @@ -257,8 +263,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; } } @@ -267,9 +273,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; exit(EXIT_FAILURE); } @@ -289,7 +295,7 @@ int main(int argc, const char **argv) vpImage labels_connex4; int nbComponents = 0; double t = vpTime::measureTimeMs(); - vp::connectedComponents(I, labels_connex4, nbComponents, vpImageMorphology::CONNEXITY_4); + VISP_NAMESPACE_NAME::connectedComponents(I, labels_connex4, nbComponents, vpImageMorphology::CONNEXITY_4); t = vpTime::measureTimeMs() - t; std::cout << "\n4-connexity connected components:" << std::endl; std::cout << "Time: " << t << " ms" << std::endl; @@ -297,7 +303,7 @@ int main(int argc, const char **argv) vpImage labels_connex8; t = vpTime::measureTimeMs(); - vp::connectedComponents(I, labels_connex8, nbComponents, vpImageMorphology::CONNEXITY_8); + VISP_NAMESPACE_NAME::connectedComponents(I, labels_connex8, nbComponents, vpImageMorphology::CONNEXITY_8); t = vpTime::measureTimeMs() - t; std::cout << "\n8-connexity connected components:" << std::endl; std::cout << "Time: " << t << " ms" << std::endl; @@ -393,7 +399,8 @@ int main(int argc, const char **argv) #endif return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/imgproc/test/with-dataset/testContours.cpp b/modules/imgproc/test/with-dataset/testContours.cpp index b1c7a9b9a3..9d11831de4 100644 --- a/modules/imgproc/test/with-dataset/testContours.cpp +++ b/modules/imgproc/test/with-dataset/testContours.cpp @@ -31,6 +31,12 @@ * Test contours extraction. */ +/*! + \example testContours.cpp + + \brief Test contours extraction. +*/ + #include #include @@ -39,15 +45,13 @@ #include #include -/*! - \example testContours.cpp - - \brief Test contours extraction. -*/ - // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); @@ -69,7 +73,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n \ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -167,15 +171,15 @@ void printImage(const vpImage &I, const std::string &name) } } -void displayContourInfo(const vp::vpContour &contour, int level) +void displayContourInfo(const VISP_NAMESPACE_NAME::vpContour &contour, int level) { std::cout << "\nContour:" << std::endl; std::cout << "\tlevel: " << level << std::endl; - std::cout << "\tcontour type: " << (contour.m_contourType == vp::CONTOUR_OUTER ? "outer contour" : "hole contour") - << std::endl; + std::cout << "\tcontour type: " << (contour.m_contourType == VISP_NAMESPACE_NAME::CONTOUR_OUTER ? "outer contour" : "hole contour") + << std::endl; std::cout << "\tnb children: " << contour.m_children.size() << std::endl; - for (std::vector::const_iterator it = contour.m_children.begin(); it != contour.m_children.end(); + for (std::vector::const_iterator it = contour.m_children.begin(); it != contour.m_children.end(); ++it) { displayContourInfo(**it, level + 1); } @@ -229,7 +233,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 +249,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 +259,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; exit(EXIT_FAILURE); } @@ -268,16 +273,16 @@ int main(int argc, const char **argv) 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 0, 0, 1, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, - 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 1, 0, 1, 0, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; + 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 1, 0, 1, 0, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; vpImage I_test_data(image_data, 14, 10, true); std::cout << "Test with image data:" << std::endl; printImage(I_test_data, "I_test_data"); - vp::vpContour vp_contours; + VISP_NAMESPACE_NAME::vpContour vp_contours; std::vector > contours; double t = vpTime::measureTimeMs(); - vp::findContours(I_test_data, vp_contours, contours); + VISP_NAMESPACE_NAME::findContours(I_test_data, vp_contours, contours); t = vpTime::measureTimeMs() - t; displayContourInfo(vp_contours, 0); @@ -299,7 +304,7 @@ int main(int argc, const char **argv) vpImageIo::write(I2, filename); t = vpTime::measureTimeMs(); - vp::findContours(I, vp_contours, contours); + VISP_NAMESPACE_NAME::findContours(I, vp_contours, contours); t = vpTime::measureTimeMs() - t; displayContourInfo(vp_contours, 0); @@ -308,52 +313,52 @@ int main(int argc, const char **argv) // Draw and save vpImage I_draw_contours(I2.getHeight(), I2.getWidth(), 0); - vp::drawContours(I_draw_contours, contours); + VISP_NAMESPACE_NAME::drawContours(I_draw_contours, contours); filename = vpIoTools::createFilePath(opath, "Klimt_contours_extracted.pgm"); vpImageIo::write(I_draw_contours, filename); vpImage I_draw_contours_color(I2.getHeight(), I2.getWidth(), vpRGBa(0, 0, 0)); - vp::drawContours(I_draw_contours_color, contours, vpColor::red); + VISP_NAMESPACE_NAME::drawContours(I_draw_contours_color, contours, vpColor::red); filename = vpIoTools::createFilePath(opath, "Klimt_contours_extracted_color.ppm"); vpImageIo::write(I_draw_contours_color, filename); // Test retrieve list - vp::findContours(I, vp_contours, contours, vp::CONTOUR_RETR_LIST); + VISP_NAMESPACE_NAME::findContours(I, vp_contours, contours, VISP_NAMESPACE_NAME::CONTOUR_RETR_LIST); vpImage I_draw_contours_list(I2.getHeight(), I2.getWidth(), 0); vpImage I_tmp_list(I.getHeight(), I.getWidth(), 0); - vp::drawContours(I_tmp_list, contours); + VISP_NAMESPACE_NAME::drawContours(I_tmp_list, contours); contours.clear(); - for (std::vector::const_iterator it = vp_contours.m_children.begin(); + for (std::vector::const_iterator it = vp_contours.m_children.begin(); it != vp_contours.m_children.end(); ++it) { contours.push_back((*it)->m_points); } - vp::drawContours(I_draw_contours_list, contours); + VISP_NAMESPACE_NAME::drawContours(I_draw_contours_list, contours); std::cout << "(I_tmp_list == I_draw_contours_list)? " << (I_tmp_list == I_draw_contours_list) << std::endl; filename = vpIoTools::createFilePath(opath, "Klimt_contours_extracted_list.pgm"); vpImageIo::write(I_draw_contours_list, filename); // Test retrieve external - vp::findContours(I, vp_contours, contours, vp::CONTOUR_RETR_EXTERNAL); + VISP_NAMESPACE_NAME::findContours(I, vp_contours, contours, VISP_NAMESPACE_NAME::CONTOUR_RETR_EXTERNAL); vpImage I_draw_contours_external(I2.getHeight(), I2.getWidth(), 0); vpImage I_tmp_external(I.getHeight(), I.getWidth(), 0); - vp::drawContours(I_tmp_external, contours); + VISP_NAMESPACE_NAME::drawContours(I_tmp_external, contours); contours.clear(); - for (std::vector::const_iterator it = vp_contours.m_children.begin(); + for (std::vector::const_iterator it = vp_contours.m_children.begin(); it != vp_contours.m_children.end(); ++it) { contours.push_back((*it)->m_points); } - vp::drawContours(I_draw_contours_external, contours); + VISP_NAMESPACE_NAME::drawContours(I_draw_contours_external, contours); std::cout << "(I_tmp_external == I_draw_contours_external)? " << (I_tmp_external == I_draw_contours_external) - << std::endl; + << std::endl; filename = vpIoTools::createFilePath(opath, "Klimt_contours_extracted_external.pgm"); vpImageIo::write(I_draw_contours_external, filename); @@ -364,7 +369,7 @@ int main(int argc, const char **argv) (unsigned char)255); t = vpTime::measureTimeMs(); - vp::fillHoles(I_holes); + VISP_NAMESPACE_NAME::fillHoles(I_holes); t = vpTime::measureTimeMs() - t; std::cout << "\nFill Holes: " << t << " ms" << std::endl; @@ -390,7 +395,7 @@ int main(int argc, const char **argv) } std::cout << "(I_draw_contours_opencv == I_drawContours)? " << (I_draw_contours_opencv == I_draw_contours) - << std::endl; + << std::endl; filename = vpIoTools::createFilePath(opath, "Klimt_contours_extracted_opencv.pgm"); vpImageIo::write(I_draw_contours_opencv, filename); @@ -409,9 +414,9 @@ int main(int argc, const char **argv) } std::cout << "(I_draw_contours_opencv == I_draw_contours_list)? " - << (I_draw_contours_opencv == I_draw_contours_list) << std::endl; + << (I_draw_contours_opencv == I_draw_contours_list) << std::endl; - // Test retrieve external +// Test retrieve external vpImageConvert::convert(I, matImg); contours_opencv.clear(); cv::findContours(matImg, contours_opencv, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE); @@ -425,11 +430,12 @@ int main(int argc, const char **argv) } std::cout << "(I_draw_contours_opencv == I_draw_contours_external)? " - << (I_draw_contours_opencv == I_draw_contours_external) << std::endl; + << (I_draw_contours_opencv == I_draw_contours_external) << std::endl; #endif return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/imgproc/test/with-dataset/testFloodFill.cpp b/modules/imgproc/test/with-dataset/testFloodFill.cpp index dfe48dcd43..f8b6d4be96 100644 --- a/modules/imgproc/test/with-dataset/testFloodFill.cpp +++ b/modules/imgproc/test/with-dataset/testFloodFill.cpp @@ -31,6 +31,12 @@ * Test flood fill algorithm. */ +/*! + \example testFloodFill.cpp + + \brief Test flood fill algorithm. +*/ + #include #include @@ -39,15 +45,13 @@ #include #include -/*! - \example testFloodFill.cpp - - \brief Test flood fill algorithm. -*/ - // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); @@ -69,7 +73,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n \ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -221,7 +225,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; @@ -236,8 +241,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; } } @@ -246,9 +251,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; exit(EXIT_FAILURE); } @@ -256,50 +261,50 @@ int main(int argc, const char **argv) // Here starts really the test // - unsigned char image_data[8 * 8] = {1, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0, + unsigned char image_data[8 * 8] = { 1, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0, 1, 1, 1, 1, 0, 1, 1, 1, 1, 0, 0, 1, - 1, 0, 1, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0}; + 1, 0, 1, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0 }; vpImage I_test_flood_fill_4_connexity(image_data, 8, 8, true); vpImage I_test_flood_fill_8_connexity = I_test_flood_fill_4_connexity; printImage(I_test_flood_fill_4_connexity, "Test image data"); unsigned char image_data_check_4_connexity[8 * 8] = { 1, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, - 1, 1, 1, 1, 0, 1, 1, 1, 1, 0, 0, 1, 1, 0, 1, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0}; + 1, 1, 1, 1, 0, 1, 1, 1, 1, 0, 0, 1, 1, 0, 1, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0 }; vpImage I_check_4_connexity(image_data_check_4_connexity, 8, 8, true); unsigned char image_data_check_8_connexity[8 * 8] = { 1, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 1, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0}; + 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 1, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0 }; vpImage I_check_8_connexity(image_data_check_8_connexity, 8, 8, true); // Test flood fill on test data 4-connexity - vp::floodFill(I_test_flood_fill_4_connexity, vpImagePoint(2, 2), 0, 1, vpImageMorphology::CONNEXITY_4); + VISP_NAMESPACE_NAME::floodFill(I_test_flood_fill_4_connexity, vpImagePoint(2, 2), 0, 1, vpImageMorphology::CONNEXITY_4); printImage(I_test_flood_fill_4_connexity, "I_test_flood_fill_4_connexity"); if (I_test_flood_fill_4_connexity != I_check_4_connexity) { - throw vpException(vpException::fatalError, "Problem with vp::floodFill() and 4-connexity!"); + throw vpException(vpException::fatalError, "Problem with VISP_NAMESPACE_NAME::floodFill() and 4-connexity!"); } std::cout << "\n(I_test_flood_fill_4_connexity == I_check_4_connexity)? " - << (I_test_flood_fill_4_connexity == I_check_4_connexity) << std::endl; + << (I_test_flood_fill_4_connexity == I_check_4_connexity) << std::endl; - // Test flood fill on test data 8-connexity - vp::floodFill(I_test_flood_fill_8_connexity, vpImagePoint(2, 2), 0, 1, vpImageMorphology::CONNEXITY_8); +// Test flood fill on test data 8-connexity + VISP_NAMESPACE_NAME::floodFill(I_test_flood_fill_8_connexity, vpImagePoint(2, 2), 0, 1, vpImageMorphology::CONNEXITY_8); printImage(I_test_flood_fill_8_connexity, "I_test_flood_fill_8_connexity"); if (I_test_flood_fill_8_connexity != I_check_8_connexity) { - throw vpException(vpException::fatalError, "Problem with vp::floodFill() and 8-connexity!"); + throw vpException(vpException::fatalError, "Problem with VISP_NAMESPACE_NAME::floodFill() and 8-connexity!"); } std::cout << "\n(I_test_flood_fill_8_connexity == I_check_8_connexity)? " - << (I_test_flood_fill_8_connexity == I_check_8_connexity) << std::endl; + << (I_test_flood_fill_8_connexity == I_check_8_connexity) << std::endl; - // Read Klimt.ppm +// Read Klimt.ppm filename = vpIoTools::createFilePath(ipath, "Klimt/Klimt.pgm"); vpImage I_klimt; vpImageIo::read(I_klimt, filename); std::cout << "\nRead image: " << filename << " (" << I_klimt.getWidth() << "x" << I_klimt.getHeight() << ")" - << std::endl - << std::endl; + << std::endl + << std::endl; vpImageTools::binarise(I_klimt, (unsigned char)127, (unsigned char)255, (unsigned char)0, (unsigned char)255, (unsigned char)255); @@ -308,7 +313,7 @@ int main(int argc, const char **argv) vpImage I_klimt_flood_fill_4_connexity = I_klimt; double t = vpTime::measureTimeMs(); - vp::floodFill(I_klimt_flood_fill_4_connexity, vpImagePoint(seed_y, seed_x), 0, 255, vpImageMorphology::CONNEXITY_4); + VISP_NAMESPACE_NAME::floodFill(I_klimt_flood_fill_4_connexity, vpImagePoint(seed_y, seed_x), 0, 255, vpImageMorphology::CONNEXITY_4); t = vpTime::measureTimeMs() - t; std::cout << "Flood fill on Klimt image (4-connexity): " << t << " ms" << std::endl; @@ -317,7 +322,7 @@ int main(int argc, const char **argv) vpImage I_klimt_flood_fill_8_connexity = I_klimt; t = vpTime::measureTimeMs(); - vp::floodFill(I_klimt_flood_fill_8_connexity, vpImagePoint(seed_y, seed_x), 0, 255, vpImageMorphology::CONNEXITY_8); + VISP_NAMESPACE_NAME::floodFill(I_klimt_flood_fill_8_connexity, vpImagePoint(seed_y, seed_x), 0, 255, vpImageMorphology::CONNEXITY_8); t = vpTime::measureTimeMs() - t; std::cout << "Flood fill on Klimt image (8-connexity): " << t << " ms" << std::endl; filename = vpIoTools::createFilePath(opath, "Klimt_flood_fill_8_connexity.pgm"); @@ -355,11 +360,11 @@ int main(int argc, const char **argv) // Check std::cout << "\n(I_klimt_flood_fill_4_connexity == " - "I_klimt_flood_fill_4_connexity_check)? " - << (I_klimt_flood_fill_4_connexity == I_klimt_flood_fill_4_connexity_check) << std::endl; + "I_klimt_flood_fill_4_connexity_check)? " + << (I_klimt_flood_fill_4_connexity == I_klimt_flood_fill_4_connexity_check) << std::endl; std::cout << "(I_klimt_flood_fill_8_connexity == " - "I_klimt_flood_fill_8_connexity_check)? " - << (I_klimt_flood_fill_8_connexity == I_klimt_flood_fill_8_connexity_check) << std::endl; + "I_klimt_flood_fill_8_connexity_check)? " + << (I_klimt_flood_fill_8_connexity == I_klimt_flood_fill_8_connexity_check) << std::endl; if (I_klimt_flood_fill_4_connexity != I_klimt_flood_fill_4_connexity_check) { throw vpException(vpException::fatalError, "(I_klimt_flood_fill_4_connexity != " @@ -372,13 +377,14 @@ int main(int argc, const char **argv) std::cout << "\nTest flood fill is ok!" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } #else - (void) argc; - (void) argv; + (void)argc; + (void)argv; std::cout << "Install OpenCV imgproc module required by this test" << std::endl; return EXIT_SUCCESS; #endif diff --git a/modules/imgproc/test/with-dataset/testImgproc.cpp b/modules/imgproc/test/with-dataset/testImgproc.cpp index 3f2fb03636..6af19a1427 100644 --- a/modules/imgproc/test/with-dataset/testImgproc.cpp +++ b/modules/imgproc/test/with-dataset/testImgproc.cpp @@ -31,6 +31,12 @@ * Test imgproc functions. */ +/*! + \example testImgproc.cpp + + \brief Test imgproc functions. +*/ + #include #include #include @@ -40,15 +46,13 @@ #include #include -/*! - \example testImgproc.cpp - - \brief Test imgproc functions. -*/ - // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); @@ -252,7 +256,7 @@ int main(int argc, const char **argv) double alpha = 1.5, beta = -10.0; vpImage I_color_adjust; double t = vpTime::measureTimeMs(); - vp::adjust(I_color, I_color_adjust, alpha, beta); + VISP_NAMESPACE_NAME::adjust(I_color, I_color_adjust, alpha, beta); t = vpTime::measureTimeMs() - t; std::cout << "Time to do color adjust: " << t << " ms" << std::endl; @@ -263,7 +267,7 @@ int main(int argc, const char **argv) // Equalize Histogram vpImage I_color_equalize_histogram; t = vpTime::measureTimeMs(); - vp::equalizeHistogram(I_color, I_color_equalize_histogram); + VISP_NAMESPACE_NAME::equalizeHistogram(I_color, I_color_equalize_histogram); t = vpTime::measureTimeMs() - t; std::cout << "Time to do color histogram equalization: " << t << " ms" << std::endl; @@ -275,7 +279,7 @@ int main(int argc, const char **argv) vpImage I_color_gamma_correction; float gamma = 2.2f; t = vpTime::measureTimeMs(); - vp::gammaCorrection(I_color, I_color_gamma_correction, gamma); + VISP_NAMESPACE_NAME::gammaCorrection(I_color, I_color_gamma_correction, gamma); t = vpTime::measureTimeMs() - t; std::cout << "Time to do color gamma correction: " << t << " ms" << std::endl; @@ -286,7 +290,7 @@ int main(int argc, const char **argv) // Retinex vpImage I_color_retinex; t = vpTime::measureTimeMs(); - vp::retinex(I_color, I_color_retinex); + VISP_NAMESPACE_NAME::retinex(I_color, I_color_retinex); t = vpTime::measureTimeMs() - t; std::cout << "Time to do color retinex: " << t << " ms" << std::endl; @@ -297,7 +301,7 @@ int main(int argc, const char **argv) // Stretch contrast vpImage I_color_stretch_contrast; t = vpTime::measureTimeMs(); - vp::stretchContrast(I_color, I_color_stretch_contrast); + VISP_NAMESPACE_NAME::stretchContrast(I_color, I_color_stretch_contrast); t = vpTime::measureTimeMs() - t; std::cout << "Time to do color contrast stretching: " << t << " ms" << std::endl; @@ -308,7 +312,7 @@ int main(int argc, const char **argv) // Stretch Contrast HSV vpImage I_color_stretch_contrast_HSV; t = vpTime::measureTimeMs(); - vp::stretchContrastHSV(I_color, I_color_stretch_contrast_HSV); + VISP_NAMESPACE_NAME::stretchContrastHSV(I_color, I_color_stretch_contrast_HSV); t = vpTime::measureTimeMs() - t; std::cout << "Time to do color HSV contrast stretching: " << t << " ms" << std::endl; @@ -320,7 +324,7 @@ int main(int argc, const char **argv) vpImage I_color_unsharp_mask; const float sigma = 1.0f; t = vpTime::measureTimeMs(); - vp::unsharpMask(I_color, I_color_unsharp_mask, sigma); + VISP_NAMESPACE_NAME::unsharpMask(I_color, I_color_unsharp_mask, sigma); t = vpTime::measureTimeMs() - t; std::cout << "Time to do color unsharp mask: " << t << " ms" << std::endl; @@ -331,7 +335,7 @@ int main(int argc, const char **argv) // CLAHE vpImage I_color_clahe; t = vpTime::measureTimeMs(); - vp::clahe(I_color, I_color_clahe, 50); + VISP_NAMESPACE_NAME::clahe(I_color, I_color_clahe, 50); t = vpTime::measureTimeMs() - t; std::cout << "Time to do color CLAHE: " << t << " ms" << std::endl; @@ -355,7 +359,7 @@ int main(int argc, const char **argv) vpImage I_adjust; beta = -20.0; t = vpTime::measureTimeMs(); - vp::adjust(I, I_adjust, alpha, beta); + VISP_NAMESPACE_NAME::adjust(I, I_adjust, alpha, beta); t = vpTime::measureTimeMs() - t; std::cout << "Time to do grayscale adjust: " << t << " ms" << std::endl; @@ -366,7 +370,7 @@ int main(int argc, const char **argv) // Equalize Histogram vpImage I_equalize_histogram; t = vpTime::measureTimeMs(); - vp::equalizeHistogram(I, I_equalize_histogram); + VISP_NAMESPACE_NAME::equalizeHistogram(I, I_equalize_histogram); t = vpTime::measureTimeMs() - t; std::cout << "Time to do grayscale histogram equalization: " << t << " ms" << std::endl; @@ -378,7 +382,7 @@ int main(int argc, const char **argv) vpImage I_gamma_correction; gamma = 1.8f; t = vpTime::measureTimeMs(); - vp::gammaCorrection(I, I_gamma_correction, gamma); + VISP_NAMESPACE_NAME::gammaCorrection(I, I_gamma_correction, gamma); t = vpTime::measureTimeMs() - t; std::cout << "Time to do grayscale gamma correction: " << t << " ms" << std::endl; @@ -389,7 +393,7 @@ int main(int argc, const char **argv) // Stretch contrast vpImage I_stretch_contrast; t = vpTime::measureTimeMs(); - vp::stretchContrast(I, I_stretch_contrast); + VISP_NAMESPACE_NAME::stretchContrast(I, I_stretch_contrast); t = vpTime::measureTimeMs() - t; std::cout << "Time to do grayscale contrast stretching: " << t << " ms" << std::endl; @@ -400,7 +404,7 @@ int main(int argc, const char **argv) // Unsharp Mask vpImage I_unsharp_mask; t = vpTime::measureTimeMs(); - vp::unsharpMask(I, I_unsharp_mask, sigma); + VISP_NAMESPACE_NAME::unsharpMask(I, I_unsharp_mask, sigma); t = vpTime::measureTimeMs() - t; std::cout << "Time to do grayscale unsharp mask: " << t << " ms" << std::endl; @@ -411,7 +415,7 @@ int main(int argc, const char **argv) // CLAHE vpImage I_clahe; t = vpTime::measureTimeMs(); - vp::clahe(I, I_clahe, 50); + VISP_NAMESPACE_NAME::clahe(I, I_clahe, 50); t = vpTime::measureTimeMs() - t; std::cout << "Time to do grayscale CLAHE: " << t << " ms" << std::endl; diff --git a/modules/io/include/visp3/io/vpDiskGrabber.h b/modules/io/include/visp3/io/vpDiskGrabber.h index 221dc48806..fc2f9a275d 100644 --- a/modules/io/include/visp3/io/vpDiskGrabber.h +++ b/modules/io/include/visp3/io/vpDiskGrabber.h @@ -45,6 +45,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpDiskGrabber * @@ -99,7 +101,7 @@ * } * } * \endcode - */ +*/ class VISP_EXPORT vpDiskGrabber : public vpFrameGrabber { private: @@ -269,4 +271,6 @@ class VISP_EXPORT vpDiskGrabber : public vpFrameGrabber void setStep(long step) { m_image_step = step; } }; +END_VISP_NAMESPACE + #endif diff --git a/modules/io/include/visp3/io/vpImageIo.h b/modules/io/include/visp3/io/vpImageIo.h index b2c400aa7f..2553761649 100644 --- a/modules/io/include/visp3/io/vpImageIo.h +++ b/modules/io/include/visp3/io/vpImageIo.h @@ -46,6 +46,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! \class vpImageIo @@ -185,4 +187,7 @@ class VISP_EXPORT vpImageIo static void writePNGtoMem(const vpImage &I, std::vector &buffer, int backend = IO_DEFAULT_BACKEND, bool saveAlpha = false); }; + +END_VISP_NAMESPACE + #endif diff --git a/modules/io/include/visp3/io/vpImageQueue.h b/modules/io/include/visp3/io/vpImageQueue.h index e7869d1036..d7c1da9c5b 100644 --- a/modules/io/include/visp3/io/vpImageQueue.h +++ b/modules/io/include/visp3/io/vpImageQueue.h @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpImageQueue @@ -282,6 +283,6 @@ template class vpImageQueue bool m_directory_to_create; bool m_recording_trigger; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/io/include/visp3/io/vpImageStorageWorker.h b/modules/io/include/visp3/io/vpImageStorageWorker.h index 1eb0e79b2b..d192ecdfa3 100644 --- a/modules/io/include/visp3/io/vpImageStorageWorker.h +++ b/modules/io/include/visp3/io/vpImageStorageWorker.h @@ -41,6 +41,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpImageStorageWorker @@ -132,6 +133,6 @@ template class vpImageStorageWorker std::ofstream m_ofs_data; bool m_data_file_created; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/io/include/visp3/io/vpJsonArgumentParser.h b/modules/io/include/visp3/io/vpJsonArgumentParser.h index 4cee71ee34..64ad2b9f50 100644 --- a/modules/io/include/visp3/io/vpJsonArgumentParser.h +++ b/modules/io/include/visp3/io/vpJsonArgumentParser.h @@ -33,6 +33,7 @@ #ifndef _vpJsonArgumentParser_h_ #define _vpJsonArgumentParser_h_ + #include #if defined(VISP_HAVE_NLOHMANN_JSON) @@ -66,6 +67,9 @@ nlohmann::json convertCommandLineArgument(const std::string &arg) nlohmann::json j = arg; return j; } + +BEGIN_VISP_NAMESPACE + /*! \class vpJsonArgumentParser \ingroup module_io_cmd_parser @@ -78,53 +82,53 @@ nlohmann::json convertCommandLineArgument(const std::string &arg) A very basic program that uses both a JSON file and command line arguments can be found below: \code{.cpp} - #include - #include - int main(int argc, char* argv[]) - { - double d = 1.0; - std::string s = "Default"; - - vpJsonArgumentParser parser("Example program for arguments with vpJsonArgumentParser", "config", "/"); - - parser.add_argument("scalar", d, true, "An important value: must be defined by the user") - .add_argument("string", s, false, "An optional value: if left unspecified, will default to its initialized value (\"Default\")") - .parse(argc, argv); - - std::cout << "Scalar = " << d << std::endl; - std::cout << "String = " << s << std::endl; - } + #include + #include + int main(int argc, char* argv[]) + { + double d = 1.0; + std::string s = "Default"; + + vpJsonArgumentParser parser("Example program for arguments with vpJsonArgumentParser", "config", "/"); + + parser.add_argument("scalar", d, true, "An important value: must be defined by the user") + .add_argument("string", s, false, "An optional value: if left unspecified, will default to its initialized value (\"Default\")") + .parse(argc, argv); + + std::cout << "Scalar = " << d << std::endl; + std::cout << "String = " << s << std::endl; + } \endcode Compiling this sample and calling the program with the arguments from the command line would yield: \code{.sh} - $ ./program scalar 2.0 string "A new value" - Scalar = 2.0 - String = a new value - $ ./program scalar 2.0 - Scalar = 2.0 - String = default + $ ./program scalar 2.0 string "A new value" + Scalar = 2.0 + String = a new value + $ ./program scalar 2.0 + Scalar = 2.0 + String = default \endcode Here the arguments are specified from the command line. Since the "string" argument is optional, it does not have to be specified. For programs with more arguments it is helpful to use a JSON file that contains a base configuration. For the program above, a JSON file could look like: \code{.json} - { - "scalar": 3.0, - "string": "Some base value" - } + { + "scalar": 3.0, + "string": "Some base value" + } \endcode we could then call the program with: \code{.sh} - $ ./program config my_settings.json - Scalar = 3.0 - String = Some base value + $ ./program config my_settings.json + Scalar = 3.0 + String = Some base value \endcode The values contained in the JSON file can be overridden with command line arguments \code{.sh} - $ ./program config my_settings.json scalar 5 - Scalar = 5.0 - String = Some base value + $ ./program config my_settings.json scalar 5 + Scalar = 5.0 + String = Some base value \endcode The program can also be called with the "-h" or "--help" argument to display the help associated to the arguments, as well as an example json configuration file @@ -261,6 +265,8 @@ class VISP_EXPORT vpJsonArgumentParser nlohmann::json exampleJson; // Example JSON argument file: displayed when user calls for help }; +END_VISP_NAMESPACE + #endif // VISP_HAVE_NLOHMANN_JSON #endif diff --git a/modules/io/include/visp3/io/vpKeyboard.h b/modules/io/include/visp3/io/vpKeyboard.h index 6026faeebd..a96ed19a32 100644 --- a/modules/io/include/visp3/io/vpKeyboard.h +++ b/modules/io/include/visp3/io/vpKeyboard.h @@ -49,6 +49,7 @@ #include #endif // defined UNIX +BEGIN_VISP_NAMESPACE /*! \class vpKeyboard @@ -97,5 +98,5 @@ class VISP_EXPORT vpKeyboard struct termios initial_settings, new_settings; #endif // defined UNIX }; - +END_VISP_NAMESPACE #endif diff --git a/modules/io/include/visp3/io/vpParallelPort.h b/modules/io/include/visp3/io/vpParallelPort.h index 043aed23ab..8dab7b75d7 100644 --- a/modules/io/include/visp3/io/vpParallelPort.h +++ b/modules/io/include/visp3/io/vpParallelPort.h @@ -52,6 +52,7 @@ #include +BEGIN_VISP_NAMESPACE /*! \class vpParallelPort @@ -92,7 +93,7 @@ class VISP_EXPORT vpParallelPort int fd; // parallel port descriptor std::string device; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/io/include/visp3/io/vpParallelPortException.h b/modules/io/include/visp3/io/vpParallelPortException.h index f7ff7fd38e..39c8312ca1 100644 --- a/modules/io/include/visp3/io/vpParallelPortException.h +++ b/modules/io/include/visp3/io/vpParallelPortException.h @@ -46,12 +46,13 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpParallelPortException * * \brief Error that can be emitted by the vpParallelPort class and its * derivates. - */ +*/ class VISP_EXPORT vpParallelPortException : public vpException { public: @@ -88,5 +89,5 @@ class VISP_EXPORT vpParallelPortException : public vpException */ explicit vpParallelPortException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/io/include/visp3/io/vpParseArgv.h b/modules/io/include/visp3/io/vpParseArgv.h index aa83214d54..e93e2c2832 100644 --- a/modules/io/include/visp3/io/vpParseArgv.h +++ b/modules/io/include/visp3/io/vpParseArgv.h @@ -29,6 +29,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! \class vpParseArgv \ingroup module_io_cmd_parser @@ -39,102 +41,102 @@ name with more than one character. \code -#include -#include -#include + #include + #include + #include -// Usage : [-bool] [-int ] [-long ] -// [-float ] [-double ] [-string ] [-h] -int main(int argc, const char ** argv) -{ - // Variables to set by command line parsing - bool b_val = false; - int i_val = 10; - long l_val = 123456; - float f_val = 0.1f; - double d_val = M_PI; - char *s_val; - - // Parse the command line to set the variables - vpParseArgv::vpArgvInfo argTable[] = + // Usage : [-bool] [-int ] [-long ] + // [-float ] [-double ] [-string ] [-h] + int main(int argc, const char ** argv) { - {"-bool", vpParseArgv::ARGV_CONSTANT_BOOL, 0, (char *) &b_val, - "Flag enabled."}, - {"-int", vpParseArgv::ARGV_INT, (char*) nullptr, (char *) &i_val, - "An integer value."}, - {"-long", vpParseArgv::ARGV_LONG, (char*) nullptr, (char *) &l_val, - "An integer value."}, - {"-float", vpParseArgv::ARGV_FLOAT, (char*) nullptr, (char *) &f_val, - "A float value."}, - {"-double", vpParseArgv::ARGV_DOUBLE, (char*) nullptr, (char *) &d_val, - "A double value."}, - {"-string", vpParseArgv::ARGV_STRING, (char*) nullptr, (char *) &s_val, - "A string value."}, - {"-h", vpParseArgv::ARGV_HELP, (char*) nullptr, (char *) nullptr, - "Print the help."}, - {(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)) { - return (false); - } + // Variables to set by command line parsing + bool b_val = false; + int i_val = 10; + long l_val = 123456; + float f_val = 0.1f; + double d_val = M_PI; + char *s_val; + + // Parse the command line to set the variables + vpParseArgv::vpArgvInfo argTable[] = + { + {"-bool", vpParseArgv::ARGV_CONSTANT_BOOL, 0, (char *) &b_val, + "Flag enabled."}, + {"-int", vpParseArgv::ARGV_INT, (char*) nullptr, (char *) &i_val, + "An integer value."}, + {"-long", vpParseArgv::ARGV_LONG, (char*) nullptr, (char *) &l_val, + "An integer value."}, + {"-float", vpParseArgv::ARGV_FLOAT, (char*) nullptr, (char *) &f_val, + "A float value."}, + {"-double", vpParseArgv::ARGV_DOUBLE, (char*) nullptr, (char *) &d_val, + "A double value."}, + {"-string", vpParseArgv::ARGV_STRING, (char*) nullptr, (char *) &s_val, + "A string value."}, + {"-h", vpParseArgv::ARGV_HELP, (char*) nullptr, (char *) nullptr, + "Print the help."}, + {(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)) { + return (false); + } - // b_val, i_val, l_val, f_val, d_val, s_val may have new values -} + // b_val, i_val, l_val, f_val, d_val, s_val may have new values + } \endcode The code below shows an other way to parse command line arguments using vpParseArgv class. Here command line options are only one character long. \code -#include -#include -#include -#include + #include + #include + #include + #include -// List of allowed command line options -#define GETOPTARGS "bi:l:f:d:h" // double point mean here that the preceding option request an argument + // List of allowed command line options + #define GETOPTARGS "bi:l:f:d:h" // double point mean here that the preceding option request an argument -// Usage : [-b] [-i ] [-l ] -// [-f ] [-d ] [-s ] [-h] -int main(int argc, const char ** argv) -{ - // Variables to set by command line parsing - bool b_val = false; - int i_val = 10; - long l_val = 123456; - float f_val = 0.1f; - double d_val = M_PI; - std::string s_val; - - // Parse the command line to set the variables - const char *optarg; - int c; - while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg)) > 1) { - - switch (c) { - case 'b': b_val = true; break; - case 'i': i_val = atoi(optarg); break; - case 'l': l_val = atol(optarg); break; - case 'f': f_val = static_cast(atof(optarg)); break; - case 'd': d_val = atof(optarg); break; - case 's': s_val = std::string(optarg); break; - case 'h': printf("Usage: ...\n"); return EXIT_SUCCESS; break; - - default: - printf("Usage: ...\n"); return EXIT_SUCCESS; break; + // Usage : [-b] [-i ] [-l ] + // [-f ] [-d ] [-s ] [-h] + int main(int argc, const char ** argv) + { + // Variables to set by command line parsing + bool b_val = false; + int i_val = 10; + long l_val = 123456; + float f_val = 0.1f; + double d_val = M_PI; + std::string s_val; + + // Parse the command line to set the variables + const char *optarg; + int c; + while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg)) > 1) { + + switch (c) { + case 'b': b_val = true; break; + case 'i': i_val = atoi(optarg); break; + case 'l': l_val = atol(optarg); break; + case 'f': f_val = static_cast(atof(optarg)); break; + case 'd': d_val = atof(optarg); break; + case 's': s_val = std::string(optarg); break; + case 'h': printf("Usage: ...\n"); return EXIT_SUCCESS; break; + + default: + printf("Usage: ...\n"); return EXIT_SUCCESS; break; + } + } + if ((c == 1) || (c == -1)) { + // standalone param or error + printf("Usage: ...\n"); + return EXIT_FAILURE; } - } - if ((c == 1) || (c == -1)) { - // standalone param or error - printf("Usage: ...\n"); - return EXIT_FAILURE; - } - // b_val, i_val, l_val, f_val, d_val, s_val may have new values -} + // b_val, i_val, l_val, f_val, d_val, s_val may have new values + } \endcode */ @@ -145,7 +147,8 @@ class VISP_EXPORT vpParseArgv /*! Legal values for the type field of a vpArgvInfo. */ - typedef enum { + typedef enum + { ARGV_CONSTANT, ///< Stand alone argument. Same as vpParseArgv::ARGV_CONSTANT_INT. ARGV_CONSTANT_INT, ///< Stand alone argument associated to an int var that is set to 1. ARGV_CONSTANT_BOOL, ///< Stand alone argument associated to a bool var that is set to true. @@ -164,7 +167,8 @@ class VISP_EXPORT vpParseArgv /*! Flag bits. */ - typedef enum { + typedef enum + { ARGV_NO_DEFAULTS = 0x1, ///< No default options like -help. ARGV_NO_LEFTOVERS = 0x2, ///< Print an error message if an option is not in the argument list. ARGV_NO_ABBREV = 0x4, ///< No abrevation. Print an error message if an option is abrevated (ie "-i" in place of @@ -178,7 +182,8 @@ class VISP_EXPORT vpParseArgv Structure used to specify how to handle argv options. */ - typedef struct { + typedef struct + { const char *key; ///< The key string that flags the option in the argv array. vpArgvType type; ///< Indicates option type. const char *src; ///< Value to be used in setting dst; usage depends on type. @@ -196,4 +201,6 @@ class VISP_EXPORT vpParseArgv static void printUsage(vpArgvInfo *argTable, int flags); }; +END_VISP_NAMESPACE + #endif diff --git a/modules/io/include/visp3/io/vpVideoReader.h b/modules/io/include/visp3/io/vpVideoReader.h index a6ea82161e..dad5010101 100644 --- a/modules/io/include/visp3/io/vpVideoReader.h +++ b/modules/io/include/visp3/io/vpVideoReader.h @@ -48,6 +48,8 @@ #include #endif +BEGIN_VISP_NAMESPACE + /*! * \class vpVideoReader * @@ -159,7 +161,7 @@ * return 0; * } * \endcode - */ +*/ class VISP_EXPORT vpVideoReader : public vpFrameGrabber { @@ -375,4 +377,6 @@ class VISP_EXPORT vpVideoReader : public vpFrameGrabber void getProperties(); }; +END_VISP_NAMESPACE + #endif diff --git a/modules/io/include/visp3/io/vpVideoWriter.h b/modules/io/include/visp3/io/vpVideoWriter.h index 85d6cdd977..3e8e5d05ed 100644 --- a/modules/io/include/visp3/io/vpVideoWriter.h +++ b/modules/io/include/visp3/io/vpVideoWriter.h @@ -48,6 +48,8 @@ #include #endif +BEGIN_VISP_NAMESPACE + /*! \class vpVideoWriter @@ -258,4 +260,6 @@ class VISP_EXPORT vpVideoWriter static std::string getExtension(const std::string &filename); }; +END_VISP_NAMESPACE + #endif diff --git a/modules/io/src/image/private/vpImageIoBackend.h b/modules/io/src/image/private/vpImageIoBackend.h index 56fcc2e3ba..3cce610e29 100644 --- a/modules/io/src/image/private/vpImageIoBackend.h +++ b/modules/io/src/image/private/vpImageIoBackend.h @@ -41,6 +41,8 @@ #include +BEGIN_VISP_NAMESPACE + // Portable FloatMap format (PFM) // Portable Graymap format (PGM) // Portable Pixmap format (PPM) @@ -133,4 +135,6 @@ void writePNGtoMemStb(const vpImage &I, std::vector &I, std::vector &buffer, bool saveAlpha); #endif +END_VISP_NAMESPACE + #endif diff --git a/modules/io/src/image/private/vpImageIoLibjpeg.cpp b/modules/io/src/image/private/vpImageIoLibjpeg.cpp index 692183d742..29ea3cc599 100644 --- a/modules/io/src/image/private/vpImageIoLibjpeg.cpp +++ b/modules/io/src/image/private/vpImageIoLibjpeg.cpp @@ -50,6 +50,7 @@ #if defined(VISP_HAVE_JPEG) +BEGIN_VISP_NAMESPACE /*! Write the content of the image bitmap in the file which name is given by \e filename. This function writes a JPEG file. @@ -332,4 +333,7 @@ void readJPEGLibjpeg(vpImage &I, const std::string &filename) jpeg_destroy_decompress(&cinfo); fclose(file); } + +END_VISP_NAMESPACE + #endif diff --git a/modules/io/src/image/private/vpImageIoLibpng.cpp b/modules/io/src/image/private/vpImageIoLibpng.cpp index e7b3afcc5b..e5c2aae071 100644 --- a/modules/io/src/image/private/vpImageIoLibpng.cpp +++ b/modules/io/src/image/private/vpImageIoLibpng.cpp @@ -49,6 +49,7 @@ #if defined(VISP_HAVE_PNG) +BEGIN_VISP_NAMESPACE /*! Write the content of the image bitmap in the file which name is given by \e filename. This function writes a PNG file. @@ -598,4 +599,7 @@ void readPNGLibpng(vpImage &I, const std::string &filename) png_destroy_read_struct(&png_ptr, &info_ptr, nullptr); fclose(file); } + +END_VISP_NAMESPACE + #endif diff --git a/modules/io/src/image/private/vpImageIoOpenCV.cpp b/modules/io/src/image/private/vpImageIoOpenCV.cpp index dceed26214..8fc3d9e7d5 100644 --- a/modules/io/src/image/private/vpImageIoOpenCV.cpp +++ b/modules/io/src/image/private/vpImageIoOpenCV.cpp @@ -59,6 +59,7 @@ #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) \ && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) +BEGIN_VISP_NAMESPACE /*! Read the contents of the image file, allocate memory for the corresponding gray level image, if necessary convert the data in @@ -302,4 +303,6 @@ void writePNGtoMemOpenCV(const vpImage &I_color, std::vector #include +BEGIN_VISP_NAMESPACE + #ifndef DOXYGEN_SHOULD_SKIP_THIS /*! * Decode the PNM image header. @@ -837,3 +839,5 @@ void vp_writePPM(const vpImage &I, const std::string &filename) fflush(f); fclose(f); } + +END_VISP_NAMESPACE diff --git a/modules/io/src/image/private/vpImageIoSimd.cpp b/modules/io/src/image/private/vpImageIoSimd.cpp index 261af7012f..dce0cb3f90 100644 --- a/modules/io/src/image/private/vpImageIoSimd.cpp +++ b/modules/io/src/image/private/vpImageIoSimd.cpp @@ -42,6 +42,8 @@ #include "vpImageIoBackend.h" #include +BEGIN_VISP_NAMESPACE + void readSimdlib(vpImage &I, const std::string &filename) { size_t stride = 0, width = 0, height = 0; @@ -91,4 +93,7 @@ void writePNGSimdlib(const vpImage &I, const std::string &filename) SimdImageSaveToFile((const uint8_t *)I.bitmap, I.getWidth() * 4, I.getWidth(), I.getHeight(), SimdPixelFormatRgba32, SimdImageFilePng, 90, filename.c_str()); } + +END_VISP_NAMESPACE + #endif diff --git a/modules/io/src/image/private/vpImageIoStb.cpp b/modules/io/src/image/private/vpImageIoStb.cpp index 5db5a9f3bd..c755992af3 100644 --- a/modules/io/src/image/private/vpImageIoStb.cpp +++ b/modules/io/src/image/private/vpImageIoStb.cpp @@ -57,6 +57,8 @@ #define STB_IMAGE_WRITE_IMPLEMENTATION #include +BEGIN_VISP_NAMESPACE + void readStb(vpImage &I, const std::string &filename) { int width = 0, height = 0, channels = 0; @@ -266,4 +268,7 @@ void writePNGtoMemStb(const vpImage &I_color, std::vector #endif } } + +END_VISP_NAMESPACE + #endif diff --git a/modules/io/src/image/private/vpImageIoTinyEXR.cpp b/modules/io/src/image/private/vpImageIoTinyEXR.cpp index d26e5078aa..7aa7a7a03b 100644 --- a/modules/io/src/image/private/vpImageIoTinyEXR.cpp +++ b/modules/io/src/image/private/vpImageIoTinyEXR.cpp @@ -51,6 +51,8 @@ #define TINYEXR_IMPLEMENTATION #include +BEGIN_VISP_NAMESPACE + void readEXRTiny(vpImage &I, const std::string &filename) { EXRVersion exr_version; @@ -319,4 +321,6 @@ void writeEXRTiny(const vpImage &I, const std::string &filename) free(header.pixel_types); } +END_VISP_NAMESPACE + #endif diff --git a/modules/io/src/image/vpImageIo.cpp b/modules/io/src/image/vpImageIo.cpp index 567969e0d3..e66dcc64fe 100644 --- a/modules/io/src/image/vpImageIo.cpp +++ b/modules/io/src/image/vpImageIo.cpp @@ -41,6 +41,10 @@ #include "private/vpImageIoBackend.h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + vpImageIo::vpImageFormatType vpImageIo::getFormat(const std::string &filename) { std::string ext = vpImageIo::getExtension(filename); diff --git a/modules/io/src/parallel-port/vpParallelPort.cpp b/modules/io/src/parallel-port/vpParallelPort.cpp index 26d39c4533..92827e4f90 100644 --- a/modules/io/src/parallel-port/vpParallelPort.cpp +++ b/modules/io/src/parallel-port/vpParallelPort.cpp @@ -31,6 +31,11 @@ * Parallel port management. */ +/*! + \file vpParallelPort.cpp + \brief Parallel port management under unix. +*/ + #include #ifdef VISP_HAVE_PARPORT @@ -43,11 +48,9 @@ #include -/*! - \file vpParallelPort.cpp - \brief Parallel port management under unix. -*/ + +BEGIN_VISP_NAMESPACE static unsigned char vpParallelPortData; /*! @@ -157,7 +160,7 @@ void vpParallelPort::close() throw(vpParallelPortException(vpParallelPortException::closing, "Can't close the parallel port")); } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpParallelPort.cpp.o) has no symbols void dummy_vpParallelPort() { }; diff --git a/modules/io/src/tools/vpJsonArgumentParser.cpp b/modules/io/src/tools/vpJsonArgumentParser.cpp index 9c605fd767..f38e0cbd91 100644 --- a/modules/io/src/tools/vpJsonArgumentParser.cpp +++ b/modules/io/src/tools/vpJsonArgumentParser.cpp @@ -27,13 +27,14 @@ * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. */ + +#include #include #include -#include #include - #if defined(VISP_HAVE_NLOHMANN_JSON) +BEGIN_VISP_NAMESPACE using json = nlohmann::json; //! json namespace shortcut @@ -150,4 +151,6 @@ void vpJsonArgumentParser::parse(int argc, const char *argv[]) } } +END_VISP_NAMESPACE + #endif diff --git a/modules/io/src/tools/vpKeyboard.cpp b/modules/io/src/tools/vpKeyboard.cpp index 76c202b0c8..d0efc4c9ab 100644 --- a/modules/io/src/tools/vpKeyboard.cpp +++ b/modules/io/src/tools/vpKeyboard.cpp @@ -31,6 +31,11 @@ * Keyboard management. */ +/*! + \file vpKeyboard.cpp + \brief Keyboard management under unix. +*/ + #include #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) @@ -41,10 +46,7 @@ #include #include -/*! - \file vpKeyboard.cpp - \brief Keyboard management under unix. -*/ +BEGIN_VISP_NAMESPACE /*! Activates the raw mode to read keys in an non blocking way. @@ -56,11 +58,9 @@ vpKeyboard::vpKeyboard() init(); } #else -{} +{ } #endif - - /*! Stops the raw mode. */ @@ -72,7 +72,6 @@ vpKeyboard::~vpKeyboard() } /*! - Get the hit key. kbhit() indicates if a key was hitten. */ int vpKeyboard::getchar() @@ -89,8 +88,6 @@ int vpKeyboard::getchar() } /*! - - \return 1 : if a key was hit. */ int vpKeyboard::kbhit() @@ -161,5 +158,6 @@ void vpKeyboard::setRawMode(bool active) tcsetattr(STDIN_FILENO, TCSANOW, &initial_settings); } } - #endif // defined UNIX + +END_VISP_NAMESPACE diff --git a/modules/io/src/tools/vpParseArgv.cpp b/modules/io/src/tools/vpParseArgv.cpp index 5dcc3755c1..075d03e983 100644 --- a/modules/io/src/tools/vpParseArgv.cpp +++ b/modules/io/src/tools/vpParseArgv.cpp @@ -32,6 +32,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /* * Default table of argument descriptors. These are normally available * in every application. @@ -39,7 +41,7 @@ vpParseArgv::vpArgvInfo vpParseArgv::defaultTable[2] = { {"-help", ARGV_HELP, (char *)nullptr, (char *)nullptr, "Print summary of command-line options and abort.\n"}, - {nullptr, ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr}}; + {nullptr, ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr} }; int (*handlerProc1)(const char *dst, const char *key, const char *argument); int (*handlerProc2)(const char *dst, const char *key, int valargc, const char **argument); @@ -94,7 +96,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i if (flags & ARGV_DONT_SKIP_FIRST_ARG) { srcIndex = dstIndex = 0; argc = *argcPtr; - } else { + } + else { srcIndex = dstIndex = 1; argc = *argcPtr - 1; } @@ -116,7 +119,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned int i = 0; i < 2; ++i) { if (i == 0) { infoPtr = argTable; - } else { + } + else { infoPtr = defaultTable; } for (; infoPtr->type != ARGV_END; ++infoPtr) { @@ -175,7 +179,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { char *endPtr = nullptr; *(((int *)infoPtr->dst) + i) = (int)strtol(argv[srcIndex], &endPtr, 0); @@ -195,7 +200,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { char *endPtr = nullptr; *(((long *)infoPtr->dst) + i) = strtol(argv[srcIndex], &endPtr, 0); @@ -215,7 +221,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { *(((const char **)infoPtr->dst) + i) = argv[srcIndex]; srcIndex++; argc--; @@ -232,7 +239,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { char *endPtr; *(((float *)infoPtr->dst) + i) = (float)strtod(argv[srcIndex], &endPtr); // Here we use strtod @@ -253,7 +261,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { char *endPtr; *(((double *)infoPtr->dst) + i) = strtod(argv[srcIndex], &endPtr); @@ -379,7 +388,8 @@ void vpParseArgv::printUsage(vpArgvInfo *argTable, int flags) while (numSpaces > 0) { if (numSpaces >= NUM_SPACES) { FPRINTF(stderr, "%s", spaces); - } else { + } + else { FPRINTF(stderr, "%s", spaces + NUM_SPACES - numSpaces); } numSpaces -= NUM_SPACES; @@ -522,38 +532,45 @@ int vpParseArgv::parse(int argc, const char **argv, const char *validOpts, const // next argv is the param iArg++; pszParam = psz; - } else { - // reached end of args looking for param - // option specified without parameter + } + else { + // reached end of args looking for param + // option specified without parameter chOpt = -1; pszParam = &(argv[iArg][0]); } - } else { - // param is attached to option + } + else { + // param is attached to option pszParam = psz; } - } else { - // option is alone, has no parameter } - } else { - // option specified is not in list of valid options + else { + // option is alone, has no parameter + } + } + else { + // option specified is not in list of valid options chOpt = -1; pszParam = &(argv[iArg][0]); } - } else { - // though option specifier was given, option character - // is not alpha or was was not specified + } + else { + // though option specifier was given, option character + // is not alpha or was was not specified chOpt = -1; pszParam = &(argv[iArg][0]); } - } else { - // standalone arg given with no option specifier + } + else { + // standalone arg given with no option specifier chOpt = 1; pszParam = &(argv[iArg][0]); } - } else { - // end of argument list + } + else { + // end of argument list chOpt = 0; } @@ -561,3 +578,5 @@ int vpParseArgv::parse(int argc, const char **argv, const char *validOpts, const *param = pszParam; return (chOpt); } + +END_VISP_NAMESPACE diff --git a/modules/io/src/video/vpDiskGrabber.cpp b/modules/io/src/video/vpDiskGrabber.cpp index f8c923d542..1e5a84653b 100644 --- a/modules/io/src/video/vpDiskGrabber.cpp +++ b/modules/io/src/video/vpDiskGrabber.cpp @@ -33,6 +33,8 @@ #include +BEGIN_VISP_NAMESPACE + vpDiskGrabber::vpDiskGrabber() : m_image_number(0), m_image_number_next(0), m_image_step(1), m_number_of_zero(0), m_directory("/tmp"), m_base_name("I"), m_extension("pgm"), m_use_generic_name(false), m_generic_name("empty") @@ -247,3 +249,5 @@ void vpDiskGrabber::setGenericName(const std::string &generic_name) m_generic_name = generic_name; m_use_generic_name = true; } + +END_VISP_NAMESPACE diff --git a/modules/io/src/video/vpVideoReader.cpp b/modules/io/src/video/vpVideoReader.cpp index 600a63695c..4f94da9773 100644 --- a/modules/io/src/video/vpVideoReader.cpp +++ b/modules/io/src/video/vpVideoReader.cpp @@ -43,7 +43,8 @@ #include #include #include -#include // numeric_limits + +BEGIN_VISP_NAMESPACE /*! Basic constructor. @@ -906,3 +907,5 @@ bool vpVideoReader::isVideoFormat() const return false; } } + +END_VISP_NAMESPACE diff --git a/modules/io/src/video/vpVideoWriter.cpp b/modules/io/src/video/vpVideoWriter.cpp index d21829e200..f38d889ddd 100644 --- a/modules/io/src/video/vpVideoWriter.cpp +++ b/modules/io/src/video/vpVideoWriter.cpp @@ -44,16 +44,18 @@ #include #endif +BEGIN_VISP_NAMESPACE + /*! Basic constructor. */ vpVideoWriter::vpVideoWriter() : #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) - m_writer(), m_framerate(25.0), + m_writer(), m_framerate(25.0), #endif - m_formatType(FORMAT_UNKNOWN), m_videoName(), m_frameName(), m_initFileName(false), m_isOpen(false), m_frameCount(0), - m_firstFrame(0), m_width(0), m_height(0), m_frameStep(1) + m_formatType(FORMAT_UNKNOWN), m_videoName(), m_frameName(), m_initFileName(false), m_isOpen(false), m_frameCount(0), + m_firstFrame(0), m_width(0), m_height(0), m_frameStep(1) { #if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) #if (VISP_HAVE_OPENCV_VERSION >= 0x030000) @@ -67,7 +69,7 @@ vpVideoWriter::vpVideoWriter() /*! Basic destructor. */ -vpVideoWriter::~vpVideoWriter() {} +vpVideoWriter::~vpVideoWriter() { } /*! It enables to set the path and the name of the video or sequence of images @@ -121,8 +123,9 @@ void vpVideoWriter::open(vpImage &I) m_formatType == FORMAT_PNG) { m_width = I.getWidth(); m_height = I.getHeight(); - } else if (m_formatType == FORMAT_AVI || m_formatType == FORMAT_MPEG || m_formatType == FORMAT_MPEG4 || - m_formatType == FORMAT_MOV) { + } + else if (m_formatType == FORMAT_AVI || m_formatType == FORMAT_MPEG || m_formatType == FORMAT_MPEG4 || + m_formatType == FORMAT_MOV) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) m_writer = cv::VideoWriter(m_videoName, m_fourcc, m_framerate, cv::Size(static_cast(I.getWidth()), static_cast(I.getHeight()))); @@ -160,8 +163,9 @@ void vpVideoWriter::open(vpImage &I) m_formatType == FORMAT_PNG) { m_width = I.getWidth(); m_height = I.getHeight(); - } else if (m_formatType == FORMAT_AVI || m_formatType == FORMAT_MPEG || m_formatType == FORMAT_MPEG4 || - m_formatType == FORMAT_MOV) { + } + else if (m_formatType == FORMAT_AVI || m_formatType == FORMAT_MPEG || m_formatType == FORMAT_MPEG4 || + m_formatType == FORMAT_MOV) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) m_writer = cv::VideoWriter(m_videoName, m_fourcc, m_framerate, cv::Size(static_cast(I.getWidth()), static_cast(I.getHeight()))); @@ -200,7 +204,8 @@ void vpVideoWriter::saveFrame(vpImage &I) snprintf(name, FILENAME_MAX, m_videoName.c_str(), m_frameCount); vpImageIo::write(I, name); m_frameName = std::string(name); - } else { + } + else { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) cv::Mat matFrame; vpImageConvert::convert(I, matFrame); @@ -232,7 +237,8 @@ void vpVideoWriter::saveFrame(vpImage &I) snprintf(name, FILENAME_MAX, m_videoName.c_str(), m_frameCount); vpImageIo::write(I, name); m_frameName = std::string(name); - } else { + } + else { #if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) #if (VISP_HAVE_OPENCV_VERSION >= 0x030000) cv::Mat matFrame, rgbMatFrame; @@ -339,3 +345,5 @@ void vpVideoWriter::setFirstFrameIndex(int first_frame) } m_firstFrame = first_frame; } + +END_VISP_NAMESPACE diff --git a/modules/io/test/image-with-dataset/perfImageLoadSave.cpp b/modules/io/test/image-with-dataset/perfImageLoadSave.cpp index 815525b09f..3a039d903f 100644 --- a/modules/io/test/image-with-dataset/perfImageLoadSave.cpp +++ b/modules/io/test/image-with-dataset/perfImageLoadSave.cpp @@ -44,6 +44,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + static std::string ipath = vpIoTools::getViSPImagesDataPath(); static std::vector paths { ipath + "/Solvay/Solvay_conference_1927_Version2_640x440", diff --git a/modules/io/test/image-with-dataset/testImageLoadSave.cpp b/modules/io/test/image-with-dataset/testImageLoadSave.cpp index 3d3ae6d855..72b8190888 100644 --- a/modules/io/test/image-with-dataset/testImageLoadSave.cpp +++ b/modules/io/test/image-with-dataset/testImageLoadSave.cpp @@ -44,6 +44,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + static const std::string ipath = vpIoTools::getViSPImagesDataPath(); static const std::string path = ipath + "/Solvay/Solvay_conference_1927_Version2_640x440"; diff --git a/modules/io/test/testJsonArgumentParser.cpp b/modules/io/test/testJsonArgumentParser.cpp index be315000a0..9a783aea74 100644 --- a/modules/io/test/testJsonArgumentParser.cpp +++ b/modules/io/test/testJsonArgumentParser.cpp @@ -49,6 +49,10 @@ using json = nlohmann::json; //! json namespace shortcut #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + std::pair> convertToArgcAndArgv(const std::vector &args) { std::vector argvs; @@ -93,7 +97,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") json j = loadJson(jsonPath); modify(j); saveJson(j, jsonPath); - }; + }; GIVEN("Some specific arguments") { @@ -139,7 +143,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") THEN("Calling the parser without any argument fails") { const int argc = 1; - const char *argv [] = { + const char *argv[] = { "program" }; @@ -149,7 +153,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") THEN("Calling the parser with only the JSON file works") { const int argc = 3; - const char *argv [] = { + const char *argv[] = { "program", "--config", jsonPath.c_str() @@ -165,7 +169,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") THEN("Calling the parser by specifying the json argument but leaving the file path empty throws an error") { const int argc = 2; - const char *argv [] = { + const char *argv[] = { "program", "--config", }; @@ -176,7 +180,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") const int argc = 3; for (const auto &jsonElem : j.items()) { modifyJson([&jsonElem](json &j) { j.erase(jsonElem.key()); }); - const char *argv [] = { + const char *argv[] = { "program", "--config", jsonPath.c_str() @@ -189,7 +193,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") const int argc = 3; for (const auto &jsonElem : j.items()) { modifyJson([&jsonElem](json &j) { j[jsonElem.key()] = nullptr; }); - const char *argv [] = { + const char *argv[] = { "program", "--config", jsonPath.c_str() @@ -200,7 +204,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") THEN("Calling the parser with an invalid json file path throws an error") { const int argc = 3; - const char *argv [] = { + const char *argv[] = { "program", "--config", "some_invalid_json/file/path.json" @@ -289,7 +293,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") { float bcopy = b; const int argc = 1; - const char *argv [] = { + const char *argv[] = { "program" }; @@ -308,7 +312,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") { float bcopy = b; const int argc = 1; - const char *argv [] = { + const char *argv[] = { "program" }; @@ -351,7 +355,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") } } -int main(int argc, char *argv []) +int main(int argc, char *argv[]) { Catch::Session session; // There must be exactly one instance session.applyCommandLine(argc, argv); diff --git a/modules/io/test/video/testVideo.cpp b/modules/io/test/video/testVideo.cpp index 4d105fd960..734bc4e96f 100644 --- a/modules/io/test/video/testVideo.cpp +++ b/modules/io/test/video/testVideo.cpp @@ -48,6 +48,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + static long first_frame = 100; static int frame_step = 2; static unsigned int nframes = 3; @@ -72,7 +76,8 @@ bool test_createSequence(vpImage &I, const std::string &videoname, unsigne std::cout << "Frame saved in: " << writer.getFrameName() << std::endl; } return true; - } catch (...) { + } + catch (...) { return false; } } @@ -177,7 +182,8 @@ int main(int argc, char *argv[]) try { // Create the dirname vpIoTools::makeDirectory(tmp); - } catch (...) { + } + catch (...) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << tmp << std::endl; } diff --git a/modules/robot/include/visp3/robot/vpAfma4.h b/modules/robot/include/visp3/robot/vpAfma4.h index f203268fe7..27a3831f30 100644 --- a/modules/robot/include/visp3/robot/vpAfma4.h +++ b/modules/robot/include/visp3/robot/vpAfma4.h @@ -99,17 +99,19 @@ */ #include +#include #include #include #include #include +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpAfma4 { public: vpAfma4(); /*! Destructor that does nothing. */ - virtual ~vpAfma4(){}; + virtual ~vpAfma4() { }; /** @name Inherited functionalities from vpAfma4 */ //@{ @@ -150,7 +152,7 @@ class VISP_EXPORT vpAfma4 vpHomogeneousMatrix _eMc; // Camera extrinsic parameters: effector to camera }; - +END_VISP_NAMESPACE /* * Local variables: * c-basic-offset: 2 diff --git a/modules/robot/include/visp3/robot/vpAfma6.h b/modules/robot/include/visp3/robot/vpAfma6.h index f916f45d46..868eb86f23 100644 --- a/modules/robot/include/visp3/robot/vpAfma6.h +++ b/modules/robot/include/visp3/robot/vpAfma6.h @@ -33,9 +33,6 @@ * *****************************************************************************/ -#ifndef _vpAfma6_h -#define _vpAfma6_h - /*! \file vpAfma6.h @@ -44,6 +41,18 @@ */ +#ifndef _vpAfma6_h +#define _vpAfma6_h + +#include + +#include +#include +#include +#include +#include + +BEGIN_VISP_NAMESPACE /*! \class vpAfma6 @@ -65,13 +74,6 @@ set this tool during robot initialisation or using set_eMc(). */ - -#include -#include -#include -#include -#include - class VISP_EXPORT vpAfma6 { public: @@ -120,7 +122,8 @@ class VISP_EXPORT vpAfma6 static const char *const CONST_INTEL_D435_CAMERA_NAME; //! List of possible tools that can be attached to the robot end-effector. - typedef enum { + typedef enum + { TOOL_CCMOP, /*!< Pneumatic CCMOP gripper. */ TOOL_GRIPPER, /*!< Pneumatic gripper with 2 fingers. */ TOOL_VACUUM, /*!< Pneumatic vaccum gripper. */ @@ -135,7 +138,7 @@ class VISP_EXPORT vpAfma6 public: vpAfma6(); /*! Destructor that does nothing. */ - virtual ~vpAfma6(){}; + virtual ~vpAfma6() { }; /** @name Inherited functionalities from vpAfma6 */ //@{ @@ -145,8 +148,8 @@ class VISP_EXPORT vpAfma6 void init(vpAfma6::vpAfma6ToolType tool, const std::string &filename); void init(vpAfma6::vpAfma6ToolType tool, const vpHomogeneousMatrix &eMc_); void - init(vpAfma6::vpAfma6ToolType tool, - vpCameraParameters::vpCameraParametersProjType projModel = vpCameraParameters::perspectiveProjWithoutDistortion); + init(vpAfma6::vpAfma6ToolType tool, + vpCameraParameters::vpCameraParametersProjType projModel = vpCameraParameters::perspectiveProjWithoutDistortion); vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const; int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest = true, @@ -211,5 +214,5 @@ class VISP_EXPORT vpAfma6 // Used projection model vpCameraParameters::vpCameraParametersProjType projModel; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpBiclops.h b/modules/robot/include/visp3/robot/vpBiclops.h index e0af4beac1..1d47b5d2d5 100644 --- a/modules/robot/include/visp3/robot/vpBiclops.h +++ b/modules/robot/include/visp3/robot/vpBiclops.h @@ -36,11 +36,13 @@ #include +#include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpBiclops * @@ -57,7 +59,7 @@ * See http://www.traclabs.com/tracbiclops.htm for more details concerning the * hardware. * - */ +*/ class VISP_EXPORT vpBiclops { public: @@ -319,5 +321,5 @@ class VISP_EXPORT vpBiclops */ friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpBiclops &dummy); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpImageSimulator.h b/modules/robot/include/visp3/robot/vpImageSimulator.h index e781d4bd47..05a75e1fc4 100644 --- a/modules/robot/include/visp3/robot/vpImageSimulator.h +++ b/modules/robot/include/visp3/robot/vpImageSimulator.h @@ -129,6 +129,7 @@ #include #include +#include #include #include #include @@ -138,6 +139,7 @@ #include #include +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpImageSimulator { public: @@ -302,7 +304,7 @@ class VISP_EXPORT vpImageSimulator void getRoi(const unsigned int &Iwidth, const unsigned int &Iheight, const vpCameraParameters &cam, const std::vector &point, vpRect &rect); }; - +END_VISP_NAMESPACE #endif /* diff --git a/modules/robot/include/visp3/robot/vpPioneer.h b/modules/robot/include/visp3/robot/vpPioneer.h index daed355600..28ac2962a8 100644 --- a/modules/robot/include/visp3/robot/vpPioneer.h +++ b/modules/robot/include/visp3/robot/vpPioneer.h @@ -33,10 +33,12 @@ #ifndef VPPIONEER_H #define VPPIONEER_H +#include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpPioneer * @@ -80,7 +82,7 @@ * \end{array} * \right) * \f]. - */ +*/ class VISP_EXPORT vpPioneer : public vpUnicycle { public: @@ -138,5 +140,5 @@ class VISP_EXPORT vpPioneer : public vpUnicycle eJe_[5][1] = 1; // wz } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpPioneerPan.h b/modules/robot/include/visp3/robot/vpPioneerPan.h index e8d882b639..23bf29fb44 100644 --- a/modules/robot/include/visp3/robot/vpPioneerPan.h +++ b/modules/robot/include/visp3/robot/vpPioneerPan.h @@ -33,11 +33,13 @@ #ifndef VPPIONEERPAN_H #define VPPIONEERPAN_H +#include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpPioneerPan * @@ -86,7 +88,7 @@ * * with \f$p_x, p_y\f$ the position of the head base frame in the mobile * platform frame located at the middle point between the two wheels. - */ +*/ class VISP_EXPORT vpPioneerPan : public vpUnicycle { public: @@ -222,5 +224,5 @@ class VISP_EXPORT vpPioneerPan : public vpUnicycle vpHomogeneousMatrix mMp_; // constant vpHomogeneousMatrix pMe_; // depends on q pan }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpPololu.h b/modules/robot/include/visp3/robot/vpPololu.h index c0d62ab647..7c82437964 100644 --- a/modules/robot/include/visp3/robot/vpPololu.h +++ b/modules/robot/include/visp3/robot/vpPololu.h @@ -44,6 +44,7 @@ class RPMSerialInterface; +BEGIN_VISP_NAMESPACE /*! * \class vpPololu * \ingroup group_robot_real_arm @@ -70,7 +71,7 @@ class RPMSerialInterface; * Each servo has a pwm position range that could be retrieved using calibrate() and set using set using setPwmRange(). * * It is the user responsability to set the corresponding angular range using setAngularRange(). - */ +*/ class VISP_EXPORT vpPololu { public: @@ -328,6 +329,6 @@ class VISP_EXPORT vpPololu */ void VelocityCmdThread(); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpPtu46.h b/modules/robot/include/visp3/robot/vpPtu46.h index 01c8ab91a0..be3a323e0f 100644 --- a/modules/robot/include/visp3/robot/vpPtu46.h +++ b/modules/robot/include/visp3/robot/vpPtu46.h @@ -54,6 +54,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpPtu46 @@ -81,7 +82,7 @@ class VISP_EXPORT vpPtu46 public: /* Methodes publiques */ vpPtu46(void); /*! Destructor that does nothing. */ - virtual ~vpPtu46(){}; + virtual ~vpPtu46() { }; /** @name Inherited functionalities from vpPtu46 */ //@{ @@ -99,5 +100,5 @@ class VISP_EXPORT vpPtu46 //@} friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpPtu46 &constant); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpQbDevice.h b/modules/robot/include/visp3/robot/vpQbDevice.h index 034df6731e..2bcf17a980 100644 --- a/modules/robot/include/visp3/robot/vpQbDevice.h +++ b/modules/robot/include/visp3/robot/vpQbDevice.h @@ -44,6 +44,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpQbDevice @@ -112,6 +113,6 @@ class VISP_EXPORT vpQbDevice int m_max_repeats; //!< Max number of trials to send a command. bool m_init_done; //!< Flag used to indicate if the device is initialized. }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpQbSoftHand.h b/modules/robot/include/visp3/robot/vpQbSoftHand.h index 3b26d947fc..ae0aa96d47 100644 --- a/modules/robot/include/visp3/robot/vpQbSoftHand.h +++ b/modules/robot/include/visp3/robot/vpQbSoftHand.h @@ -40,6 +40,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpQbSoftHand * @@ -95,6 +96,6 @@ class VISP_EXPORT vpQbSoftHand : public vpQbDevice void setPosition(const vpColVector &position, const int &id = 1); void setPosition(const vpColVector &position, double speed_factor, double stiffness, const int &id = 1); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpReflexTakktile2.h b/modules/robot/include/visp3/robot/vpReflexTakktile2.h index e5ef4be753..c18be789b5 100644 --- a/modules/robot/include/visp3/robot/vpReflexTakktile2.h +++ b/modules/robot/include/visp3/robot/vpReflexTakktile2.h @@ -44,6 +44,7 @@ #include +BEGIN_VISP_NAMESPACE /*! \class vpReflexTakktile2 @@ -84,7 +85,7 @@ class VISP_EXPORT vpReflexTakktile2 std::vector error_state; HandInfo(); - ~HandInfo() {} + ~HandInfo() { } friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const HandInfo &hand); }; @@ -155,6 +156,6 @@ class VISP_EXPORT vpReflexTakktile2 class Impl; Impl *m_impl; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpRingLight.h b/modules/robot/include/visp3/robot/vpRingLight.h index bbcc213837..2fd6a04d36 100644 --- a/modules/robot/include/visp3/robot/vpRingLight.h +++ b/modules/robot/include/visp3/robot/vpRingLight.h @@ -33,14 +33,14 @@ * *****************************************************************************/ -#ifndef vpRingLight_h -#define vpRingLight_h - /*! \file vpRingLight.h \brief Ring light management under unix. */ +#ifndef vpRingLight_h +#define vpRingLight_h + #include #if defined(VISP_HAVE_MODULE_IO) && defined(VISP_HAVE_PARPORT) @@ -49,6 +49,8 @@ #include #include + +BEGIN_VISP_NAMESPACE /*! \class vpRingLight @@ -117,7 +119,7 @@ class VISP_EXPORT vpRingLight private: vpParallelPort parport; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpRobot.h b/modules/robot/include/visp3/robot/vpRobot.h index afe660e3ae..9677b115ce 100644 --- a/modules/robot/include/visp3/robot/vpRobot.h +++ b/modules/robot/include/visp3/robot/vpRobot.h @@ -33,19 +33,21 @@ * *****************************************************************************/ -#ifndef vpRobot_H -#define vpRobot_H - /*! \file vpRobot.h \brief class that defines a generic virtual robot */ +#ifndef vpRobot_H +#define vpRobot_H + #include +#include #include #include #include +BEGIN_VISP_NAMESPACE /*! \class vpRobot \ingroup group_robot_real_gantry group_robot_real_cylindrical @@ -181,5 +183,5 @@ class VISP_EXPORT vpRobot vpControlFrameType getRobotFrame(void) const { return frameRobot; } //@} }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpRobotAfma4.h b/modules/robot/include/visp3/robot/vpRobotAfma4.h index 3f32584850..6c664fd8e9 100644 --- a/modules/robot/include/visp3/robot/vpRobotAfma4.h +++ b/modules/robot/include/visp3/robot/vpRobotAfma4.h @@ -54,6 +54,7 @@ extern "C" { #include "trycatch.h" } +BEGIN_VISP_NAMESPACE /*! \class vpRobotAfma4 @@ -266,6 +267,6 @@ class VISP_EXPORT vpRobotAfma4 : public vpAfma4, public vpRobot void stopMotion(); }; - +END_VISP_NAMESPACE #endif #endif /* #ifndef vpRobotAfma4_h */ diff --git a/modules/robot/include/visp3/robot/vpRobotAfma6.h b/modules/robot/include/visp3/robot/vpRobotAfma6.h index a31f56d6d8..a6c8e0bca1 100644 --- a/modules/robot/include/visp3/robot/vpRobotAfma6.h +++ b/modules/robot/include/visp3/robot/vpRobotAfma6.h @@ -55,6 +55,7 @@ extern "C" { #include "trycatch.h" } +BEGIN_VISP_NAMESPACE /*! \class vpRobotAfma6 @@ -315,6 +316,6 @@ class VISP_EXPORT vpRobotAfma6 : public vpAfma6, public vpRobot void stopMotion(); }; - +END_VISP_NAMESPACE #endif #endif /* #ifndef vpRobotAfma6_h */ diff --git a/modules/robot/include/visp3/robot/vpRobotBebop2.h b/modules/robot/include/visp3/robot/vpRobotBebop2.h index 3c4576607b..95bef049ae 100644 --- a/modules/robot/include/visp3/robot/vpRobotBebop2.h +++ b/modules/robot/include/visp3/robot/vpRobotBebop2.h @@ -59,6 +59,7 @@ extern "C" { #include #include +BEGIN_VISP_NAMESPACE /*! \class vpRobotBebop2 @@ -249,6 +250,6 @@ class VISP_EXPORT vpRobotBebop2 ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, void *customData); //*** ***// }; - +END_VISP_NAMESPACE #endif //#ifdef VISP_HAVE_ARSDK #endif //#ifndef _vpRobotBebop2_h_ diff --git a/modules/robot/include/visp3/robot/vpRobotBiclops.h b/modules/robot/include/visp3/robot/vpRobotBiclops.h index d4c0ac0416..d254c70fc1 100644 --- a/modules/robot/include/visp3/robot/vpRobotBiclops.h +++ b/modules/robot/include/visp3/robot/vpRobotBiclops.h @@ -57,6 +57,7 @@ /* --- CLASS -------------------------------------------------------------- */ /* ------------------------------------------------------------------------ */ +BEGIN_VISP_NAMESPACE /*! * \class vpRobotBiclops * @@ -86,7 +87,7 @@ * \warning With the understanding that hitting the hard limits at full * speed/power can damage the unit, damage due to velocity mode commanding is * under user responsibility. - */ +*/ class VISP_EXPORT vpRobotBiclops : public vpBiclops, public vpRobot { public: @@ -439,7 +440,7 @@ class VISP_EXPORT vpRobotBiclops : public vpBiclops, public vpRobot // } //#endif }; - +END_VISP_NAMESPACE #endif /* #ifndef _vpRobotBiclops_h_ */ #endif diff --git a/modules/robot/include/visp3/robot/vpRobotCamera.h b/modules/robot/include/visp3/robot/vpRobotCamera.h index 5eace8d3ce..e7cb180022 100644 --- a/modules/robot/include/visp3/robot/vpRobotCamera.h +++ b/modules/robot/include/visp3/robot/vpRobotCamera.h @@ -33,14 +33,14 @@ * *****************************************************************************/ -#ifndef vpRobotCamera_H -#define vpRobotCamera_H - /*! \file vpRobotCamera.h \brief class that defines the simplest robot : a free flying camera */ +#ifndef vpRobotCamera_H +#define vpRobotCamera_H + #include #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpRobotCamera \ingroup group_robot_simu_camera @@ -132,6 +133,6 @@ class VISP_EXPORT vpRobotCamera : public vpRobotSimulator void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) vp_override { }; void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) vp_override { }; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpRobotException.h b/modules/robot/include/visp3/robot/vpRobotException.h index acf7b01cee..3c3f30aaa9 100644 --- a/modules/robot/include/visp3/robot/vpRobotException.h +++ b/modules/robot/include/visp3/robot/vpRobotException.h @@ -31,23 +31,25 @@ * Exception that can be emitted by the vpRobot class and its derivatives. */ -#ifndef _vpRobotException_h_ -#define _vpRobotException_h_ - /*! * \file vpRobotException.h * \brief error that can be emitted by the vpRobot class and its derivatives */ +#ifndef _vpRobotException_h_ +#define _vpRobotException_h_ + +#include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpRobotException * \brief Error that can be emitted by the vpRobot class and its derivatives. - */ +*/ class VISP_EXPORT vpRobotException : public vpException { public: @@ -115,5 +117,5 @@ class VISP_EXPORT vpRobotException : public vpException */ explicit vpRobotException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpRobotFlirPtu.h b/modules/robot/include/visp3/robot/vpRobotFlirPtu.h index 1000af16d4..ba77625e0b 100644 --- a/modules/robot/include/visp3/robot/vpRobotFlirPtu.h +++ b/modules/robot/include/visp3/robot/vpRobotFlirPtu.h @@ -33,14 +33,14 @@ * *****************************************************************************/ -#ifndef vpRobotFlirPtu_h -#define vpRobotFlirPtu_h - /*! \file vpRobotFlirPtu.h Interface for Flir Ptu Cpi robot. */ +#ifndef vpRobotFlirPtu_h +#define vpRobotFlirPtu_h + #include #ifdef VISP_HAVE_FLIR_PTU_SDK @@ -49,6 +49,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpRobotFlirPtu \ingroup group_robot_real_arm @@ -166,6 +167,6 @@ class VISP_EXPORT vpRobotFlirPtu : public vpRobot int m_njoints; double m_positioning_velocity; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpRobotFranka.h b/modules/robot/include/visp3/robot/vpRobotFranka.h index 22b3d632ab..ad9634b889 100644 --- a/modules/robot/include/visp3/robot/vpRobotFranka.h +++ b/modules/robot/include/visp3/robot/vpRobotFranka.h @@ -54,6 +54,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpRobotFranka * @@ -217,7 +218,7 @@ * * \sa \ref tutorial-franka-pbvs * \sa \ref tutorial-franka-ibvs - */ +*/ class VISP_EXPORT vpRobotFranka : public vpRobot { private: @@ -353,6 +354,6 @@ class VISP_EXPORT vpRobotFranka : public vpRobot void stopMotion(); }; - +END_VISP_NAMESPACE #endif #endif // #ifndef __vpRobotFranka_h_ diff --git a/modules/robot/include/visp3/robot/vpRobotKinova.h b/modules/robot/include/visp3/robot/vpRobotKinova.h index 885483b683..2bf7e1c2d5 100644 --- a/modules/robot/include/visp3/robot/vpRobotKinova.h +++ b/modules/robot/include/visp3/robot/vpRobotKinova.h @@ -33,9 +33,6 @@ * *****************************************************************************/ -#ifndef vpRobotKinova_h -#define vpRobotKinova_h - /*! \file vpRobotKinova.h @@ -44,6 +41,9 @@ */ +#ifndef vpRobotKinova_h +#define vpRobotKinova_h + #include #ifdef VISP_HAVE_JACOSDK @@ -60,7 +60,7 @@ #elif _WIN32 #include #include -#include +#include #include #include #include @@ -69,6 +69,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpRobotKinova @@ -178,6 +179,6 @@ class VISP_EXPORT vpRobotKinova : public vpRobot int (*KinovaSetAngularControl)(); int (*KinovaSetCartesianControl)(); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpRobotMavsdk.h b/modules/robot/include/visp3/robot/vpRobotMavsdk.h index 376fcd2025..27e6e42201 100644 --- a/modules/robot/include/visp3/robot/vpRobotMavsdk.h +++ b/modules/robot/include/visp3/robot/vpRobotMavsdk.h @@ -51,6 +51,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * \class vpRobotMavsdk * @@ -157,6 +158,6 @@ class VISP_EXPORT vpRobotMavsdk class vpRobotMavsdkImpl; vpRobotMavsdkImpl *m_impl; }; - +END_VISP_NAMESPACE #endif // #ifdef VISP_HAVE_MAVSDK #endif // #ifndef vpRobotMavsdk_h_ diff --git a/modules/robot/include/visp3/robot/vpRobotPioneer.h b/modules/robot/include/visp3/robot/vpRobotPioneer.h index 6c6f847e43..48d12e0c47 100644 --- a/modules/robot/include/visp3/robot/vpRobotPioneer.h +++ b/modules/robot/include/visp3/robot/vpRobotPioneer.h @@ -48,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpRobotPioneer * @@ -58,7 +59,7 @@ * This class provides a position and speed control interface for Pioneer * mobile robots. It inherits from the Aria ArRobot class. For more information * about the model of the robot, see vpPioneer documentation. - */ +*/ class VISP_EXPORT vpRobotPioneer : public vpRobot, public vpPioneer, public ArRobot { private: /* Not allowed functions. */ @@ -130,7 +131,7 @@ class VISP_EXPORT vpRobotPioneer : public vpRobot, public vpPioneer, public ArRo protected: bool isInitialized; }; - +END_VISP_NAMESPACE #endif #endif // VPROBOTPIONEER_H diff --git a/modules/robot/include/visp3/robot/vpRobotPololuPtu.h b/modules/robot/include/visp3/robot/vpRobotPololuPtu.h index 4620c8567a..035ccd39ab 100644 --- a/modules/robot/include/visp3/robot/vpRobotPololuPtu.h +++ b/modules/robot/include/visp3/robot/vpRobotPololuPtu.h @@ -41,7 +41,7 @@ #include #include - +BEGIN_VISP_NAMESPACE /*! * \class vpRobotPololuPtu * \ingroup group_robot_real_arm @@ -59,7 +59,7 @@ * | :---: | :-------: | :-------: | -------------: | ----------------: | * | 1 | 0 | 0 | \f$ \pi/2\f$ | \f$q_1\f$ | * | 2 | 0 | 0 | \f$-\pi/2\f$ | \f$q_2 - \pi/2\f$ | - */ +*/ class VISP_EXPORT vpRobotPololuPtu : public vpRobot { public: @@ -268,6 +268,6 @@ class VISP_EXPORT vpRobotPololuPtu : public vpRobot bool m_verbose; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpRobotPtu46.h b/modules/robot/include/visp3/robot/vpRobotPtu46.h index 302f48fe22..bffe1eca06 100644 --- a/modules/robot/include/visp3/robot/vpRobotPtu46.h +++ b/modules/robot/include/visp3/robot/vpRobotPtu46.h @@ -59,7 +59,7 @@ /* ------------------------------------------------------------------------ */ /* --- CLASS ------------------------------------------------------------- */ /* ------------------------------------------------------------------------ */ - +BEGIN_VISP_NAMESPACE /*! \class vpRobotPtu46 @@ -122,7 +122,7 @@ class VISP_EXPORT vpRobotPtu46 : public vpPtu46, public vpRobot void stopMotion(); }; - +END_VISP_NAMESPACE #endif /* #ifndef _vpRobotPtu46_h_ */ #endif diff --git a/modules/robot/include/visp3/robot/vpRobotSimulator.h b/modules/robot/include/visp3/robot/vpRobotSimulator.h index b6d87cbe0d..73ac96fd44 100644 --- a/modules/robot/include/visp3/robot/vpRobotSimulator.h +++ b/modules/robot/include/visp3/robot/vpRobotSimulator.h @@ -31,19 +31,20 @@ * Basic class used to make robot simulators. */ -#ifndef vpRobotSimulator_HH -#define vpRobotSimulator_HH - /*! * \file vpRobotSimulator.h * \brief Basic class used to make robot simulators. */ +#ifndef vpRobotSimulator_HH +#define vpRobotSimulator_HH + #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpRobotSimulator * @@ -52,7 +53,7 @@ * * \brief This class aims to be a basis used to create all the * robot simulators. - */ +*/ class VISP_EXPORT vpRobotSimulator : public vpRobot { protected: @@ -80,5 +81,5 @@ class VISP_EXPORT vpRobotSimulator : public vpRobot virtual inline void setSamplingTime(const double &delta_t) { this->delta_t_ = delta_t; } //@} }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpRobotTemplate.h b/modules/robot/include/visp3/robot/vpRobotTemplate.h index 0b732f1871..f7f01bbe2e 100644 --- a/modules/robot/include/visp3/robot/vpRobotTemplate.h +++ b/modules/robot/include/visp3/robot/vpRobotTemplate.h @@ -31,24 +31,25 @@ * Defines a robot just to show which function you must implement. */ -#ifndef vpRobotTemplate_h -#define vpRobotTemplate_h - /*! * \file vpRobotTemplate.h * Defines a robot just to show which function you must implement. */ +#ifndef vpRobotTemplate_h +#define vpRobotTemplate_h + #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpRobotTemplate * \ingroup group_robot_real_template * \brief Class that defines a robot just to show which function you must implement. - */ +*/ class VISP_EXPORT vpRobotTemplate : public vpRobot { public: @@ -84,5 +85,5 @@ class VISP_EXPORT vpRobotTemplate : public vpRobot protected: vpHomogeneousMatrix m_eMc; //!< Constant transformation between end-effector and tool (or camera) frame }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpRobotUniversalRobots.h b/modules/robot/include/visp3/robot/vpRobotUniversalRobots.h index 3ea8684179..a4e74e9358 100644 --- a/modules/robot/include/visp3/robot/vpRobotUniversalRobots.h +++ b/modules/robot/include/visp3/robot/vpRobotUniversalRobots.h @@ -49,6 +49,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpRobotUniversalRobots @@ -136,6 +137,6 @@ class VISP_EXPORT vpRobotUniversalRobots : public vpRobot double m_max_linear_acceleration; vpRobot::vpControlFrameType m_vel_control_frame; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpRobotViper650.h b/modules/robot/include/visp3/robot/vpRobotViper650.h index 5b1a9323b7..742ea15188 100644 --- a/modules/robot/include/visp3/robot/vpRobotViper650.h +++ b/modules/robot/include/visp3/robot/vpRobotViper650.h @@ -55,6 +55,7 @@ extern "C" { #include "trycatch.h" } +BEGIN_VISP_NAMESPACE /*! \class vpRobotViper650 @@ -465,6 +466,6 @@ class VISP_EXPORT vpRobotViper650 : public vpViper650, public vpRobot private: double m_maxRotationVelocity_joint6; }; - +END_VISP_NAMESPACE #endif #endif /* #ifndef vpRobotViper650_h */ diff --git a/modules/robot/include/visp3/robot/vpRobotViper850.h b/modules/robot/include/visp3/robot/vpRobotViper850.h index ba9ea8b336..bd7abd4453 100644 --- a/modules/robot/include/visp3/robot/vpRobotViper850.h +++ b/modules/robot/include/visp3/robot/vpRobotViper850.h @@ -63,6 +63,7 @@ extern "C" { #include #endif +BEGIN_VISP_NAMESPACE /* ! \class vpRobotViper850 @@ -478,6 +479,6 @@ class VISP_EXPORT vpRobotViper850 : public vpViper850, public vpRobot private: double maxRotationVelocity_joint6; }; - +END_VISP_NAMESPACE #endif #endif /* #ifndef vpRobotViper850_h */ diff --git a/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h b/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h index a84db8f60c..9dfc689d15 100644 --- a/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h +++ b/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h @@ -31,14 +31,14 @@ * Basic class used to make robot simulators. */ -#ifndef vpRobotWireFrameSimulator_HH -#define vpRobotWireFrameSimulator_HH - /*! * \file vpRobotWireFrameSimulator.h * \brief Basic class used to make robot simulators. */ +#ifndef vpRobotWireFrameSimulator_HH +#define vpRobotWireFrameSimulator_HH + #include #if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) @@ -58,6 +58,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpRobotWireFrameSimulator * @@ -74,7 +75,7 @@ * \warning This class uses threading capabilities. Thus on Unix-like * platforms, the libpthread third-party library need to be * installed. On Windows, we use the native threading capabilities. - */ +*/ class VISP_EXPORT vpRobotWireFrameSimulator : protected vpWireFrameSimulator, public vpRobotSimulator { public: @@ -411,6 +412,6 @@ class VISP_EXPORT vpRobotWireFrameSimulator : protected vpWireFrameSimulator, pu virtual void get_fMi(vpHomogeneousMatrix *fMit) = 0; //@} }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpServolens.h b/modules/robot/include/visp3/robot/vpServolens.h index fbffd072c0..36bf1f3adf 100644 --- a/modules/robot/include/visp3/robot/vpServolens.h +++ b/modules/robot/include/visp3/robot/vpServolens.h @@ -34,13 +34,6 @@ * *****************************************************************************/ -#ifndef _vpServolens_h_ -#define _vpServolens_h_ - -#include - -#if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) - /*! \file vpServolens.h @@ -50,9 +43,18 @@ */ +#ifndef _vpServolens_h_ +#define _vpServolens_h_ + +#include + +#if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) + #include +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpServolens @@ -90,7 +92,8 @@ class VISP_EXPORT vpServolens { public: typedef enum { ZOOM = 1, FOCUS = 2, IRIS = 3 } vpServoType; - typedef enum { + typedef enum + { ZOOM_MAX = 10000, // Valeur maxi zoom (mm/100) ZOOM_MIN = 1000, // Valeur mini zoom (mm/100) FOCUS_MAX = 1500, // Valeur maxi focus (metres/100) @@ -130,6 +133,6 @@ class VISP_EXPORT vpServolens int remfd; // file pointer of the host's tty bool isinit; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpSimulatorAfma6.h b/modules/robot/include/visp3/robot/vpSimulatorAfma6.h index b15ebe6bdf..c5a8d44fa1 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorAfma6.h +++ b/modules/robot/include/visp3/robot/vpSimulatorAfma6.h @@ -31,14 +31,15 @@ * Class which provides a simulator for the robot Afma6. */ -#ifndef vpSimulatorAfma6_HH -#define vpSimulatorAfma6_HH - /*! * \file vpSimulatorAfma6.h * \brief Class which provides a simulator for the robot Afma6. */ +#ifndef vpSimulatorAfma6_HH +#define vpSimulatorAfma6_HH + +#include #include #include @@ -46,6 +47,7 @@ #if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) +BEGIN_VISP_NAMESPACE /*! * \class vpSimulatorAfma6 * @@ -166,7 +168,7 @@ * * To know how this class can be used to achieve a visual servoing simulation, * you can follow the \ref tutorial-ibvs. - */ +*/ class VISP_EXPORT vpSimulatorAfma6 : public vpRobotWireFrameSimulator, public vpAfma6 { public: @@ -257,7 +259,7 @@ class VISP_EXPORT vpSimulatorAfma6 : public vpRobotWireFrameSimulator, public vp void updateArticularPosition() vp_override; //@} }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpSimulatorCamera.h b/modules/robot/include/visp3/robot/vpSimulatorCamera.h index fa3c77c01b..8f75ee1d36 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorCamera.h +++ b/modules/robot/include/visp3/robot/vpSimulatorCamera.h @@ -31,20 +31,22 @@ * Defines the simplest robot : a free flying camera. */ -#ifndef vpSimulatorCamera_H -#define vpSimulatorCamera_H - /*! * \file vpSimulatorCamera.h * \brief class that defines the simplest robot : a free flying camera */ +#ifndef vpSimulatorCamera_H +#define vpSimulatorCamera_H + #include +#include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpSimulatorCamera * @@ -98,7 +100,7 @@ * * To know how this class can be used to achieve a visual servoing simulation, * you can follow the \ref tutorial-ibvs. - */ +*/ class VISP_EXPORT vpSimulatorCamera : public vpRobotSimulator { protected: @@ -128,5 +130,5 @@ class VISP_EXPORT vpSimulatorCamera : public vpRobotSimulator void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) vp_override { }; void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) vp_override { }; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpSimulatorPioneer.h b/modules/robot/include/visp3/robot/vpSimulatorPioneer.h index 7df272f7b4..e6f4b60ee7 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorPioneer.h +++ b/modules/robot/include/visp3/robot/vpSimulatorPioneer.h @@ -41,12 +41,14 @@ */ #include +#include #include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpSimulatorPioneer * @@ -93,7 +95,7 @@ * * The usage of this class is also highlighted in \ref * tutorial-simu-robot-pioneer. - */ +*/ class VISP_EXPORT vpSimulatorPioneer : public vpPioneer, public vpRobotSimulator { @@ -130,5 +132,5 @@ class VISP_EXPORT vpSimulatorPioneer : public vpPioneer, public vpRobotSimulator void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) vp_override { }; void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) vp_override { }; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpSimulatorPioneerPan.h b/modules/robot/include/visp3/robot/vpSimulatorPioneerPan.h index 5af9d8d45c..c6c09d7378 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorPioneerPan.h +++ b/modules/robot/include/visp3/robot/vpSimulatorPioneerPan.h @@ -31,22 +31,24 @@ * Pioneer mobile robot equipped with a pan head simulator without display. */ -#ifndef vpSimulatorPioneerPan_H -#define vpSimulatorPioneerPan_H - /*! * \file vpSimulatorPioneerPan.h * \brief class that defines the Pioneer mobile robot simulator equipped * with a camera able to move in pan. */ +#ifndef vpSimulatorPioneerPan_H +#define vpSimulatorPioneerPan_H + #include +#include #include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpSimulatorPioneerPan * @@ -93,7 +95,7 @@ * \endcode * * The usage of this class is also highlighted in \ref tutorial-simu-robot-pioneer. - */ +*/ class VISP_EXPORT vpSimulatorPioneerPan : public vpPioneerPan, public vpRobotSimulator { @@ -131,5 +133,5 @@ class VISP_EXPORT vpSimulatorPioneerPan : public vpPioneerPan, public vpRobotSim void getDisplacement(const vpRobot::vpControlFrameType /* frame */, vpColVector & /* q */) vp_override { }; void setPosition(const vpRobot::vpControlFrameType /* frame */, const vpColVector & /* q */) vp_override { }; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpSimulatorViper850.h b/modules/robot/include/visp3/robot/vpSimulatorViper850.h index 854f7646f9..90a1f7436f 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorViper850.h +++ b/modules/robot/include/visp3/robot/vpSimulatorViper850.h @@ -31,14 +31,15 @@ * Class which provides a simulator for the robot Viper850. */ -#ifndef vpSimulatorViper850_HH -#define vpSimulatorViper850_HH - /*! * \file vpSimulatorViper850.h * \brief Class which provides a simulator for the robot Viper850.. */ +#ifndef vpSimulatorViper850_HH +#define vpSimulatorViper850_HH + +#include #include #if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) @@ -46,6 +47,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * \class vpSimulatorViper850 * @@ -191,7 +193,7 @@ * * To know how this class can be used to achieve a visual servoing simulation, * you can follow the \ref tutorial-ibvs. - */ +*/ class VISP_EXPORT vpSimulatorViper850 : public vpRobotWireFrameSimulator, public vpViper850 { public: @@ -284,7 +286,7 @@ class VISP_EXPORT vpSimulatorViper850 : public vpRobotWireFrameSimulator, public void updateArticularPosition() vp_override; //@} }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpUnicycle.h b/modules/robot/include/visp3/robot/vpUnicycle.h index 15e74fed3d..d36f4c628e 100644 --- a/modules/robot/include/visp3/robot/vpUnicycle.h +++ b/modules/robot/include/visp3/robot/vpUnicycle.h @@ -33,10 +33,12 @@ #ifndef VPUNICYCLE_H #define VPUNICYCLE_H +#include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpUnicycle * @@ -45,7 +47,7 @@ * \brief Generic functions for unicycle mobile robots. * * This class provides common features for unicycle mobile robots. - */ +*/ class VISP_EXPORT vpUnicycle { public: @@ -114,5 +116,5 @@ class VISP_EXPORT vpUnicycle vpHomogeneousMatrix cMe_; // Camera frame to mobile platform frame vpMatrix eJe_; // Robot jacobian }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpViper.h b/modules/robot/include/visp3/robot/vpViper.h index 465f81500a..b75842f4b4 100644 --- a/modules/robot/include/visp3/robot/vpViper.h +++ b/modules/robot/include/visp3/robot/vpViper.h @@ -33,9 +33,6 @@ * *****************************************************************************/ -#ifndef vpViper_h -#define vpViper_h - /*! \file vpViper.h @@ -44,13 +41,18 @@ */ +#ifndef vpViper_h +#define vpViper_h + #include +#include #include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! \class vpViper @@ -111,7 +113,7 @@ class VISP_EXPORT vpViper { public: vpViper(); - virtual ~vpViper(){}; + virtual ~vpViper() { }; /** @name Inherited functionalities from vpViper */ //@{ @@ -169,5 +171,5 @@ class VISP_EXPORT vpViper vpColVector joint_max; // Maximal value of the joints vpColVector joint_min; // Minimal value of the joints }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpViper650.h b/modules/robot/include/visp3/robot/vpViper650.h index ab2082ae04..63d86e836c 100644 --- a/modules/robot/include/visp3/robot/vpViper650.h +++ b/modules/robot/include/visp3/robot/vpViper650.h @@ -31,17 +31,19 @@ * Interface for the ADEPT Viper 650 robot. */ -#ifndef vpViper650_h -#define vpViper650_h - -#include - /*! * \file vpViper650.h * * Modelization of the ADEPT Viper 650 robot. */ +#ifndef vpViper650_h +#define vpViper650_h + +#include +#include + +BEGIN_VISP_NAMESPACE /*! * \class vpViper650 * @@ -88,7 +90,7 @@ * set this tool during robot initialisation or using set_eMc(). * * - \f$ {\cal F}_s \f$: the force/torque sensor frame, with \f$d7=0.0666\f$. - */ +*/ class VISP_EXPORT vpViper650 : public vpViper { public: @@ -165,5 +167,5 @@ class VISP_EXPORT vpViper650 : public vpViper // Used projection model vpCameraParameters::vpCameraParametersProjType projModel; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpViper850.h b/modules/robot/include/visp3/robot/vpViper850.h index 2a04d80c5a..edb4788de5 100644 --- a/modules/robot/include/visp3/robot/vpViper850.h +++ b/modules/robot/include/visp3/robot/vpViper850.h @@ -31,19 +31,19 @@ * Interface for the ADEPT Viper 850 robot. */ -#ifndef vpViper850_h -#define vpViper850_h - - -#include -#include - /*! * \file vpViper850.h * * Modelization of the ADEPT Viper 850 robot. */ +#ifndef vpViper850_h +#define vpViper850_h + +#include +#include + +BEGIN_VISP_NAMESPACE /*! * \class vpViper850 * @@ -90,7 +90,7 @@ * set this during robot initialisation or using set_eMc(). * * - \f$ {\cal F}_s \f$: the force/torque sensor frame, with \f$d7=0.0666\f$. - */ +*/ class VISP_EXPORT vpViper850 : public vpViper { public: @@ -167,5 +167,5 @@ class VISP_EXPORT vpViper850 : public vpViper // Used projection model vpCameraParameters::vpCameraParametersProjType projModel; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpVirtuose.h b/modules/robot/include/visp3/robot/vpVirtuose.h index 80222a272f..1ad4c33739 100644 --- a/modules/robot/include/visp3/robot/vpVirtuose.h +++ b/modules/robot/include/visp3/robot/vpVirtuose.h @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + \file vpVirtuose.h + \brief Wrapper over Haption Virtuose SDK to control haptic devices. +*/ + #ifndef _vpVirtuose_h_ #define _vpVirtuose_h_ @@ -45,10 +50,7 @@ #include -/*! - \file vpVirtuose.h - \brief Wrapper over Haption Virtuose SDK to control haptic devices. -*/ +BEGIN_VISP_NAMESPACE /*! \class vpVirtuose \ingroup group_robot_haptic @@ -136,7 +138,7 @@ int main() std::cout << "Joint position: " << q.t() << std::endl; } \endcode - */ +*/ class VISP_EXPORT vpVirtuose { public: @@ -225,6 +227,6 @@ class VISP_EXPORT vpVirtuose float m_period; unsigned int m_njoints; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/include/visp3/robot/vpWireFrameSimulator.h b/modules/robot/include/visp3/robot/vpWireFrameSimulator.h index 88d0d29a63..0bea74a8d9 100644 --- a/modules/robot/include/visp3/robot/vpWireFrameSimulator.h +++ b/modules/robot/include/visp3/robot/vpWireFrameSimulator.h @@ -33,13 +33,14 @@ * *****************************************************************************/ -#ifndef vpWireFrameSimulator_HH -#define vpWireFrameSimulator_HH - /*! \file vpWireFrameSimulator.h \brief Implementation of a wire frame simulator. */ + +#ifndef vpWireFrameSimulator_HH +#define vpWireFrameSimulator_HH + #include // std::fabs #include #include // numeric_limits @@ -58,6 +59,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpWireFrameSimulator @@ -603,5 +605,5 @@ class VISP_EXPORT vpWireFrameSimulator const vpHomogeneousMatrix &fMo, const vpHomogeneousMatrix &cMf); //@} }; - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/include/visp3/robot/vpWireFrameSimulatorTypes.h b/modules/robot/include/visp3/robot/vpWireFrameSimulatorTypes.h index 3ae751a3b6..90389ca6f1 100644 --- a/modules/robot/include/visp3/robot/vpWireFrameSimulatorTypes.h +++ b/modules/robot/include/visp3/robot/vpWireFrameSimulatorTypes.h @@ -39,7 +39,7 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE typedef unsigned short Index; typedef char Type; typedef float Matrix[4][4]; @@ -64,13 +64,15 @@ typedef float Matrix[4][4]; * sommets: si (nbr > DEFAULT_VSIZE) | alors ptr est alloue et libere * dynamiquement | sinon ptr = tbl fsi; */ -typedef struct { +typedef struct +{ Index nbr; /* nombre de sommets */ Index *ptr; /* liste dynamique */ Index tbl[DEFAULT_VSIZE]; } Vertex_list; -typedef struct { +typedef struct +{ unsigned is_polygonal : 1; /* face polygonale */ unsigned is_visible : 1; /* face affichable */ #ifdef face_edge @@ -82,21 +84,25 @@ typedef struct { #endif // face_normal } Face; -typedef struct { +typedef struct +{ Index nbr; /* nombre de faces */ Face *ptr; /* liste dynamique */ } Face_list; -typedef struct { +typedef struct +{ float x, y, z; } Point3f; -typedef struct { +typedef struct +{ Index nbr; /* nombre de points */ Point3f *ptr; /* liste dynamique */ } Point3f_list; -typedef struct { +typedef struct +{ unsigned is_display : 1; /* surface affichable */ unsigned is_polygonal : 1; /* surface polyedrique */ Type type; /* type de la primitive */ @@ -110,15 +116,17 @@ typedef struct { #endif // face_normal } Bound; -typedef struct { +typedef struct +{ Index nbr; /* nombre de surfaces */ Bound *ptr; /* liste dynamique */ } Bound_list; -typedef struct { +typedef struct +{ char *name; /* nom de la scene */ Bound_list bound; /* liste de surfaces */ } Bound_scene; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp b/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp index 7c022269f1..abc7b3e4ec 100644 --- a/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp +++ b/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp @@ -43,6 +43,7 @@ #include #include +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpQbDevice::Impl { @@ -737,5 +738,5 @@ void vpQbDevice::setMaxRepeats(const int &max_repeats) m_max_repeats = max_repeats; m_impl->setMaxRepeats(m_max_repeats); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp b/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp index 5f5e3c3322..07dd0943fd 100644 --- a/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp +++ b/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp @@ -40,6 +40,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * Default constructor that does nothing. * To connect to a device call init(). @@ -204,4 +205,5 @@ void vpQbSoftHand::setPosition(const vpColVector &position, double speed_factor, vpTime::wait(t0, delta_t); } while (!vpMath::equal(q[0], position[0], precision) && !(current_failures > 1)); } +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/haptic-device/reflex-takktile/vpReflexTakktile2.cpp b/modules/robot/src/haptic-device/reflex-takktile/vpReflexTakktile2.cpp index 667abc5a34..2f36fb5667 100644 --- a/modules/robot/src/haptic-device/reflex-takktile/vpReflexTakktile2.cpp +++ b/modules/robot/src/haptic-device/reflex-takktile/vpReflexTakktile2.cpp @@ -42,13 +42,14 @@ #include #include +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpReflexTakktile2::Impl : public reflex_driver2::ReflexDriver { public: - Impl() {} + Impl() { } - ~Impl() {} + ~Impl() { } }; #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS @@ -119,9 +120,8 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpReflexTakktile2:: */ vpReflexTakktile2::vpReflexTakktile2() : m_network_interface(), m_finger_file_name(), m_tactile_file_name(), m_motor_file_name(), m_hand_info(), - m_impl(new Impl()) -{ -} + m_impl(new Impl()) +{ } /*! * Destructor. @@ -325,5 +325,5 @@ void vpReflexTakktile2::open() * \param milliseconds : Duration in [ms]. */ void vpReflexTakktile2::wait(int milliseconds) { m_impl->wait(milliseconds); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp b/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp index e14fb6d859..edda95e56a 100644 --- a/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp +++ b/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp @@ -42,7 +42,7 @@ #include #ifdef VISP_HAVE_VIRTUOSE - +BEGIN_VISP_NAMESPACE /*! * Default constructor. * Set command type to virtual mechanism by default (impedance mode). @@ -1043,7 +1043,7 @@ void vpVirtuose::stopPeriodicFunction() else std::cout << "Haptic loop closed." << std::endl; } - +END_VISP_NAMESPACE #else // Work around to avoid warning void dummy_vpVirtuose() { }; diff --git a/modules/robot/src/image-simulator/vpImageSimulator.cpp b/modules/robot/src/image-simulator/vpImageSimulator.cpp index d71babc2db..5607b7a832 100644 --- a/modules/robot/src/image-simulator/vpImageSimulator.cpp +++ b/modules/robot/src/image-simulator/vpImageSimulator.cpp @@ -45,6 +45,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! Basic constructor. @@ -57,9 +58,9 @@ */ vpImageSimulator::vpImageSimulator(const vpColorPlan &col) : cMt(), pt(), ptClipped(), interp(SIMPLE), normal_obj(), normal_Cam(), normal_Cam_optim(), distance(1.), - visible_result(1.), visible(false), X0_2_optim(nullptr), frobeniusNorm_u(0.), fronbniusNorm_v(0.), vbase_u(), - vbase_v(), vbase_u_optim(nullptr), vbase_v_optim(nullptr), Xinter_optim(nullptr), listTriangle(), colorI(col), Ig(), Ic(), - rect(), cleanPrevImage(false), setBackgroundTexture(false), bgColor(vpColor::white), focal(), needClipping(false) + visible_result(1.), visible(false), X0_2_optim(nullptr), frobeniusNorm_u(0.), fronbniusNorm_v(0.), vbase_u(), + vbase_v(), vbase_u_optim(nullptr), vbase_v_optim(nullptr), Xinter_optim(nullptr), listTriangle(), colorI(col), Ig(), Ic(), + rect(), cleanPrevImage(false), setBackgroundTexture(false), bgColor(vpColor::white), focal(), needClipping(false) { for (int i = 0; i < 4; i++) X[i].resize(3); @@ -94,10 +95,10 @@ vpImageSimulator::vpImageSimulator(const vpColorPlan &col) */ vpImageSimulator::vpImageSimulator(const vpImageSimulator &text) : cMt(), pt(), ptClipped(), interp(SIMPLE), normal_obj(), normal_Cam(), normal_Cam_optim(), distance(1.), - visible_result(1.), visible(false), X0_2_optim(nullptr), frobeniusNorm_u(0.), fronbniusNorm_v(0.), vbase_u(), - vbase_v(), vbase_u_optim(nullptr), vbase_v_optim(nullptr), Xinter_optim(nullptr), listTriangle(), colorI(GRAY_SCALED), Ig(), - Ic(), rect(), cleanPrevImage(false), setBackgroundTexture(false), bgColor(vpColor::white), focal(), - needClipping(false) + visible_result(1.), visible(false), X0_2_optim(nullptr), frobeniusNorm_u(0.), fronbniusNorm_v(0.), vbase_u(), + vbase_v(), vbase_u_optim(nullptr), vbase_v_optim(nullptr), Xinter_optim(nullptr), listTriangle(), colorI(GRAY_SCALED), Ig(), + Ic(), rect(), cleanPrevImage(false), setBackgroundTexture(false), bgColor(vpColor::white), focal(), + needClipping(false) { pt.resize(4); for (unsigned int i = 0; i < 4; i++) { @@ -224,11 +225,12 @@ void vpImageSimulator::getImage(vpImage &I, const vpCameraParamet if (getPixel(ip, Ipixelplan)) { *(bitmap + i * width + j) = Ipixelplan; } - } else if (colorI == COLORED) { + } + else if (colorI == COLORED) { vpRGBa Ipixelplan; if (getPixel(ip, Ipixelplan)) { unsigned char pixelgrey = - (unsigned char)(0.2126 * Ipixelplan.R + 0.7152 * Ipixelplan.G + 0.0722 * Ipixelplan.B); + (unsigned char)(0.2126 * Ipixelplan.R + 0.7152 * Ipixelplan.G + 0.0722 * Ipixelplan.B); *(bitmap + i * width + j) = pixelgrey; } } @@ -344,12 +346,13 @@ void vpImageSimulator::getImage(vpImage &I, const vpCameraParamet zBuffer[i][j] = Xinter_optim[2]; } } - } else if (colorI == COLORED) { + } + else if (colorI == COLORED) { vpRGBa Ipixelplan; if (getPixel(ip, Ipixelplan)) { if (Xinter_optim[2] < zBuffer[i][j] || zBuffer[i][j] < 0) { unsigned char pixelgrey = - (unsigned char)(0.2126 * Ipixelplan.R + 0.7152 * Ipixelplan.G + 0.0722 * Ipixelplan.B); + (unsigned char)(0.2126 * Ipixelplan.R + 0.7152 * Ipixelplan.G + 0.0722 * Ipixelplan.B); *(bitmap + i * width + j) = pixelgrey; zBuffer[i][j] = Xinter_optim[2]; } @@ -407,7 +410,8 @@ void vpImageSimulator::getImage(vpImage &I, const vpCameraParameters &ca pixelcolor.B = Ipixelplan; *(bitmap + i * width + j) = pixelcolor; } - } else if (colorI == COLORED) { + } + else if (colorI == COLORED) { vpRGBa Ipixelplan; if (getPixel(ip, Ipixelplan)) { *(bitmap + i * width + j) = Ipixelplan; @@ -528,7 +532,8 @@ void vpImageSimulator::getImage(vpImage &I, const vpCameraParameters &ca zBuffer[i][j] = Xinter_optim[2]; } } - } else if (colorI == COLORED) { + } + else if (colorI == COLORED) { vpRGBa Ipixelplan; if (getPixel(ip, Ipixelplan)) { if (Xinter_optim[2] < zBuffer[i][j] || zBuffer[i][j] < 0) { @@ -724,11 +729,12 @@ void vpImageSimulator::getImage(vpImage &I, std::listgetPixel(ip, Ipixelplan); *(bitmap + i * width + j) = Ipixelplan; - } else if (simList[indice]->colorI == COLORED) { + } + else if (simList[indice]->colorI == COLORED) { vpRGBa Ipixelplan(255, 255, 255); simList[indice]->getPixel(ip, Ipixelplan); unsigned char pixelgrey = - (unsigned char)(0.2126 * Ipixelplan.R + 0.7152 * Ipixelplan.G + 0.0722 * Ipixelplan.B); + (unsigned char)(0.2126 * Ipixelplan.R + 0.7152 * Ipixelplan.G + 0.0722 * Ipixelplan.B); *(bitmap + i * width + j) = pixelgrey; } } @@ -926,7 +932,8 @@ void vpImageSimulator::getImage(vpImage &I, std::list pixelcolor.G = Ipixelplan; pixelcolor.B = Ipixelplan; *(bitmap + i * width + j) = pixelcolor; - } else if (simList[indice]->colorI == COLORED) { + } + else if (simList[indice]->colorI == COLORED) { vpRGBa Ipixelplan(255, 255, 255); simList[indice]->getPixel(ip, Ipixelplan); // unsigned char pixelgrey = 0.2126 * Ipixelplan.R + 0.7152 * @@ -977,7 +984,8 @@ void vpImageSimulator::setCameraPosition(const vpHomogeneousMatrix &cMt_) if (angle > 0) { visible = true; - } else { + } + else { visible = false; } @@ -1263,7 +1271,8 @@ bool vpImageSimulator::getPixel(const vpImagePoint &iP, unsigned char &Ipixelpla else if (interp == SIMPLE) Ipixelplan = Ig[(unsigned int)i2][(unsigned int)j2]; return true; - } else + } + else return false; } @@ -1316,7 +1325,8 @@ bool vpImageSimulator::getPixel(vpImage &Isrc, const vpImagePoint else if (interp == SIMPLE) Ipixelplan = Isrc[(unsigned int)i2][(unsigned int)j2]; return true; - } else + } + else return false; } @@ -1368,7 +1378,8 @@ bool vpImageSimulator::getPixel(const vpImagePoint &iP, vpRGBa &Ipixelplan) else if (interp == SIMPLE) Ipixelplan = Ic[(unsigned int)i2][(unsigned int)j2]; return true; - } else + } + else return false; } @@ -1420,7 +1431,8 @@ bool vpImageSimulator::getPixel(vpImage &Isrc, const vpImagePoint &iP, v else if (interp == SIMPLE) Ipixelplan = Isrc[(unsigned int)i2][(unsigned int)j2]; return true; - } else + } + else return false; } @@ -1536,3 +1548,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpImageSimulator & os << ""; return os; } +END_VISP_NAMESPACE diff --git a/modules/robot/src/light/vpRingLight.cpp b/modules/robot/src/light/vpRingLight.cpp index 27f469e6ea..68c0612e63 100644 --- a/modules/robot/src/light/vpRingLight.cpp +++ b/modules/robot/src/light/vpRingLight.cpp @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + \file vpRingLight.cpp + \brief Ring light management under unix. +*/ + #include #if defined(VISP_HAVE_MODULE_IO) && defined(VISP_HAVE_PARPORT) @@ -48,11 +53,7 @@ #include #include -/*! - \file vpRingLight.cpp - \brief Ring light management under unix. -*/ - +BEGIN_VISP_NAMESPACE /*! Constructor to access to the ring light device connected to the parallel @@ -212,7 +213,7 @@ void vpRingLight::off() // vpTRACE("Send 0x%x = %d\n", data, data); parport.sendData(data); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRingLight.cpp.o) has no symbols void dummy_vpRingLight() { }; diff --git a/modules/robot/src/real-robot/afma4/vpAfma4.cpp b/modules/robot/src/real-robot/afma4/vpAfma4.cpp index 264f1a1ad8..58a63de5fd 100644 --- a/modules/robot/src/real-robot/afma4/vpAfma4.cpp +++ b/modules/robot/src/real-robot/afma4/vpAfma4.cpp @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* ----------------------------------------------------------------------- */ /* --- STATIC ------------------------------------------------------------ */ /* ---------------------------------------------------------------------- */ @@ -600,3 +601,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpAfma4 &afma4) return os; } +END_VISP_NAMESPACE diff --git a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp index cdfac7c7e9..700c2edb51 100644 --- a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp +++ b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* ---------------------------------------------------------------------- */ /* --- STATIC ----------------------------------------------------------- */ /* ---------------------------------------------------------------------- */ @@ -1752,7 +1753,7 @@ void vpRobotAfma4::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity."); } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotAfma4.cpp.o) has no symbols void dummy_vpRobotAfma4() { }; diff --git a/modules/robot/src/real-robot/afma4/vpServolens.cpp b/modules/robot/src/real-robot/afma4/vpServolens.cpp index f4a8bc9fa0..fd58b201f8 100644 --- a/modules/robot/src/real-robot/afma4/vpServolens.cpp +++ b/modules/robot/src/real-robot/afma4/vpServolens.cpp @@ -59,13 +59,14 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Default constructor. Does nothing. \sa open() */ -vpServolens::vpServolens() : remfd(0), isinit(false) {} +vpServolens::vpServolens() : remfd(0), isinit(false) { } /*! Open and initialize the Servolens serial link at 9600 bauds, 7 @@ -512,16 +513,19 @@ bool vpServolens::getPosition(vpServoType servo, unsigned int &position) const if (c >= '0' && c <= '9') { *pt_posit++ = c; /* sauvegarde de la position */ lecture_posit_en_cours = 1; - } else if (lecture_posit_en_cours) { + } + else if (lecture_posit_en_cours) { fin_lect_posit = 1; *pt_posit = '\0'; - } else + } + else posit_car = 0; break; } - } else { - // Timout sur la lecture, on retoure FALSE + } + else { + // Timout sur la lecture, on retoure FALSE return false; } } while (!fin_lect_posit); @@ -710,7 +714,7 @@ bool vpServolens::read(char *c, long timeout_s) const } fd_set readfds; /* list of fds for select to listen to */ - struct timeval timeout = {timeout_s, 0}; // seconde, micro-sec + struct timeval timeout = { timeout_s, 0 }; // seconde, micro-sec FD_ZERO(&readfds); FD_SET(static_cast(this->remfd), &readfds); @@ -793,5 +797,5 @@ bool vpServolens::clean(const char *in, char *out) const } return (error); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/real-robot/afma6/vpAfma6.cpp b/modules/robot/src/real-robot/afma6/vpAfma6.cpp index 93f1e324c2..3174f11e2f 100644 --- a/modules/robot/src/real-robot/afma6/vpAfma6.cpp +++ b/modules/robot/src/real-robot/afma6/vpAfma6.cpp @@ -58,6 +58,7 @@ /* --- STATIC ------------------------------------------------------------ */ /* ---------------------------------------------------------------------- */ +BEGIN_VISP_NAMESPACE static const char *opt_Afma6[] = { "JOINT_MAX", "JOINT_MIN", "LONG_56", "COUPL_56", "CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", nullptr }; @@ -1590,3 +1591,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpAfma6 &afma6) return os; } +END_VISP_NAMESPACE diff --git a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp index 0cbc49a76c..6678162334 100644 --- a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp +++ b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp @@ -51,6 +51,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* ---------------------------------------------------------------------- */ /* --- STATIC ----------------------------------------------------------- */ /* ---------------------------------------------------------------------- */ @@ -2307,7 +2308,7 @@ bool vpRobotAfma6::checkJointLimits(vpColVector &jointsStatus) return status; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotAfma6.cpp.o) has no symbols void dummy_vpRobotAfma6() { }; diff --git a/modules/robot/src/real-robot/bebop2/vpRobotBebop2.cpp b/modules/robot/src/real-robot/bebop2/vpRobotBebop2.cpp index feb38b1155..61aa27ab61 100644 --- a/modules/robot/src/real-robot/bebop2/vpRobotBebop2.cpp +++ b/modules/robot/src/real-robot/bebop2/vpRobotBebop2.cpp @@ -72,6 +72,7 @@ extern "C" { + z : down */ +BEGIN_VISP_NAMESPACE bool vpRobotBebop2::m_running = false; ARCONTROLLER_Device_t *vpRobotBebop2::m_deviceController = nullptr; @@ -2002,7 +2003,7 @@ void vpRobotBebop2::commandReceivedCallback(eARCONTROLLER_DICTIONARY_KEY command } #undef TAG - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotBebop2.cpp.o) has // no symbols diff --git a/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.cpp b/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.cpp index bf9231b1ac..6f2448e035 100644 --- a/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.cpp +++ b/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.cpp @@ -52,6 +52,7 @@ #include +BEGIN_VISP_NAMESPACE vpRobotBiclops::vpRobotBiclopsController::vpRobotBiclopsController() : m_biclops(), m_axisMask(0), m_panAxis(nullptr), m_tiltAxis(nullptr), m_vergeAxis(nullptr), m_panProfile(), m_tiltProfile(), m_vergeProfile(), m_shm(), m_stopControllerThread(false) @@ -350,7 +351,7 @@ vpRobotBiclops::vpRobotBiclopsController::shmType vpRobotBiclops::vpRobotBiclops return tmp_shm; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: // libvisp_robot.a(vpRobotBiclopsController.cpp.o) has no symbols diff --git a/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.h b/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.h index abdcff0d92..21bbb4bc96 100644 --- a/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.h +++ b/modules/robot/src/real-robot/biclops/private/vpRobotBiclopsController_impl.h @@ -45,6 +45,7 @@ #include // Contrib for Biclops sdk #include // Contrib for Biclops sdk +BEGIN_VISP_NAMESPACE #if defined(_WIN32) class VISP_EXPORT Biclops; // needed for dll creation #endif @@ -65,7 +66,7 @@ class VISP_EXPORT Biclops; // needed for dll creation * * This class uses libraries libBiclops.so, libUtils.so and libPMD.so and * includes Biclops.h and PMDUtils.h provided by Traclabs. - */ +*/ class VISP_EXPORT vpRobotBiclops::vpRobotBiclopsController { public: @@ -242,9 +243,9 @@ class VISP_EXPORT vpRobotBiclops::vpRobotBiclopsController shmType m_shm; bool m_stopControllerThread; }; - -#endif /* #ifndef _vpRobotBiclopsController_h_ */ +END_VISP_NAMESPACE +#endif // #ifdef VISP_HAVE_BICLOPS #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS -#endif +#endif /* #ifndef _vpRobotBiclopsController_h_ */ diff --git a/modules/robot/src/real-robot/biclops/vpBiclops.cpp b/modules/robot/src/real-robot/biclops/vpBiclops.cpp index 95b9763943..5886148d85 100644 --- a/modules/robot/src/real-robot/biclops/vpBiclops.cpp +++ b/modules/robot/src/real-robot/biclops/vpBiclops.cpp @@ -37,6 +37,7 @@ #include #include +BEGIN_VISP_NAMESPACE const unsigned int vpBiclops::ndof = 2; const float vpBiclops::h = 0.048f; const float vpBiclops::panJointLimit = (float)(M_PI); @@ -257,3 +258,4 @@ void vpBiclops::get_fJe(const vpColVector &q, vpMatrix &fJe) const fJe[5][0] = 1; } } +END_VISP_NAMESPACE diff --git a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp index a22d01df94..80e4a1536c 100644 --- a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp +++ b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp @@ -55,6 +55,7 @@ //#define VP_DEBUG_MODE 12 // Activate debug level up to 12 #include +BEGIN_VISP_NAMESPACE /* ---------------------------------------------------------------------- */ /* --- STATIC ------------------------------------------------------------ */ /* ------------------------------------------------------------------------ */ @@ -852,7 +853,7 @@ void vpRobotBiclops::getDisplacement(vpRobot::vpControlFrameType frame, vpColVec m_q_previous = q_current; // Update for next call of this method } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotBiclops.cpp.o) has no symbols void dummy_vpRobotBiclops() { }; diff --git a/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp b/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp index 0f45047691..ce4e9a98e1 100644 --- a/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp +++ b/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp @@ -52,6 +52,7 @@ extern "C" { #include #include +BEGIN_VISP_NAMESPACE /*! Emergency stops the robot if the program is interrupted by a SIGINT @@ -946,7 +947,7 @@ double vpRobotFlirPtu::tics2deg(int axis, int tics) { return (tics * m_res[axis] \sa pos2rad() */ double vpRobotFlirPtu::tics2rad(int axis, int tics) { return vpMath::rad(tics2deg(axis, tics)); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotFlirPtu.cpp.o) has // no symbols diff --git a/modules/robot/src/real-robot/franka/vpForceTorqueGenerator_impl.cpp b/modules/robot/src/real-robot/franka/vpForceTorqueGenerator_impl.cpp index 36fe1eaf32..9a84971541 100644 --- a/modules/robot/src/real-robot/franka/vpForceTorqueGenerator_impl.cpp +++ b/modules/robot/src/real-robot/franka/vpForceTorqueGenerator_impl.cpp @@ -54,6 +54,7 @@ #include // TODO: Remove when initial_position var is removed +BEGIN_VISP_NAMESPACE vpColVector ft_cart_des_prev(6, 0); void vpForceTorqueGenerator::control_thread(franka::Robot *robot, std::atomic_bool &stop, const std::string &log_folder, @@ -77,7 +78,7 @@ void vpForceTorqueGenerator::control_thread(franka::Robot *robot, std::atomic_bo Eigen::Map > initial_gravity(gravity_array.data()); initial_tau_ext = initial_tau_measured - initial_gravity; - franka::Torques zero_torques{{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}}; + franka::Torques zero_torques { {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0} }; Eigen::VectorXd tau_joint_d(7), tau_cart_d(6); for (size_t i = 0; i < 7; i++) { tau_joint_d[i] = 0; @@ -123,7 +124,7 @@ void vpForceTorqueGenerator::control_thread(franka::Robot *robot, std::atomic_bo if (frame == vpRobot::CAMERA_FRAME || frame == vpRobot::REFERENCE_FRAME || frame == vpRobot::END_EFFECTOR_FRAME) { for (size_t i = 0; i < 7; i++) { gnuplot << "plot 'tau_d.log' u " << i + 1 << " title \"tau_d" << i + 1 << "\", 'tau_mes.log' u " << i + 1 - << " title \"tau_mes" << i + 1 << "\"" << std::endl; + << " title \"tau_mes" << i + 1 << "\"" << std::endl; gnuplot << "\npause -1\n" << std::endl; } } @@ -139,9 +140,9 @@ void vpForceTorqueGenerator::control_thread(franka::Robot *robot, std::atomic_bo std::ofstream log_tau_diff_prev; auto force_joint_control_callback = - [=, &log_time, &log_tau_cmd, &log_tau_d, &log_tau_mes, &time, &model, &initial_position, &stop, &zero_torques, - &robot_state, &tau_joint_d, &tau_error_integral, &mutex, - &tau_J_des](const franka::RobotState &state, franka::Duration period) -> franka::Torques { + [=, &log_time, &log_tau_cmd, &log_tau_d, &log_tau_mes, &time, &model, &initial_position, &stop, &zero_torques, + &robot_state, &tau_joint_d, &tau_error_integral, &mutex, + &tau_J_des](const franka::RobotState &state, franka::Duration period) -> franka::Torques { time += period.toSec(); if (time == 0.0) { @@ -174,18 +175,18 @@ void vpForceTorqueGenerator::control_thread(franka::Robot *robot, std::atomic_bo // FF + PI control tau_cmd << tau_joint_d + k_p * (tau_joint_d - tau_ext) + k_i * tau_error_integral; - std::array tau_d_array{}; + std::array tau_d_array {}; Eigen::VectorXd::Map(&tau_d_array[0], 7) = tau_cmd; if (!log_folder.empty()) { log_time << time << std::endl; log_tau_cmd << std::fixed << std::setprecision(8) << tau_cmd[0] << " " << tau_cmd[1] << " " << tau_cmd[2] << " " - << tau_cmd[3] << " " << tau_cmd[4] << " " << tau_cmd[5] << " " << tau_cmd[6] << std::endl; + << tau_cmd[3] << " " << tau_cmd[4] << " " << tau_cmd[5] << " " << tau_cmd[6] << std::endl; log_tau_d << std::fixed << std::setprecision(8) << tau_joint_d[0] << " " << tau_joint_d[1] << " " - << tau_joint_d[2] << " " << tau_joint_d[3] << " " << tau_joint_d[4] << " " << tau_joint_d[5] << " " - << tau_joint_d[6] << std::endl; + << tau_joint_d[2] << " " << tau_joint_d[3] << " " << tau_joint_d[4] << " " << tau_joint_d[5] << " " + << tau_joint_d[6] << std::endl; log_tau_mes << std::fixed << std::setprecision(8) << tau_ext[0] << " " << tau_ext[1] << " " << tau_ext[2] << " " - << tau_ext[3] << " " << tau_ext[4] << " " << tau_ext[5] << " " << tau_ext[6] << std::endl; + << tau_ext[3] << " " << tau_ext[4] << " " << tau_ext[5] << " " << tau_ext[6] << std::endl; } if (stop) { @@ -199,97 +200,97 @@ void vpForceTorqueGenerator::control_thread(franka::Robot *robot, std::atomic_bo } return tau_d_array; - }; + }; auto force_cart_control_callback = [=, &log_time, &log_tau_cmd, &log_tau_d, &log_tau_mes, &log_tau_diff, - &log_tau_diff_prev, &time, &model, /*&initial_position, */ - &stop, &zero_torques, &robot_state, &tau_cart_d, &tau_error_integral, &mutex, - &ft_cart_des](const franka::RobotState &state, - franka::Duration period) -> franka::Torques { - time += period.toSec(); + &log_tau_diff_prev, &time, &model, /*&initial_position, */ + &stop, &zero_torques, &robot_state, &tau_cart_d, &tau_error_integral, &mutex, + &ft_cart_des](const franka::RobotState &state, + franka::Duration period) -> franka::Torques { + time += period.toSec(); - Eigen::VectorXd tau_d(7), tau_cmd(7), tau_ext(7), desired_tau(7); + Eigen::VectorXd tau_d(7), tau_cmd(7), tau_ext(7), desired_tau(7); - if (time == 0.0) { - tau_d << 0, 0, 0, 0, 0, 0, 0; - tau_ext << 0, 0, 0, 0, 0, 0, 0; + if (time == 0.0) { + tau_d << 0, 0, 0, 0, 0, 0, 0; + tau_ext << 0, 0, 0, 0, 0, 0, 0; - if (!log_folder.empty()) { - log_time.open(log_folder + "/time.log"); - log_tau_cmd.open(log_folder + "/tau_cmd.log"); - log_tau_d.open(log_folder + "/tau_d.log"); - log_tau_mes.open(log_folder + "/tau_mes.log"); - log_tau_diff.open(log_folder + "/tau_diff.log"); - log_tau_diff_prev.open(log_folder + "/tau_diff_prev.log"); - } + if (!log_folder.empty()) { + log_time.open(log_folder + "/time.log"); + log_tau_cmd.open(log_folder + "/tau_cmd.log"); + log_tau_d.open(log_folder + "/tau_d.log"); + log_tau_mes.open(log_folder + "/tau_mes.log"); + log_tau_diff.open(log_folder + "/tau_diff.log"); + log_tau_diff_prev.open(log_folder + "/tau_diff_prev.log"); } + } - { - std::lock_guard lock(mutex); - robot_state = state; - } + { + std::lock_guard lock(mutex); + robot_state = state; + } - // get state variables - std::array jacobian_array = model.zeroJacobian(franka::Frame::kEndEffector, state); + // get state variables + std::array jacobian_array = model.zeroJacobian(franka::Frame::kEndEffector, state); - Eigen::Map > jacobian(jacobian_array.data()); - Eigen::Map > tau_measured(state.tau_J.data()); - Eigen::Map > gravity(gravity_array.data()); + Eigen::Map > jacobian(jacobian_array.data()); + Eigen::Map > tau_measured(state.tau_J.data()); + Eigen::Map > gravity(gravity_array.data()); - tau_ext << tau_measured - gravity - initial_tau_ext; + tau_ext << tau_measured - gravity - initial_tau_ext; - tau_error_integral += period.toSec() * (tau_d - tau_ext); + tau_error_integral += period.toSec() * (tau_d - tau_ext); - // Apply force with gradually increasing the force - for (size_t i = 0; i < 7; i++) { - tau_cart_d[i] = filter_gain * ft_cart_des[i] + (1 - filter_gain) * tau_cart_d[i]; - } + // Apply force with gradually increasing the force + for (size_t i = 0; i < 7; i++) { + tau_cart_d[i] = filter_gain * ft_cart_des[i] + (1 - filter_gain) * tau_cart_d[i]; + } - tau_d << jacobian.transpose() * tau_cart_d; + tau_d << jacobian.transpose() * tau_cart_d; - // FF + PI control - tau_cmd << tau_d + k_p * (tau_d - tau_ext) + k_i * tau_error_integral; + // FF + PI control + tau_cmd << tau_d + k_p * (tau_d - tau_ext) + k_i * tau_error_integral; - std::array tau_d_array{}; - Eigen::VectorXd::Map(&tau_d_array[0], 7) = tau_cmd; + std::array tau_d_array {}; + Eigen::VectorXd::Map(&tau_d_array[0], 7) = tau_cmd; - if (!log_folder.empty()) { - log_time << time << std::endl; - log_tau_cmd << std::fixed << std::setprecision(8) << tau_cmd[0] << " " << tau_cmd[1] << " " << tau_cmd[2] << " " - << tau_cmd[3] << " " << tau_cmd[4] << " " << tau_cmd[5] << " " << tau_cmd[6] << std::endl; - log_tau_d << std::fixed << std::setprecision(8) << tau_d[0] << " " << tau_d[1] << " " << tau_d[2] << " " - << tau_d[3] << " " << tau_d[4] << " " << tau_d[5] << " " << tau_d[6] << std::endl; - log_tau_mes << std::fixed << std::setprecision(8) << tau_ext[0] << " " << tau_ext[1] << " " << tau_ext[2] << " " - << tau_ext[3] << " " << tau_ext[4] << " " << tau_ext[5] << " " << tau_ext[6] << std::endl; - log_tau_diff << std::fixed << std::setprecision(8); - for (size_t i = 0; i < ft_cart_des.size(); i++) { - log_tau_diff << ft_cart_des[i] - tau_cart_d[i] << " "; - } - log_tau_diff << std::endl; + if (!log_folder.empty()) { + log_time << time << std::endl; + log_tau_cmd << std::fixed << std::setprecision(8) << tau_cmd[0] << " " << tau_cmd[1] << " " << tau_cmd[2] << " " + << tau_cmd[3] << " " << tau_cmd[4] << " " << tau_cmd[5] << " " << tau_cmd[6] << std::endl; + log_tau_d << std::fixed << std::setprecision(8) << tau_d[0] << " " << tau_d[1] << " " << tau_d[2] << " " + << tau_d[3] << " " << tau_d[4] << " " << tau_d[5] << " " << tau_d[6] << std::endl; + log_tau_mes << std::fixed << std::setprecision(8) << tau_ext[0] << " " << tau_ext[1] << " " << tau_ext[2] << " " + << tau_ext[3] << " " << tau_ext[4] << " " << tau_ext[5] << " " << tau_ext[6] << std::endl; + log_tau_diff << std::fixed << std::setprecision(8); + for (size_t i = 0; i < ft_cart_des.size(); i++) { + log_tau_diff << ft_cart_des[i] - tau_cart_d[i] << " "; + } + log_tau_diff << std::endl; - log_tau_diff_prev << std::fixed << std::setprecision(8); - for (size_t i = 0; i < ft_cart_des.size(); i++) { - log_tau_diff_prev << ft_cart_des[i] - ft_cart_des_prev[i] << " "; - } - log_tau_diff_prev << std::endl; + log_tau_diff_prev << std::fixed << std::setprecision(8); + for (size_t i = 0; i < ft_cart_des.size(); i++) { + log_tau_diff_prev << ft_cart_des[i] - ft_cart_des_prev[i] << " "; } + log_tau_diff_prev << std::endl; + } - if (stop) { - if (!log_folder.empty()) { - log_time.close(); - log_tau_cmd.close(); - log_tau_d.close(); - log_tau_mes.close(); - log_tau_diff.close(); - log_tau_diff_prev.close(); - } - return franka::MotionFinished(zero_torques); + if (stop) { + if (!log_folder.empty()) { + log_time.close(); + log_tau_cmd.close(); + log_tau_d.close(); + log_tau_mes.close(); + log_tau_diff.close(); + log_tau_diff_prev.close(); } + return franka::MotionFinished(zero_torques); + } - ft_cart_des_prev = ft_cart_des; + ft_cart_des_prev = ft_cart_des; - return tau_d_array; - }; + return tau_d_array; + }; #if !(VISP_HAVE_FRANKA_VERSION < 0x000500) double cutoff_frequency = 10; @@ -302,7 +303,8 @@ void vpForceTorqueGenerator::control_thread(franka::Robot *robot, std::atomic_bo try { robot->control(force_joint_control_callback, true, cutoff_frequency); break; - } catch (const franka::ControlException &e) { + } + catch (const franka::ControlException &e) { std::cerr << "Warning: communication error: " << e.what() << "\nRetry attempt: " << attempt << std::endl; robot->automaticErrorRecovery(); if (attempt == nbAttempts) @@ -319,7 +321,8 @@ void vpForceTorqueGenerator::control_thread(franka::Robot *robot, std::atomic_bo try { robot->control(force_cart_control_callback, true, cutoff_frequency); break; - } catch (const franka::ControlException &e) { + } + catch (const franka::ControlException &e) { std::cerr << "Warning: communication error: " << e.what() << "\nRetry attempt: " << attempt << std::endl; robot->automaticErrorRecovery(); if (attempt == nbAttempts) @@ -333,8 +336,8 @@ void vpForceTorqueGenerator::control_thread(franka::Robot *robot, std::atomic_bo } } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpForceTorqueGenerator.cpp.o) has no symbols -void dummy_vpForceTorqueGenerator(){}; +void dummy_vpForceTorqueGenerator() { }; #endif // VISP_HAVE_FRANKA diff --git a/modules/robot/src/real-robot/franka/vpForceTorqueGenerator_impl.h b/modules/robot/src/real-robot/franka/vpForceTorqueGenerator_impl.h index 05e1bc47dd..ac7546b82c 100644 --- a/modules/robot/src/real-robot/franka/vpForceTorqueGenerator_impl.h +++ b/modules/robot/src/real-robot/franka/vpForceTorqueGenerator_impl.h @@ -54,17 +54,18 @@ #include +BEGIN_VISP_NAMESPACE class vpForceTorqueGenerator { public: - vpForceTorqueGenerator() {} - virtual ~vpForceTorqueGenerator() {} + vpForceTorqueGenerator() { } + virtual ~vpForceTorqueGenerator() { } void control_thread(franka::Robot *robot, std::atomic_bool &stop, const std::string &log_folder, const vpRobot::vpControlFrameType &frame, const std::array &tau_J_des, const vpColVector &ft_cart_des, franka::RobotState &robot_state, std::mutex &mutex, const double &filter_gain, const bool &activate_pi_controller); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/real-robot/franka/vpJointPosTrajGenerator_impl.cpp b/modules/robot/src/real-robot/franka/vpJointPosTrajGenerator_impl.cpp index d9ea9f759d..fe53abbd21 100644 --- a/modules/robot/src/real-robot/franka/vpJointPosTrajGenerator_impl.cpp +++ b/modules/robot/src/real-robot/franka/vpJointPosTrajGenerator_impl.cpp @@ -50,9 +50,10 @@ #include #include +BEGIN_VISP_NAMESPACE vpJointPosTrajGenerator::vpJointPosTrajGenerator(double speed_factor, const std::array &q_goal) : m_q_goal(7), m_q_start(7), m_delta_q(7), m_dq_max_sync(7), m_t_1_sync(7), m_t_2_sync(7), m_t_f_sync(7), m_q_1(7), - m_dq_max(7), m_ddq_max_start(7), m_ddq_max_goal(7) + m_dq_max(7), m_ddq_max_start(7), m_ddq_max_goal(7) { for (size_t i = 0; i < 7; i++) { m_q_goal[i] = q_goal[i]; @@ -75,26 +76,30 @@ bool vpJointPosTrajGenerator::calculateDesiredValues(double t, vpColVector &delt vpColVector t_d = m_t_2_sync - m_t_1_sync; vpColVector delta_t_2_sync = m_t_f_sync - m_t_2_sync; - std::array joint_motion_finished{}; + std::array joint_motion_finished {}; for (size_t i = 0; i < 7; i++) { if (std::abs(m_delta_q[i]) < kDeltaQMotionFinished) { delta_q_d[i] = 0.; joint_motion_finished[i] = true; - } else { + } + else { if (t < m_t_1_sync[i]) { delta_q_d[i] = -1.0 / std::pow(m_t_1_sync[i], 3.0) * m_dq_max_sync[i] * sign_delta_q[i] * - (0.5 * t - m_t_1_sync[i]) * std::pow(t, 3.0); - } else if (t >= m_t_1_sync[i] && t < m_t_2_sync[i]) { + (0.5 * t - m_t_1_sync[i]) * std::pow(t, 3.0); + } + else if (t >= m_t_1_sync[i] && t < m_t_2_sync[i]) { delta_q_d[i] = m_q_1[i] + (t - m_t_1_sync[i]) * m_dq_max_sync[i] * sign_delta_q[i]; - } else if (t >= m_t_2_sync[i] && t < m_t_f_sync[i]) { + } + else if (t >= m_t_2_sync[i] && t < m_t_f_sync[i]) { delta_q_d[i] = m_delta_q[i] + 0.5 * - (1.0 / std::pow(delta_t_2_sync[i], 3.0) * - (t - m_t_1_sync[i] - 2.0 * delta_t_2_sync[i] - t_d[i]) * - std::pow((t - m_t_1_sync[i] - t_d[i]), 3.0) + - (2.0 * t - 2.0 * m_t_1_sync[i] - delta_t_2_sync[i] - 2.0 * t_d[i])) * - m_dq_max_sync[i] * sign_delta_q[i]; - } else { + (1.0 / std::pow(delta_t_2_sync[i], 3.0) * + (t - m_t_1_sync[i] - 2.0 * delta_t_2_sync[i] - t_d[i]) * + std::pow((t - m_t_1_sync[i] - t_d[i]), 3.0) + + (2.0 * t - 2.0 * m_t_1_sync[i] - delta_t_2_sync[i] - 2.0 * t_d[i])) * + m_dq_max_sync[i] * sign_delta_q[i]; + } + else { delta_q_d[i] = m_delta_q[i]; joint_motion_finished[i] = true; } @@ -120,8 +125,8 @@ void vpJointPosTrajGenerator::calculateSynchronizedValues() if (std::abs(m_delta_q[i]) < (3.0 / 4.0 * (std::pow(m_dq_max[i], 2.0) / m_ddq_max_start[i]) + 3.0 / 4.0 * (std::pow(m_dq_max[i], 2.0) / m_ddq_max_goal[i]))) { dq_max_reach[i] = - std::sqrt(4.0 / 3.0 * m_delta_q[i] * sign_delta_q[i] * (m_ddq_max_start[i] * m_ddq_max_goal[i]) / - (m_ddq_max_start[i] + m_ddq_max_goal[i])); + std::sqrt(4.0 / 3.0 * m_delta_q[i] * sign_delta_q[i] * (m_ddq_max_start[i] * m_ddq_max_goal[i]) / + (m_ddq_max_start[i] + m_ddq_max_goal[i])); } t_1[i] = 1.5 * dq_max_reach[i] / m_ddq_max_start[i]; delta_t_2[i] = 1.5 * dq_max_reach[i] / m_ddq_max_goal[i]; @@ -174,7 +179,8 @@ franka::JointPositions vpJointPosTrajGenerator::operator()(const franka::RobotSt output.motion_finished = motion_finished; return output; } +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpJointPosTrajGenerator.cpp.o) has no symbols -void dummy_vpJointPosTrajGenerator(){}; +void dummy_vpJointPosTrajGenerator() { }; #endif diff --git a/modules/robot/src/real-robot/franka/vpJointPosTrajGenerator_impl.h b/modules/robot/src/real-robot/franka/vpJointPosTrajGenerator_impl.h index b266abf114..7ba37e92cd 100644 --- a/modules/robot/src/real-robot/franka/vpJointPosTrajGenerator_impl.h +++ b/modules/robot/src/real-robot/franka/vpJointPosTrajGenerator_impl.h @@ -54,11 +54,12 @@ #include #include +BEGIN_VISP_NAMESPACE /** * An example showing how to generate a joint pose motion to a goal position. Adapted from: * Wisama Khalil and Etienne Dombre. 2002. Modeling, Identification and Control of Robots * (Kogan Page Science Paper edition). - */ +*/ class vpJointPosTrajGenerator { public: @@ -100,6 +101,6 @@ class vpJointPosTrajGenerator double m_time = 0.0; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/real-robot/franka/vpJointVelTrajGenerator_impl.cpp b/modules/robot/src/real-robot/franka/vpJointVelTrajGenerator_impl.cpp index e357b4d1ba..d88eba020f 100644 --- a/modules/robot/src/real-robot/franka/vpJointVelTrajGenerator_impl.cpp +++ b/modules/robot/src/real-robot/franka/vpJointVelTrajGenerator_impl.cpp @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE void vpJointVelTrajGenerator::control_thread(franka::Robot *robot, std::atomic_bool &stop, const std::string &log_folder, const vpRobot::vpControlFrameType &frame, const vpHomogeneousMatrix &eMc, @@ -203,116 +204,116 @@ void vpJointVelTrajGenerator::control_thread(franka::Robot *robot, std::atomic_b &time, &model, &q_prev, &v_cart_des, &stop, &robot_state, &mutex](const franka::RobotState &state, franka::Duration period) -> franka::JointVelocities { - time += period.toSec(); - - static vpJointVelTrajGenerator joint_vel_traj_generator; - - if (time == 0.0) { - if (!log_folder.empty()) { - log_time.open(log_folder + "/time.log"); - log_q_mes.open(log_folder + "/q-mes.log"); - log_dq_mes.open(log_folder + "/dq-mes.log"); - log_dq_des.open(log_folder + "/dq-des.log"); - log_dq_cmd.open(log_folder + "/dq-cmd.log"); - log_v_des.open(log_folder + "/v-des.log"); - } - q_prev = state.q_d; - joint_vel_traj_generator.init(state.q_d, q_min, q_max, dq_max, ddq_max, delta_t); - } - - { - std::lock_guard lock(mutex); - robot_state = state; - } - - // Get robot Jacobian - if (frame == vpRobot::END_EFFECTOR_FRAME || frame == vpRobot::TOOL_FRAME) { - std::array jacobian = model.bodyJacobian(franka::Frame::kEndEffector, state); - // Convert row-major to col-major - for (size_t i = 0; i < 6; i++) { // TODO make a function - for (size_t j = 0; j < 7; j++) { - eJe[i][j] = jacobian[j * 6 + i]; - } - } - } - else if (frame == vpRobot::REFERENCE_FRAME) { - std::array jacobian = model.zeroJacobian(franka::Frame::kEndEffector, state); - // Convert row-major to col-major - for (size_t i = 0; i < 6; i++) { // TODO make a function - for (size_t j = 0; j < 7; j++) { - fJe[i][j] = jacobian[j * 6 + i]; - } - } - } - - // Compute joint velocity - vpColVector q_dot; - if (frame == vpRobot::END_EFFECTOR_FRAME) { - q_dot = eJe.pseudoInverse() * v_cart_des; // TODO introduce try catch - } - else if (frame == vpRobot::TOOL_FRAME) { - q_dot = (cVe * eJe).pseudoInverse() * v_cart_des; // TODO introduce try catch - } - else if (frame == vpRobot::REFERENCE_FRAME) { - q_dot = (cVe * fJe).pseudoInverse() * v_cart_des; // TODO introduce try catch - } - - std::array dq_des_eigen; - for (size_t i = 0; i < 7; i++) // TODO create a function to convert - dq_des_eigen[i] = q_dot[i]; - - std::array q_cmd; - std::array dq_cmd; - - auto dq_des_ = dq_des_eigen; - if (stop) { // Stop asked - for (auto &dq_ : dq_des_) { - dq_ = 0.0; - } - } - - joint_vel_traj_generator.applyVel(dq_des_, q_cmd, dq_cmd); - - if (!log_folder.empty()) { - log_time << time << std::endl; - log_q_mes << std::fixed << std::setprecision(8) << state.q_d[0] << " " << state.q_d[1] << " " << state.q_d[2] - << " " << state.q_d[3] << " " << state.q_d[4] << " " << state.q_d[5] << " " << state.q_d[6] - << std::endl; - log_dq_mes << std::fixed << std::setprecision(8) << state.dq_d[0] << " " << state.dq_d[1] << " " << state.dq_d[2] - << " " << state.dq_d[3] << " " << state.dq_d[4] << " " << state.dq_d[5] << " " << state.dq_d[6] - << std::endl; - log_dq_cmd << std::fixed << std::setprecision(8) << dq_cmd[0] << " " << dq_cmd[1] << " " << dq_cmd[2] << " " - << dq_cmd[3] << " " << dq_cmd[4] << " " << dq_cmd[5] << " " << dq_cmd[6] << std::endl; - log_dq_des << std::fixed << std::setprecision(8) << dq_des_[0] << " " << dq_des_[1] << " " << dq_des_[2] << " " - << dq_des_[3] << " " << dq_des_[4] << " " << dq_des_[5] << " " << dq_des_[6] << std::endl; - log_v_des << std::fixed << std::setprecision(8) << v_cart_des[0] << " " << v_cart_des[1] << " " << v_cart_des[2] - << " " << v_cart_des[3] << " " << v_cart_des[4] << " " << v_cart_des[5] << std::endl; - } - - franka::JointVelocities velocities = { dq_cmd[0], dq_cmd[1], dq_cmd[2], dq_cmd[3], dq_cmd[4], dq_cmd[5], dq_cmd[6] }; - - if (stop) { - unsigned int nb_joint_stop = 0; - const double q_eps = 1e-6; // Motion finished - for (size_t i = 0; i < 7; i++) { - if (std::abs(state.q_d[i] - q_prev[i]) < q_eps) { - nb_joint_stop++; - } - } - if (nb_joint_stop == 7) { - if (!log_folder.empty()) { - log_time.close(); - log_q_mes.close(); - log_dq_mes.close(); - log_dq_des.close(); - log_dq_cmd.close(); - log_v_des.close(); - } - return franka::MotionFinished(velocities); - } - } - - q_prev = state.q_d; + time += period.toSec(); + + static vpJointVelTrajGenerator joint_vel_traj_generator; + + if (time == 0.0) { + if (!log_folder.empty()) { + log_time.open(log_folder + "/time.log"); + log_q_mes.open(log_folder + "/q-mes.log"); + log_dq_mes.open(log_folder + "/dq-mes.log"); + log_dq_des.open(log_folder + "/dq-des.log"); + log_dq_cmd.open(log_folder + "/dq-cmd.log"); + log_v_des.open(log_folder + "/v-des.log"); + } + q_prev = state.q_d; + joint_vel_traj_generator.init(state.q_d, q_min, q_max, dq_max, ddq_max, delta_t); + } + + { + std::lock_guard lock(mutex); + robot_state = state; + } + + // Get robot Jacobian + if (frame == vpRobot::END_EFFECTOR_FRAME || frame == vpRobot::TOOL_FRAME) { + std::array jacobian = model.bodyJacobian(franka::Frame::kEndEffector, state); + // Convert row-major to col-major + for (size_t i = 0; i < 6; i++) { // TODO make a function + for (size_t j = 0; j < 7; j++) { + eJe[i][j] = jacobian[j * 6 + i]; + } + } + } + else if (frame == vpRobot::REFERENCE_FRAME) { + std::array jacobian = model.zeroJacobian(franka::Frame::kEndEffector, state); + // Convert row-major to col-major + for (size_t i = 0; i < 6; i++) { // TODO make a function + for (size_t j = 0; j < 7; j++) { + fJe[i][j] = jacobian[j * 6 + i]; + } + } + } + + // Compute joint velocity + vpColVector q_dot; + if (frame == vpRobot::END_EFFECTOR_FRAME) { + q_dot = eJe.pseudoInverse() * v_cart_des; // TODO introduce try catch + } + else if (frame == vpRobot::TOOL_FRAME) { + q_dot = (cVe * eJe).pseudoInverse() * v_cart_des; // TODO introduce try catch + } + else if (frame == vpRobot::REFERENCE_FRAME) { + q_dot = (cVe * fJe).pseudoInverse() * v_cart_des; // TODO introduce try catch + } + + std::array dq_des_eigen; + for (size_t i = 0; i < 7; i++) // TODO create a function to convert + dq_des_eigen[i] = q_dot[i]; + + std::array q_cmd; + std::array dq_cmd; + + auto dq_des_ = dq_des_eigen; + if (stop) { // Stop asked + for (auto &dq_ : dq_des_) { + dq_ = 0.0; + } + } + + joint_vel_traj_generator.applyVel(dq_des_, q_cmd, dq_cmd); + + if (!log_folder.empty()) { + log_time << time << std::endl; + log_q_mes << std::fixed << std::setprecision(8) << state.q_d[0] << " " << state.q_d[1] << " " << state.q_d[2] + << " " << state.q_d[3] << " " << state.q_d[4] << " " << state.q_d[5] << " " << state.q_d[6] + << std::endl; + log_dq_mes << std::fixed << std::setprecision(8) << state.dq_d[0] << " " << state.dq_d[1] << " " << state.dq_d[2] + << " " << state.dq_d[3] << " " << state.dq_d[4] << " " << state.dq_d[5] << " " << state.dq_d[6] + << std::endl; + log_dq_cmd << std::fixed << std::setprecision(8) << dq_cmd[0] << " " << dq_cmd[1] << " " << dq_cmd[2] << " " + << dq_cmd[3] << " " << dq_cmd[4] << " " << dq_cmd[5] << " " << dq_cmd[6] << std::endl; + log_dq_des << std::fixed << std::setprecision(8) << dq_des_[0] << " " << dq_des_[1] << " " << dq_des_[2] << " " + << dq_des_[3] << " " << dq_des_[4] << " " << dq_des_[5] << " " << dq_des_[6] << std::endl; + log_v_des << std::fixed << std::setprecision(8) << v_cart_des[0] << " " << v_cart_des[1] << " " << v_cart_des[2] + << " " << v_cart_des[3] << " " << v_cart_des[4] << " " << v_cart_des[5] << std::endl; + } + + franka::JointVelocities velocities = { dq_cmd[0], dq_cmd[1], dq_cmd[2], dq_cmd[3], dq_cmd[4], dq_cmd[5], dq_cmd[6] }; + + if (stop) { + unsigned int nb_joint_stop = 0; + const double q_eps = 1e-6; // Motion finished + for (size_t i = 0; i < 7; i++) { + if (std::abs(state.q_d[i] - q_prev[i]) < q_eps) { + nb_joint_stop++; + } + } + if (nb_joint_stop == 7) { + if (!log_folder.empty()) { + log_time.close(); + log_q_mes.close(); + log_dq_mes.close(); + log_dq_des.close(); + log_dq_cmd.close(); + log_v_des.close(); + } + return franka::MotionFinished(velocities); + } + } + + q_prev = state.q_d; #if (VISP_HAVE_FRANKA_VERSION < 0x000500) // state.q_d contains the last joint velocity command received by the robot. @@ -323,10 +324,10 @@ void vpJointVelTrajGenerator::control_thread(franka::Robot *robot, std::atomic_b // by the robot will prevent from getting discontinuity errors. // Note that if the robot does not receive a command it will try to extrapolate // the desired behavior assuming a constant acceleration model - return limitRate(ddq_max, velocities.dq, state.dq_d); + return limitRate(ddq_max, velocities.dq, state.dq_d); #else // With libfranka 0.5.0 franka::control enables limit_rate by default - return velocities; + return velocities; #endif }; @@ -623,7 +624,7 @@ std::array vpJointVelTrajGenerator::limitRate(const std::array +BEGIN_VISP_NAMESPACE class vpJointVelTrajGenerator { public: vpJointVelTrajGenerator() : m_status(), m_delta_q(), m_delta_q_max(), m_delta_q_acc(), m_q_final(), m_sign(), m_q_cmd(), m_q_cmd_prev(), - m_dist_AD(), m_dq_des(), m_dq_des_prev(), m_dist_to_final(), m_flagSpeed(), m_q_min(), m_q_max(), m_dq_max(), - m_ddq_max(), m_njoints(7), m_delta_t(0.001), m_flagJointLimit(false) - { - } - virtual ~vpJointVelTrajGenerator() {} + m_dist_AD(), m_dq_des(), m_dq_des_prev(), m_dist_to_final(), m_flagSpeed(), m_q_min(), m_q_max(), m_dq_max(), + m_ddq_max(), m_njoints(7), m_delta_t(0.001), m_flagJointLimit(false) + { } + virtual ~vpJointVelTrajGenerator() { } void applyVel(const std::array &dq_des, std::array &q_cmd, std::array &dq_cmd); @@ -81,7 +81,8 @@ class vpJointVelTrajGenerator const std::array &last_desired_values); private: - typedef enum { + typedef enum + { FLAGACC, // Axis in acceleration FLAGCTE, // Axis at constant velocity FLAGDEC, // Axis in deceleration @@ -116,6 +117,6 @@ class vpJointVelTrajGenerator const double m_offset_joint_limit = vpMath::rad(1); // stop before joint limit (rad) const double m_delta_q_min = 1e-9; // Delta q minimum (rad) }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp index 579dc4ffe1..7a265389fe 100644 --- a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp +++ b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp @@ -45,6 +45,7 @@ #include "vpJointPosTrajGenerator_impl.h" #include "vpJointVelTrajGenerator_impl.h" +BEGIN_VISP_NAMESPACE /*! Default constructor. @@ -1348,7 +1349,7 @@ int vpRobotFranka::gripperGrasp(double grasping_width, double speed, double forc return EXIT_SUCCESS; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotFranka.cpp.o) has // no symbols diff --git a/modules/robot/src/real-robot/kinova/vpRobotKinova.cpp b/modules/robot/src/real-robot/kinova/vpRobotKinova.cpp index 0b82a0095e..9fbe763f28 100644 --- a/modules/robot/src/real-robot/kinova/vpRobotKinova.cpp +++ b/modules/robot/src/real-robot/kinova/vpRobotKinova.cpp @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + * \file vpRobotKinova.cpp + * \brief Interface for Kinova Jaco2 robot. + */ + #include #ifdef VISP_HAVE_JACOSDK @@ -40,20 +45,16 @@ #include #include -/*! - * \file vpRobotKinova.cpp - * \brief Interface for Kinova Jaco2 robot. - */ - #include #include +BEGIN_VISP_NAMESPACE /*! * Default constructor that consider a 6 DoF Jaco arm. Use setDoF() to change the degrees of freedom. */ vpRobotKinova::vpRobotKinova() : m_eMc(), m_plugin_location("./"), m_verbose(false), m_plugin_loaded(false), m_devices_count(0), - m_devices_list(nullptr), m_active_device(-1), m_command_layer(CMD_LAYER_UNSET), m_command_layer_handle() + m_devices_list(nullptr), m_active_device(-1), m_command_layer(CMD_LAYER_UNSET), m_command_layer_handle() { init(); } @@ -78,7 +79,8 @@ void vpRobotKinova::setDoF(unsigned int dof) { if (dof == 4 || dof == 6 || dof == 7) { nDof = dof; - } else { + } + else { throw(vpException(vpException::fatalError, "Unsupported Kinova Jaco degrees of freedom: %d. Possible values are 4, 6 or 7.", dof)); } @@ -518,7 +520,8 @@ void vpRobotKinova::getPosition(const vpRobot::vpControlFrameType frame, vpColVe if (frame == JOINT_STATE) { getJointPosition(position); - } else if (frame == END_EFFECTOR_FRAME) { + } + else if (frame == END_EFFECTOR_FRAME) { CartesianPosition currentCommand; // We get the actual cartesian position of the robot KinovaGetCartesianCommand(currentCommand); @@ -529,7 +532,8 @@ void vpRobotKinova::getPosition(const vpRobot::vpControlFrameType frame, vpColVe position[3] = currentCommand.Coordinates.ThetaX; position[4] = currentCommand.Coordinates.ThetaY; position[5] = currentCommand.Coordinates.ThetaZ; - } else { + } + else { std::cout << "Not implemented ! " << std::endl; } } @@ -635,7 +639,8 @@ void vpRobotKinova::setPosition(const vpRobot::vpControlFrameType frame, const v std::cout << "Move robot to joint position [rad rad rad rad rad rad]: " << q.t() << std::endl; } KinovaSendBasicTrajectory(pointToSend); - } else if (frame == vpRobot::END_EFFECTOR_FRAME) { + } + else if (frame == vpRobot::END_EFFECTOR_FRAME) { if (q.size() != 6) { throw(vpException(vpException::fatalError, "Cannot move robot to cartesian position of dim %d that is not a 6-dim vector", q.size())); @@ -659,7 +664,8 @@ void vpRobotKinova::setPosition(const vpRobot::vpControlFrameType frame, const v } KinovaSendBasicTrajectory(pointToSend); - } else { + } + else { throw(vpException(vpException::fatalError, "Cannot move robot to a cartesian position. Only joint positioning is implemented")); } @@ -707,7 +713,7 @@ void vpRobotKinova::loadPlugin() #ifdef __linux__ // We load the API std::string plugin_name = (m_command_layer == CMD_LAYER_USB) ? std::string("Kinova.API.USBCommandLayerUbuntu.so") - : std::string("Kinova.API.EthCommandLayerUbuntu.so"); + : std::string("Kinova.API.EthCommandLayerUbuntu.so"); std::string plugin = vpIoTools::createFilePath(m_plugin_location, plugin_name); if (m_verbose) { std::cout << "Load plugin: \"" << plugin << "\"" << std::endl; @@ -718,7 +724,7 @@ void vpRobotKinova::loadPlugin() // We load the functions from the library KinovaCloseAPI = (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("CloseAPI")).c_str()); KinovaGetAngularCommand = - (int (*)(AngularPosition &))dlsym(m_command_layer_handle, (prefix + std::string("GetAngularCommand")).c_str()); + (int (*)(AngularPosition &))dlsym(m_command_layer_handle, (prefix + std::string("GetAngularCommand")).c_str()); KinovaGetCartesianCommand = (int (*)(CartesianPosition &))dlsym( m_command_layer_handle, (prefix + std::string("GetCartesianCommand")).c_str()); KinovaGetDevices = (int (*)(KinovaDevice devices[MAX_KINOVA_DEVICE], int &result))dlsym( @@ -727,17 +733,17 @@ void vpRobotKinova::loadPlugin() KinovaInitFingers = (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("InitFingers")).c_str()); KinovaMoveHome = (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("MoveHome")).c_str()); KinovaSendBasicTrajectory = - (int (*)(TrajectoryPoint))dlsym(m_command_layer_handle, (prefix + std::string("SendBasicTrajectory")).c_str()); + (int (*)(TrajectoryPoint))dlsym(m_command_layer_handle, (prefix + std::string("SendBasicTrajectory")).c_str()); KinovaSetActiveDevice = - (int (*)(KinovaDevice devices))dlsym(m_command_layer_handle, (prefix + std::string("SetActiveDevice")).c_str()); + (int (*)(KinovaDevice devices))dlsym(m_command_layer_handle, (prefix + std::string("SetActiveDevice")).c_str()); KinovaSetAngularControl = - (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("SetAngularControl")).c_str()); + (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("SetAngularControl")).c_str()); KinovaSetCartesianControl = - (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("SetCartesianControl")).c_str()); + (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("SetCartesianControl")).c_str()); #elif _WIN32 // We load the API. std::string plugin_name = (m_command_layer == CMD_LAYER_USB) ? std::string("CommandLayerWindows.dll") - : std::string("CommandLayerEthernet.dll"); + : std::string("CommandLayerEthernet.dll"); std::string plugin = vpIoTools::createFilePath(m_plugin_location, plugin_name); if (m_verbose) { std::cout << "Load plugin: \"" << plugin << "\"" << std::endl; @@ -748,9 +754,9 @@ void vpRobotKinova::loadPlugin() KinovaCloseAPI = (int (*)())GetProcAddress(m_command_layer_handle, "CloseAPI"); KinovaGetAngularCommand = (int (*)(AngularPosition &))GetProcAddress(m_command_layer_handle, "GetAngularCommand"); KinovaGetCartesianCommand = - (int (*)(CartesianPosition &))GetProcAddress(m_command_layer_handle, "GetCartesianCommand"); + (int (*)(CartesianPosition &))GetProcAddress(m_command_layer_handle, "GetCartesianCommand"); KinovaGetDevices = - (int (*)(KinovaDevice[MAX_KINOVA_DEVICE], int &))GetProcAddress(m_command_layer_handle, "GetDevices"); + (int (*)(KinovaDevice[MAX_KINOVA_DEVICE], int &))GetProcAddress(m_command_layer_handle, "GetDevices"); KinovaInitAPI = (int (*)())GetProcAddress(m_command_layer_handle, "InitAPI"); KinovaInitFingers = (int (*)())GetProcAddress(m_command_layer_handle, "InitFingers"); KinovaMoveHome = (int (*)())GetProcAddress(m_command_layer_handle, "MoveHome"); @@ -869,9 +875,9 @@ void vpRobotKinova::setActiveDevice(int device) KinovaSetActiveDevice(m_devices_list[m_active_device]); } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotKinova.cpp.o) has // no symbols -void dummy_vpRobotKinova(){}; +void dummy_vpRobotKinova() { }; #endif diff --git a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp index b7859649ac..b6bc4b3940 100644 --- a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp +++ b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp @@ -59,6 +59,7 @@ using std::chrono::seconds; using std::this_thread::sleep_for; using namespace std::chrono_literals; +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpRobotMavsdk::vpRobotMavsdkImpl { @@ -1578,7 +1579,9 @@ void vpRobotMavsdk::setVerbose(bool verbose) { m_impl->setVerbose(verbose); } * all the other vehicles are considered with flying capabilities. */ bool vpRobotMavsdk::hasFlyingCapability() { return m_impl->getFlyingCapability(); } - +#ifdef ENABLE_VISP_NAMESPACE + } +#endif #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotMavsdk.cpp.o) has no symbols void dummy_vpRobotMavsdk() { }; diff --git a/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp b/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp index 84658c4d3f..1d021e3a37 100644 --- a/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp +++ b/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp @@ -45,6 +45,7 @@ #ifdef VISP_HAVE_PIONEER +BEGIN_VISP_NAMESPACE /*! Default constructor that initializes Aria. */ @@ -234,7 +235,7 @@ vpColVector vpRobotPioneer::getVelocity(const vpRobot::vpControlFrameType frame) getVelocity(frame, velocity); return velocity; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotPioneer.cpp.o) has no symbols void dummy_vpRobotPioneer() { }; diff --git a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp index 3f631be8fe..97c795ae2d 100644 --- a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp +++ b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp @@ -47,6 +47,7 @@ std::chrono::milliseconds millis(1); +BEGIN_VISP_NAMESPACE RPMSerialInterface *vpPololu::m_interface = nullptr; int vpPololu::m_nb_servo = 0; @@ -331,7 +332,7 @@ void vpPololu::VelocityCmdThread() std::this_thread::sleep_for(20 * millis); } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpPololu.cpp.o) has no symbols void dummy_vpPololu() { }; diff --git a/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp b/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp index 253dce7c61..c34d830113 100644 --- a/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp +++ b/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp @@ -40,6 +40,7 @@ #include #include +BEGIN_VISP_NAMESPACE vpRobotPololuPtu::vpRobotPololuPtu(const std::string &device, int baudrate, bool verbose) : m_verbose(verbose) { @@ -289,7 +290,7 @@ void vpRobotPololuPtu::getPosition(const vpRobot::vpControlFrameType frame, vpCo q[0] = m_pan.getAngularPosition(); q[1] = m_tilt.getAngularPosition(); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotPololuPtu.cpp.o) has no symbols void dummy_vpRobotPololuPtu() { }; diff --git a/modules/robot/src/real-robot/ptu46/vpPtu46.cpp b/modules/robot/src/real-robot/ptu46/vpPtu46.cpp index 755bd43b2b..e5b7600a43 100644 --- a/modules/robot/src/real-robot/ptu46/vpPtu46.cpp +++ b/modules/robot/src/real-robot/ptu46/vpPtu46.cpp @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* ------------------------------------------------------------------------ */ /* --- COMPUTE ------------------------------------------------------------ */ /* ------------------------------------------------------------------------ */ @@ -291,3 +292,4 @@ void vpPtu46::get_fJe(const vpColVector &q, vpMatrix &fJe) const fJe[4][1] = -c1; fJe[5][0] = 1; } +END_VISP_NAMESPACE diff --git a/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp b/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp index 8cfa8d0484..67c6374206 100644 --- a/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp +++ b/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* ---------------------------------------------------------------------- */ /* --- STATIC ------------------------------------------------------------ */ /* ------------------------------------------------------------------------ */ @@ -768,7 +769,7 @@ void vpRobotPtu46::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto } } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotPtu46.cpp.o) has no symbols void dummy_vpRobotPtu46() { }; diff --git a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp index daed273a17..93d275e64f 100644 --- a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp +++ b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp @@ -40,6 +40,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Default constructor. * - set eMc transformation to eye() @@ -872,7 +873,7 @@ vpRobot::vpRobotStateType vpRobotUniversalRobots::setRobotState(vpRobot::vpRobot return vpRobot::setRobotState(newState); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotUniversalRobots.cpp.o) has no symbols void dummy_vpRobotUniversalRobots() { }; diff --git a/modules/robot/src/real-robot/viper/vpRobotViper650.cpp b/modules/robot/src/real-robot/viper/vpRobotViper650.cpp index bbca9c63e8..1b31930418 100644 --- a/modules/robot/src/real-robot/viper/vpRobotViper650.cpp +++ b/modules/robot/src/real-robot/viper/vpRobotViper650.cpp @@ -51,6 +51,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* ---------------------------------------------------------------------- */ /* --- STATIC ----------------------------------------------------------- */ /* ---------------------------------------------------------------------- */ @@ -2557,7 +2558,7 @@ void vpRobotViper650::closeGripper() const throw vpRobotException(vpRobotException::lowLevelError, "Cannot close the gripper."); } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotViper650.cpp.o) has // no symbols diff --git a/modules/robot/src/real-robot/viper/vpRobotViper850.cpp b/modules/robot/src/real-robot/viper/vpRobotViper850.cpp index 56e2861579..07b4243ba3 100644 --- a/modules/robot/src/real-robot/viper/vpRobotViper850.cpp +++ b/modules/robot/src/real-robot/viper/vpRobotViper850.cpp @@ -51,6 +51,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* ---------------------------------------------------------------------- */ /* --- STATIC ----------------------------------------------------------- */ /* ---------------------------------------------------------------------- */ @@ -2631,7 +2632,7 @@ void vpRobotViper850::setMaxRotationVelocityJoint6(double w6_max) \return Maximum rotation velocity on joint 6 expressed in rad/s. */ double vpRobotViper850::getMaxRotationVelocityJoint6() const { return maxRotationVelocity_joint6; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotViper850.cpp.o) has // no symbols diff --git a/modules/robot/src/real-robot/viper/vpViper.cpp b/modules/robot/src/real-robot/viper/vpViper.cpp index 0425c47140..4ca66c2f3a 100644 --- a/modules/robot/src/real-robot/viper/vpViper.cpp +++ b/modules/robot/src/real-robot/viper/vpViper.cpp @@ -52,6 +52,7 @@ #include #include +BEGIN_VISP_NAMESPACE const unsigned int vpViper::njoint = 6; /*! @@ -1286,3 +1287,4 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpViper &viper) return os; } +END_VISP_NAMESPACE diff --git a/modules/robot/src/real-robot/viper/vpViper650.cpp b/modules/robot/src/real-robot/viper/vpViper650.cpp index a2848c9810..c16c8c4c12 100644 --- a/modules/robot/src/real-robot/viper/vpViper650.cpp +++ b/modules/robot/src/real-robot/viper/vpViper650.cpp @@ -48,6 +48,7 @@ static const char *opt_viper650[] = { "CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", nullptr }; +BEGIN_VISP_NAMESPACE #ifdef VISP_HAVE_VIPER650_DATA const std::string vpViper650::CONST_EMC_MARLIN_F033C_WITHOUT_DISTORTION_FILENAME = std::string(VISP_VIPER650_DATA_PATH) + @@ -828,3 +829,4 @@ void vpViper650::getCameraParameters(vpCameraParameters &cam, const vpImage #include +BEGIN_VISP_NAMESPACE /*! Constructor. @@ -246,7 +247,7 @@ void vpRobotCamera::setPosition(const vpHomogeneousMatrix &cMw) this->cMw_ = cMw; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpRobotCamera.cpp.o) has no symbols void dummy_vpRobotCamera() { }; diff --git a/modules/robot/src/robot-simulator/vpRobotSimulator.cpp b/modules/robot/src/robot-simulator/vpRobotSimulator.cpp index c131bdce4f..0815e7010d 100644 --- a/modules/robot/src/robot-simulator/vpRobotSimulator.cpp +++ b/modules/robot/src/robot-simulator/vpRobotSimulator.cpp @@ -37,7 +37,9 @@ #include +BEGIN_VISP_NAMESPACE /*! Basic constructor that sets the sampling time by default to 40ms. */ -vpRobotSimulator::vpRobotSimulator() : vpRobot(), delta_t_(0.040f) {} +vpRobotSimulator::vpRobotSimulator() : vpRobot(), delta_t_(0.040f) { } +END_VISP_NAMESPACE diff --git a/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp b/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp index 9e5d3e32f9..2618e82b25 100644 --- a/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp +++ b/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp @@ -43,6 +43,7 @@ #include "../wireframe-simulator/vpScene.h" #include "../wireframe-simulator/vpVwstack.h" +BEGIN_VISP_NAMESPACE /*! Basic constructor */ @@ -354,7 +355,7 @@ vpHomogeneousMatrix vpRobotWireFrameSimulator::get_cMo() delete[] fMit; return cMoTemp; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: // libvisp_robot.a(vpRobotWireFrameSimulator.cpp.o) has no symbols diff --git a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp index 4a68074d8b..b0172373dd 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp @@ -51,6 +51,7 @@ #include "../wireframe-simulator/vpScene.h" #include "../wireframe-simulator/vpVwstack.h" +BEGIN_VISP_NAMESPACE const double vpSimulatorAfma6::defaultPositioningVelocity = 25.0; /*! @@ -2467,7 +2468,7 @@ bool vpSimulatorAfma6::setPosition(const vpHomogeneousMatrix &cdMo_, vpImage #include +BEGIN_VISP_NAMESPACE /*! Default constructor that sets the transformation between world frame and camera frame to identity. @@ -238,3 +239,4 @@ void vpSimulatorCamera::setPosition(const vpHomogeneousMatrix &wMc) this->wMc_ = wMc; } +END_VISP_NAMESPACE diff --git a/modules/robot/src/robot-simulator/vpSimulatorPioneer.cpp b/modules/robot/src/robot-simulator/vpSimulatorPioneer.cpp index 8ac4d4eeb6..d9ea150f3e 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorPioneer.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorPioneer.cpp @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Constructor. @@ -216,3 +217,4 @@ void vpSimulatorPioneer::getPosition(const vpRobot::vpControlFrameType frame, vp break; } } +END_VISP_NAMESPACE diff --git a/modules/robot/src/robot-simulator/vpSimulatorPioneerPan.cpp b/modules/robot/src/robot-simulator/vpSimulatorPioneerPan.cpp index b34b6a89fc..9afb713811 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorPioneerPan.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorPioneerPan.cpp @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Constructor. @@ -231,3 +232,4 @@ void vpSimulatorPioneerPan::getPosition(const vpRobot::vpControlFrameType frame, break; } } +END_VISP_NAMESPACE diff --git a/modules/robot/src/robot-simulator/vpSimulatorViper850.cpp b/modules/robot/src/robot-simulator/vpSimulatorViper850.cpp index b0780323d1..f97607b3a3 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorViper850.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorViper850.cpp @@ -51,6 +51,7 @@ #include "../wireframe-simulator/vpScene.h" #include "../wireframe-simulator/vpVwstack.h" +BEGIN_VISP_NAMESPACE const double vpSimulatorViper850::defaultPositioningVelocity = 25.0; /*! @@ -2358,7 +2359,7 @@ void vpSimulatorViper850::initialiseObjectRelativeToCamera(const vpHomogeneousMa fMo = fMit[7] * cMo_; m_mutex_scene.unlock(); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpSimulatorViper850.cpp.o) // has no symbols diff --git a/modules/robot/src/vpRobot.cpp b/modules/robot/src/vpRobot.cpp index 157997457c..546c300b63 100644 --- a/modules/robot/src/vpRobot.cpp +++ b/modules/robot/src/vpRobot.cpp @@ -37,6 +37,7 @@ #include #include +BEGIN_VISP_NAMESPACE const double vpRobot::maxTranslationVelocityDefault = 0.2; const double vpRobot::maxRotationVelocityDefault = 0.7; @@ -49,17 +50,16 @@ const double vpRobot::maxRotationVelocityDefault = 0.7; vpRobot::vpRobot(void) : stateRobot(vpRobot::STATE_STOP), frameRobot(vpRobot::CAMERA_FRAME), - maxTranslationVelocity(maxTranslationVelocityDefault), maxRotationVelocity(maxRotationVelocityDefault), nDof(0), - eJe(), eJeAvailable(false), fJe(), fJeAvailable(false), areJointLimitsAvailable(false), qmin(nullptr), qmax(nullptr), - verbose_(true) -{ -} + maxTranslationVelocity(maxTranslationVelocityDefault), maxRotationVelocity(maxRotationVelocityDefault), nDof(0), + eJe(), eJeAvailable(false), fJe(), fJeAvailable(false), areJointLimitsAvailable(false), qmin(nullptr), qmax(nullptr), + verbose_(true) +{ } vpRobot::vpRobot(const vpRobot &robot) : stateRobot(vpRobot::STATE_STOP), frameRobot(vpRobot::CAMERA_FRAME), - maxTranslationVelocity(maxTranslationVelocityDefault), maxRotationVelocity(maxRotationVelocityDefault), nDof(0), - eJe(), eJeAvailable(false), fJe(), fJeAvailable(false), areJointLimitsAvailable(false), qmin(nullptr), qmax(nullptr), - verbose_(true) + maxTranslationVelocity(maxTranslationVelocityDefault), maxRotationVelocity(maxRotationVelocityDefault), nDof(0), + eJe(), eJeAvailable(false), fJe(), fJeAvailable(false), areJointLimitsAvailable(false), qmin(nullptr), qmax(nullptr), + verbose_(true) { *this = robot; } @@ -268,3 +268,4 @@ void vpRobot::setMaxRotationVelocity(double w_max) \return Maximum rotation velocity expressed in rad/s. */ double vpRobot::getMaxRotationVelocity(void) const { return this->maxRotationVelocity; } +END_VISP_NAMESPACE diff --git a/modules/robot/src/vpRobotTemplate.cpp b/modules/robot/src/vpRobotTemplate.cpp index 523774c265..b13498e2b5 100644 --- a/modules/robot/src/vpRobotTemplate.cpp +++ b/modules/robot/src/vpRobotTemplate.cpp @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Basic initialization. */ @@ -277,7 +278,8 @@ void vpRobotTemplate::getPosition(const vpRobot::vpControlFrameType frame, vpCol { if (frame == JOINT_STATE) { getJointPosition(q); - } else { + } + else { std::cout << "Not implemented ! " << std::endl; } } @@ -307,3 +309,4 @@ void vpRobotTemplate::getDisplacement(const vpRobot::vpControlFrameType frame, v (void)q; std::cout << "Not implemented ! " << std::endl; } +END_VISP_NAMESPACE diff --git a/modules/robot/src/wireframe-simulator/vpArit.cpp b/modules/robot/src/wireframe-simulator/vpArit.cpp index 4e1455bb93..9412a88db0 100644 --- a/modules/robot/src/wireframe-simulator/vpArit.cpp +++ b/modules/robot/src/wireframe-simulator/vpArit.cpp @@ -44,6 +44,7 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE /* * La procedure "fprintf_matrix" affiche une matrice sur un fichier. * Entree : @@ -282,10 +283,11 @@ float cosin_to_angle(float ca, float sa) if (FABS(ca) < M_EPSILON) { a = (sa > (float)0.0) ? (float)M_PI_2 : (float)(-M_PI_2); - } else { + } + else { a = (float)atan((double)(sa / ca)); if (ca < (float)0.0) - a += (sa > (float)0.0) ? (float)M_PI : (float)(-M_PI); + a += (sa >(float)0.0) ? (float)M_PI : (float)(-M_PI); } return (a); } @@ -353,7 +355,8 @@ float norm_vector(Vector *vp) vp->x /= norm; vp->y /= norm; vp->z /= norm; - } else { + } + else { static char proc_name[] = "norm_vector"; fprintf(stderr, "%s: nul vector\n", proc_name); } @@ -499,13 +502,16 @@ void upright_vector(Vector *vp, Vector *up) if (FABS(vp->z) > M_EPSILON) { /* x et y sont fixes */ up->z = -(vp->x + vp->y) / vp->z; up->x = up->y = 1.0; - } else if (FABS(vp->y) > M_EPSILON) { /* x et z sont fixes */ + } + else if (FABS(vp->y) > M_EPSILON) { /* x et z sont fixes */ up->y = -(vp->x + vp->z) / vp->y; up->x = up->z = 1.0; - } else if (FABS(vp->x) > M_EPSILON) { /* y et z sont fixes */ + } + else if (FABS(vp->x) > M_EPSILON) { /* y et z sont fixes */ up->x = -(vp->y + vp->z) / vp->x; up->y = up->z = 1.0; - } else { + } + else { static char proc_name[] = "upright_vector"; up->x = up->y = up->z = 0.0; fprintf(stderr, "%s: nul vector\n", proc_name); @@ -568,7 +574,8 @@ void Matrix_to_Rotate(Matrix m, Vector *vp) cx = m[2][2] / cy; SET_COORD3(*vp, cosin_to_angle(cx, sx), cosin_to_angle(cy, sy), cosin_to_angle(cz, sz)); - } else { /* RZ = 0 => Ry = +/- 90 degres */ + } + else { /* RZ = 0 => Ry = +/- 90 degres */ sx = m[1][1]; cx = -m[2][1]; @@ -618,9 +625,9 @@ void Position_to_Matrix(AritPosition *pp, Matrix m) void Rotate_to_Matrix(Vector *vp, Matrix m) { float rx = vp->x * (float)M_PI / (float)180.0, /* passage en radians */ - ry = vp->y * (float)M_PI / (float)180.0, rz = vp->z * (float)M_PI / (float)180.0; + ry = vp->y * (float)M_PI / (float)180.0, rz = vp->z * (float)M_PI / (float)180.0; float cx = (float)cos((double)rx), sx = (float)sin((double)rx), cy = (float)cos((double)ry), - sy = (float)sin((double)ry), cz = (float)cos((double)rz), sz = (float)sin((double)rz); + sy = (float)sin((double)ry), cz = (float)cos((double)rz), sz = (float)sin((double)rz); m[0][0] = cy * cz; m[1][0] = (sx * sy * cz) - (cx * sz); @@ -742,5 +749,5 @@ void Translate_to_Matrix(Vector *vp, Matrix m) m[3][1] = vp->y; m[3][2] = vp->z; } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpArit.h b/modules/robot/src/wireframe-simulator/vpArit.h index 2e043502ad..b07a74ddcb 100644 --- a/modules/robot/src/wireframe-simulator/vpArit.h +++ b/modules/robot/src/wireframe-simulator/vpArit.h @@ -149,23 +149,29 @@ #define M_POLY2(x, a, b, c) (M_POLY1((x), (a), (b)) * (x) + (c)) #define M_POLY3(x, a, b, c, d) (M_POLY2((x), (a), (b), (c)) * (x) + (d)) -typedef struct { +BEGIN_VISP_NAMESPACE +typedef struct +{ int x, y; } Point2i; -typedef struct { +typedef struct +{ short x, y; } Point2s; -typedef struct { +typedef struct +{ int x, y, z; } Point3i; -typedef struct { +typedef struct +{ float x, y, z, w; } Point4f; -typedef struct { +typedef struct +{ float x, y, z; } Vector; @@ -185,7 +191,8 @@ typedef struct { * S = Sx.Sy.Sz Matrice d'homothetie sur les axes; * T = Tx.Ty.Tz Matrice de translation sur les axes. */ -typedef struct { +typedef struct +{ Vector rotate; /* vecteur rotation */ Vector scale; /* vecteur homothetie */ Vector translate; /* vecteur translation */ @@ -242,6 +249,6 @@ void Translate_to_Matrix(Vector *vp, Matrix m); void fscanf_Point3f(Point3f *pp); void fscanf_Vector(Vector *vp); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpAritio.cpp b/modules/robot/src/wireframe-simulator/vpAritio.cpp index d5cd1d50bf..db1771c16b 100644 --- a/modules/robot/src/wireframe-simulator/vpAritio.cpp +++ b/modules/robot/src/wireframe-simulator/vpAritio.cpp @@ -49,6 +49,8 @@ #include "vpToken.h" #include + +BEGIN_VISP_NAMESPACE /* * La procedure "fprintf_Position" ecrit en ascii un positionnement. * Entree : @@ -68,7 +70,7 @@ void fprintf_Position(FILE *f, AritPosition *pp) */ void fscanf_Point3f(Point3f *pp) { - static const char *err_tbl[] = {"float expected (coordinate ", " of point)"}; + static const char *err_tbl[] = { "float expected (coordinate ", " of point)" }; int t; /* Lecture de la premiere coordonnee du point. */ @@ -97,7 +99,7 @@ void fscanf_Point3f(Point3f *pp) */ void fscanf_Vector(Vector *vp) { - static const char *err_tbl[] = {"float expected (coordinate ", " of vector)"}; + static const char *err_tbl[] = { "float expected (coordinate ", " of vector)" }; int t; @@ -135,5 +137,5 @@ void fscanf_Position(AritPosition *pp) fscanf_Vector(&pp->translate); poperr(); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpAritio.h b/modules/robot/src/wireframe-simulator/vpAritio.h index 847e2f5351..bb3bd4f598 100644 --- a/modules/robot/src/wireframe-simulator/vpAritio.h +++ b/modules/robot/src/wireframe-simulator/vpAritio.h @@ -50,10 +50,11 @@ #include "vpArit.h" #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE void fprintf_Position(FILE *f, AritPosition *pp); void fscanf_Point3f(Point3f *pp); void fscanf_Vector(Vector *vp); void fscanf_Position(AritPosition *pp); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpBound.cpp b/modules/robot/src/wireframe-simulator/vpBound.cpp index b02f2358e1..02de188dbc 100644 --- a/modules/robot/src/wireframe-simulator/vpBound.cpp +++ b/modules/robot/src/wireframe-simulator/vpBound.cpp @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* * La procedure "free_Bound" libere la memoire d'une surface. * Les champs "bound.face.edge" ne sont pas utilises. @@ -217,5 +218,5 @@ void malloc_Bound_scene(Bound_scene *bsp, const char *name, Index bn) strcpy(bsp->name, name); bsp->bound.nbr = 0; } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpBound.h b/modules/robot/src/wireframe-simulator/vpBound.h index 10ead99c45..d40004790f 100644 --- a/modules/robot/src/wireframe-simulator/vpBound.h +++ b/modules/robot/src/wireframe-simulator/vpBound.h @@ -78,34 +78,40 @@ #define VECTOR_NBR 6144 #endif // face_normal +BEGIN_VISP_NAMESPACE #ifdef face_edge -typedef struct { +typedef struct +{ Index v0, v1; /* extremites */ Index f0, f1; /* faces */ } Edge; #endif // face_edge #ifdef face_edge -typedef struct { +typedef struct +{ Index nbr; /* nombre d'aretes */ Edge *ptr; /* liste dynamique */ } Edge_list; #endif // face_edge #ifdef face_normal -typedef struct { +typedef struct +{ Index nbr; /* nombre de vecteurs */ Vector *ptr; /* liste dynamique */ } Vector_list; #endif // face_normal -typedef struct { +typedef struct +{ float xmin, xmax; /* bornes sur l'axe x */ float ymin, ymax; /* bornes sur l'axe y */ float zmin, zmax; /* bornes sur l'axe z */ } Bounding_box; -typedef struct { +typedef struct +{ Index nbr; /* nombre de scenes */ Bound_scene *ptr; /* liste dynamique */ } Bound_scene_list; @@ -116,6 +122,6 @@ void free_Bound_scene(Bound_scene *bsp); void malloc_Bound(Bound *bp, Type type, int polygonal, Index fn, Index pn); void malloc_huge_Bound(Bound *bp); void malloc_Bound_scene(Bound_scene *bsp, const char *name, Index bn); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpBoundio.cpp b/modules/robot/src/wireframe-simulator/vpBoundio.cpp index 885dc77f69..09d5ecb3bb 100644 --- a/modules/robot/src/wireframe-simulator/vpBoundio.cpp +++ b/modules/robot/src/wireframe-simulator/vpBoundio.cpp @@ -55,6 +55,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* * La procedure "fscanf_Bound" lit en ascii une surface. * Entree : @@ -158,7 +159,7 @@ void fscanf_Face_list(Face_list *lp) */ void fscanf_Point3f_list(Point3f_list *lp) { - static const char *err_tbl[] = {"float expected (coordinate ", " of point)"}; + static const char *err_tbl[] = { "float expected (coordinate ", " of point)" }; Point3f *pp; /* point courant */ Point3f *pend; /* borne de "pp" */ @@ -201,5 +202,5 @@ void fscanf_Point3f_list(Point3f_list *lp) pp->z = (t == T_INT) ? (float)myint : myfloat; } } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpBoundio.h b/modules/robot/src/wireframe-simulator/vpBoundio.h index 297dbba28d..2b39dd91cb 100644 --- a/modules/robot/src/wireframe-simulator/vpBoundio.h +++ b/modules/robot/src/wireframe-simulator/vpBoundio.h @@ -49,9 +49,10 @@ #include "vpBound.h" +BEGIN_VISP_NAMESPACE void fscanf_Bound(Bound *bp); void fscanf_Face_list(Face_list *lp); void fscanf_Point3f_list(Point3f_list *lp); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpClipping.cpp b/modules/robot/src/wireframe-simulator/vpClipping.cpp index e4fa204653..a07f2cbd19 100644 --- a/modules/robot/src/wireframe-simulator/vpClipping.cpp +++ b/modules/robot/src/wireframe-simulator/vpClipping.cpp @@ -54,6 +54,7 @@ #include #include +BEGIN_VISP_NAMESPACE static void inter(Byte mask, Index v0, Index v1); static void point_4D_3D(Point4f *p4, int size, Byte *cp, Point3f *p3); @@ -119,7 +120,7 @@ void open_clipping(void) throw vpException(vpException::fatalError, "Error in open_clipping"); } #else - || (poly_tmp = (Index *)malloc(VERTEX_NBR * sizeof(Index))) == NULL) { + || (poly_tmp = (Index *)malloc(VERTEX_NBR * sizeof(Index))) == NULL) { static char proc_name[] = "open_clipping"; perror(proc_name); throw vpException(vpException::fatalError, "Error in open_clipping"); @@ -175,17 +176,20 @@ static Index clipping(Byte mask, Index vni, Index *pi, Index *po) if (ins == IS_INSIDE) { if (inp == IS_INSIDE) { /* arete interieure */ *po++ = vp; - } else { /* intersection */ + } + else { /* intersection */ inter(mask, vs, vp); *po++ = point4f_nbr++; } - } else { + } + else { if (inp == IS_INSIDE) { /* intersection */ inter(mask, vs, vp); *po++ = point4f_nbr++; *po++ = vp; vno++; - } else { /* arete exterieure */ + } + else { /* arete exterieure */ vno--; } } @@ -398,7 +402,8 @@ static void point_4D_3D(Point4f *p4, int size, Byte *cp, Point3f *p3) p3->x = p4->x / w; /* projection 4D en 3D */ p3->y = p4->y / w; p3->z = p4->z / w; - } else { /* marque invisible */ + } + else { /* marque invisible */ p3->z = -1.0; } } @@ -458,5 +463,5 @@ Byte where_is_Point4f(Point4f *p4) b |= IS_FRONT; return (b); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpClipping.h b/modules/robot/src/wireframe-simulator/vpClipping.h index 32ef60994a..9475f873af 100644 --- a/modules/robot/src/wireframe-simulator/vpClipping.h +++ b/modules/robot/src/wireframe-simulator/vpClipping.h @@ -53,12 +53,13 @@ #include "vpBound.h" #include "vpMy.h" +BEGIN_VISP_NAMESPACE void open_clipping(void); void open_clipping(void); void close_clipping(void); Bound *clipping_Bound(Bound *bp, Matrix m); void set_Point4f_code(Point4f *p4, int size, Byte *cp); Byte where_is_Point4f(Point4f *p4); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpCoreDisplay.cpp b/modules/robot/src/wireframe-simulator/vpCoreDisplay.cpp index f77e4151bd..7ba34aa3f6 100644 --- a/modules/robot/src/wireframe-simulator/vpCoreDisplay.cpp +++ b/modules/robot/src/wireframe-simulator/vpCoreDisplay.cpp @@ -51,6 +51,7 @@ #include "vpView.h" #include "vpVwstack.h" +BEGIN_VISP_NAMESPACE /* * POINT2I : * Tableau de points 2D dans l'espace ecran servant a l'affichage fil-de-fer. @@ -220,5 +221,5 @@ void wireframe_Face(Face *fp, Point2i *pp) SET_COORD2(*cp, pp[*vp].x, pp[*vp].y); } } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpCoreDisplay.h b/modules/robot/src/wireframe-simulator/vpCoreDisplay.h index 544af033a7..a38a46f86e 100644 --- a/modules/robot/src/wireframe-simulator/vpCoreDisplay.h +++ b/modules/robot/src/wireframe-simulator/vpCoreDisplay.h @@ -47,11 +47,12 @@ #include "vpArit.h" #include "vpBound.h" +BEGIN_VISP_NAMESPACE void open_display(void); void close_display(void); void point_3D_2D(Point3f *p3, Index size, int xsize, int ysize, Point2i *p2); void set_Bound_face_display(Bound *bp, Byte b); void wireframe_Face(Face *fp, Point2i *pp); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpImstack.h b/modules/robot/src/wireframe-simulator/vpImstack.h index 60ef76271c..1779885b17 100644 --- a/modules/robot/src/wireframe-simulator/vpImstack.h +++ b/modules/robot/src/wireframe-simulator/vpImstack.h @@ -43,13 +43,13 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE void fprintf_imstack(void); void load_imstack(void); void pop_imstack(void); void push_imstack(void); void swap_imstack(void); void add_imstack(void); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpKeyword.cpp b/modules/robot/src/wireframe-simulator/vpKeyword.cpp index 09959683d3..62857f64a6 100644 --- a/modules/robot/src/wireframe-simulator/vpKeyword.cpp +++ b/modules/robot/src/wireframe-simulator/vpKeyword.cpp @@ -48,7 +48,7 @@ #include #include #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE static void open_hash(void); static void close_hash(void); static int hashpjw(const char *str); @@ -62,7 +62,8 @@ static char *get_keyword(void); #define PRIME 211 #define NEXT(x) (x) = (x)->next -typedef struct bucket { +typedef struct bucket +{ struct bucket *next; /* element suivant */ char *ident; /* identifateur */ Byte length; /* longueur de "ident" */ @@ -231,5 +232,5 @@ Index get_symbol(char *ident, int length) } return (0); /* identificateur */ } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpKeyword.h b/modules/robot/src/wireframe-simulator/vpKeyword.h index 53486bd92d..7dc3b6dbee 100644 --- a/modules/robot/src/wireframe-simulator/vpKeyword.h +++ b/modules/robot/src/wireframe-simulator/vpKeyword.h @@ -45,10 +45,10 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE void open_keyword(Keyword *kwp); void close_keyword(void); Index get_symbol(char *ident, int length); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpLex.cpp b/modules/robot/src/wireframe-simulator/vpLex.cpp index 615a8d7db1..72aa61dcaf 100644 --- a/modules/robot/src/wireframe-simulator/vpLex.cpp +++ b/modules/robot/src/wireframe-simulator/vpLex.cpp @@ -55,6 +55,7 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE static void count(void); static void next_source(void); @@ -135,7 +136,7 @@ const char *lex_errtbl[] = {/* table des messages d'erreur */ "unexpected EOF in string or char constant", "newline in string or char constant", "string expected", - ""}; + "" }; char *mytext = NULL; int mylength = 0; @@ -726,7 +727,8 @@ static void next_source(void) *buf = EOF; *topbuf = EOB; /* sentinelle de fin de fichier */ mysptr = buf; - } else { + } + else { topbuf = buf + size; *topbuf = EOB; /* sentinelle de fin de buffer */ @@ -840,5 +842,5 @@ void pusherr(const char *str) } err_stack[size_stack++] = str; } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpLex.h b/modules/robot/src/wireframe-simulator/vpLex.h index 837c6d6a3d..b9bce39ec4 100644 --- a/modules/robot/src/wireframe-simulator/vpLex.h +++ b/modules/robot/src/wireframe-simulator/vpLex.h @@ -46,7 +46,7 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE void open_lex(void); void close_lex(void); int lex(void); @@ -58,6 +58,6 @@ void pusherr(const char *str); void popuperr(const char *str); void poperr(void); int lexecho(FILE *f, int token); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpMy.h b/modules/robot/src/wireframe-simulator/vpMy.h index ec3cb0f6f6..a0c2da6b74 100644 --- a/modules/robot/src/wireframe-simulator/vpMy.h +++ b/modules/robot/src/wireframe-simulator/vpMy.h @@ -85,7 +85,8 @@ (B) = (T); \ } +BEGIN_VISP_NAMESPACE typedef unsigned char Byte; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpMyio.cpp b/modules/robot/src/wireframe-simulator/vpMyio.cpp index 0455bffe9c..b58bac7b60 100644 --- a/modules/robot/src/wireframe-simulator/vpMyio.cpp +++ b/modules/robot/src/wireframe-simulator/vpMyio.cpp @@ -52,6 +52,7 @@ extern char *mytext; /* chaine du symbole courant */ +BEGIN_VISP_NAMESPACE /* * La procedure "fscanf_float" lit en ascii un nombre flottant. * Entree : @@ -123,5 +124,5 @@ void fscanf_Type(Type *ip) lexerr("start", "integer expected", NULL); *ip = (Type)myint; } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpMyio.h b/modules/robot/src/wireframe-simulator/vpMyio.h index 73e49dc263..9a18b05f01 100644 --- a/modules/robot/src/wireframe-simulator/vpMyio.h +++ b/modules/robot/src/wireframe-simulator/vpMyio.h @@ -49,11 +49,12 @@ #include "vpMy.h" +BEGIN_VISP_NAMESPACE void fscanf_float(float *fp); void fscanf_Index(Index *ip); void fscanf_int(int *ip); void fscanf_string(char **str); void fscanf_Type(Type *ip); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpParser.cpp b/modules/robot/src/wireframe-simulator/vpParser.cpp index 4bbd3b4cd6..5ae238dc33 100644 --- a/modules/robot/src/wireframe-simulator/vpParser.cpp +++ b/modules/robot/src/wireframe-simulator/vpParser.cpp @@ -47,6 +47,7 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE /* * La procedure "parser" fait l'analyse syntaxique du fichier source. * Entree/Sortie : @@ -93,5 +94,5 @@ void parser(Bound_scene *bsp) break; } } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpParser.h b/modules/robot/src/wireframe-simulator/vpParser.h index 7557f0257e..465ca78f3b 100644 --- a/modules/robot/src/wireframe-simulator/vpParser.h +++ b/modules/robot/src/wireframe-simulator/vpParser.h @@ -47,7 +47,8 @@ #include "vpBound.h" +BEGIN_VISP_NAMESPACE void parser(Bound_scene *bsp); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpProjection.cpp b/modules/robot/src/wireframe-simulator/vpProjection.cpp index fd08273c39..740d97ab3a 100644 --- a/modules/robot/src/wireframe-simulator/vpProjection.cpp +++ b/modules/robot/src/wireframe-simulator/vpProjection.cpp @@ -44,6 +44,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* * La procedure "View_to_Matrix" constuit la matrice homogene de projection * a partir des parametres de la prise de vue. @@ -231,5 +232,5 @@ void set_perspective(View_parameters *vp, Matrix wc) m[3][3] = 0.0; postmult_matrix(wc, m); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpProjection.h b/modules/robot/src/wireframe-simulator/vpProjection.h index e1602aa510..7f2d81cbf0 100644 --- a/modules/robot/src/wireframe-simulator/vpProjection.h +++ b/modules/robot/src/wireframe-simulator/vpProjection.h @@ -47,9 +47,10 @@ #include "vpArit.h" #include "vpView.h" +BEGIN_VISP_NAMESPACE void View_to_Matrix(View_parameters *vp, Matrix m); void set_parallel(View_parameters *vp, Matrix wc); void set_perspective(View_parameters *vp, Matrix wc); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpRfstack.cpp b/modules/robot/src/wireframe-simulator/vpRfstack.cpp index dbac55bd7b..2b0073ee54 100644 --- a/modules/robot/src/wireframe-simulator/vpRfstack.cpp +++ b/modules/robot/src/wireframe-simulator/vpRfstack.cpp @@ -48,9 +48,10 @@ #include #define STACKSIZE 32 -static int stack[STACKSIZE] = {vpDEFAULT_REMOVE}; /* pile */ +static int stack[STACKSIZE] = { vpDEFAULT_REMOVE }; /* pile */ static int *sp = stack; /* sommet */ +BEGIN_VISP_NAMESPACE /* * La procedure "fprintf_rfstack" affiche le sommet * de la pile des drapeaux d'elimination de faces. @@ -130,7 +131,8 @@ void pop_rfstack(void) static char proc_name[] = "pop_rfstack"; fprintf(stderr, "%s: stack underflow\n", proc_name); return; - } else + } + else sp--; } @@ -176,5 +178,5 @@ void add_rfstack(int i) { *sp |= i; } * de la pile des drapeaux d'elimination de faces. */ void sub_rfstack(int i) { *sp &= ~i; } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpRfstack.h b/modules/robot/src/wireframe-simulator/vpRfstack.h index 9c93afe124..5e4e576bce 100644 --- a/modules/robot/src/wireframe-simulator/vpRfstack.h +++ b/modules/robot/src/wireframe-simulator/vpRfstack.h @@ -45,6 +45,7 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE void fprintf_rfstack(FILE *fp); int *get_rfstack(void); void load_rfstack(int i); @@ -53,6 +54,6 @@ void push_rfstack(void); void swap_rfstack(void); void add_rfstack(int i); void sub_rfstack(int i); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpScene.cpp b/modules/robot/src/wireframe-simulator/vpScene.cpp index 6ea256b597..27d8619b73 100644 --- a/modules/robot/src/wireframe-simulator/vpScene.cpp +++ b/modules/robot/src/wireframe-simulator/vpScene.cpp @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /* Get the extension of the file and return it */ @@ -138,7 +139,8 @@ void set_scene_wrl(const char *str, Bound_scene *sc, float factor) sceneGraphVRML2 = tovrml2.getVRML2SceneGraph(); sceneGraphVRML2->ref(); sceneGraph->unref(); - } else { + } + else { sceneGraphVRML2 = SoDB::readAllVRML(&in); if (sceneGraphVRML2 == NULL) { /*return -1;*/ @@ -256,7 +258,8 @@ void ifsToBound(Bound *bptr, std::list &ifs_list) nbFace++; indSize.push_back(indice); indice = 0; - } else + } + else indice++; } } @@ -280,7 +283,8 @@ void ifsToBound(Bound *bptr, std::list &ifs_list) if (ifs->index[j] != -1) { bptr->face.ptr[indice].vertex.ptr[iter] = (Index)(ifs->index[j] + offset); iter++; - } else { + } + else { iter = 0; indice++; } @@ -297,7 +301,7 @@ void destroyIfs(std::list &ifs_list) ifs_list.clear(); } #else -void set_scene_wrl(const char * /*str*/, Bound_scene * /*sc*/, float /*factor*/) {} +void set_scene_wrl(const char * /*str*/, Bound_scene * /*sc*/, float /*factor*/) { } #endif /* @@ -310,5 +314,5 @@ void vp2jlc_matrix(const vpHomogeneousMatrix &vpM, Matrix &jlcM) jlcM[j][i] = (float)vpM[i][j]; } } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpScene.h b/modules/robot/src/wireframe-simulator/vpScene.h index e530eaa817..d059e68eca 100644 --- a/modules/robot/src/wireframe-simulator/vpScene.h +++ b/modules/robot/src/wireframe-simulator/vpScene.h @@ -64,16 +64,19 @@ #include #include -typedef struct indexFaceSet { - indexFaceSet() : nbPt(0), pt(), nbIndex(0), index(){}; +BEGIN_VISP_NAMESPACE +typedef struct indexFaceSet +{ + indexFaceSet() : nbPt(0), pt(), nbIndex(0), index() { }; int nbPt; std::vector pt; int nbIndex; std::vector index; } indexFaceSet; - +END_VISP_NAMESPACE #endif +BEGIN_VISP_NAMESPACE typedef enum { BND_MODEL, WRL_MODEL, UNKNOWN_MODEL } Model_3D; Model_3D getExtension(const char *file); @@ -86,6 +89,6 @@ void extractFaces(SoVRMLIndexedFaceSet *face_set, indexFaceSet *ifs); void ifsToBound(Bound *, std::list &); void destroyIfs(std::list &); #endif - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpSkipio.cpp b/modules/robot/src/wireframe-simulator/vpSkipio.cpp index a58d5ea2b1..069bcce599 100644 --- a/modules/robot/src/wireframe-simulator/vpSkipio.cpp +++ b/modules/robot/src/wireframe-simulator/vpSkipio.cpp @@ -47,6 +47,7 @@ #include "vpToken.h" #include +BEGIN_VISP_NAMESPACE /* * La procedure "skip_cmd" saute les structures d'une commande * jusqu'a reconnaitre le debut d'une nouvelle commande. @@ -97,5 +98,5 @@ void skip_keyword(int token, const char *err) } lexerr("start", err, NULL); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpSkipio.h b/modules/robot/src/wireframe-simulator/vpSkipio.h index 181e0b377f..d791045737 100644 --- a/modules/robot/src/wireframe-simulator/vpSkipio.h +++ b/modules/robot/src/wireframe-simulator/vpSkipio.h @@ -45,8 +45,9 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE void skip_cmd(void); void skip_keyword(int token, const char *err); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpTmstack.cpp b/modules/robot/src/wireframe-simulator/vpTmstack.cpp index f93f3beb8f..6a11ef1b80 100644 --- a/modules/robot/src/wireframe-simulator/vpTmstack.cpp +++ b/modules/robot/src/wireframe-simulator/vpTmstack.cpp @@ -50,6 +50,7 @@ #define STACKSIZE 32 +BEGIN_VISP_NAMESPACE static Matrix stack[STACKSIZE] /* = IDENTITY_MATRIX*/; /* pile */ static Matrix *sp = stack; /* sommet */ @@ -83,7 +84,8 @@ void pop_tmstack(void) static char proc_name[] = "pop_tmstack"; fprintf(stderr, "%s: stack underflow\n", proc_name); return; - } else + } + else sp--; } @@ -195,5 +197,5 @@ void prescale_tmstack(Vector *vp) { prescale_matrix(*sp, vp); } * vp Vecteur de translation. */ void pretranslate_tmstack(Vector *vp) { pretrans_matrix(*sp, vp); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpTmstack.h b/modules/robot/src/wireframe-simulator/vpTmstack.h index 686d001340..87e3ec6431 100644 --- a/modules/robot/src/wireframe-simulator/vpTmstack.h +++ b/modules/robot/src/wireframe-simulator/vpTmstack.h @@ -47,6 +47,7 @@ #include "vpArit.h" #include "vpMy.h" +BEGIN_VISP_NAMESPACE Matrix *get_tmstack(void); void load_tmstack(Matrix m); void pop_tmstack(void); @@ -61,6 +62,6 @@ void premult_tmstack(Matrix m); void prerotate_tmstack(Vector *vp); void prescale_tmstack(Vector *vp); void pretranslate_tmstack(Vector *vp); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpToken.cpp b/modules/robot/src/wireframe-simulator/vpToken.cpp index 0f23b6ef1a..9ef9466a53 100644 --- a/modules/robot/src/wireframe-simulator/vpToken.cpp +++ b/modules/robot/src/wireframe-simulator/vpToken.cpp @@ -44,6 +44,7 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE Keyword keyword_tbl[] = {/* tableau des mots cles termine par NULL*/ {"above", T_ABOVE}, {"back", T_BACK}, @@ -67,6 +68,6 @@ Keyword keyword_tbl[] = {/* tableau des mots cles termine par NULL*/ {"vrp", T_VRP}, {"vup", T_VUP}, {"window", T_WINDOW}, - {NULL, T_NULL}}; - + {NULL, T_NULL} }; +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpToken.h b/modules/robot/src/wireframe-simulator/vpToken.h index dd6a8cab8f..eeb6bd7cb9 100644 --- a/modules/robot/src/wireframe-simulator/vpToken.h +++ b/modules/robot/src/wireframe-simulator/vpToken.h @@ -45,7 +45,9 @@ #include -typedef struct { +BEGIN_VISP_NAMESPACE +typedef struct +{ const char *ident; /* identifateur */ Index token; /* code du jeton */ } Keyword; @@ -62,7 +64,7 @@ extern int mylength; extern int mylineno; extern char *mytext; extern Keyword keyword_tbl[]; - +END_VISP_NAMESPACE /* * Jetons superieurs a 270 (voir "../mylex/token.h"). */ diff --git a/modules/robot/src/wireframe-simulator/vpView.h b/modules/robot/src/wireframe-simulator/vpView.h index 9ce5c8b600..42df3c89ce 100644 --- a/modules/robot/src/wireframe-simulator/vpView.h +++ b/modules/robot/src/wireframe-simulator/vpView.h @@ -139,6 +139,7 @@ 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0 \ } +BEGIN_VISP_NAMESPACE /* * CAMERA PARAMETERS * _________________ @@ -150,8 +151,9 @@ * angle Angle d'ouverture en degres. * twist Angle de rotation sur l'axe de visee (eye,target) en degres. * speed Vitesse sur l'axe de visee (eye,target). - */ -typedef struct { +*/ +typedef struct +{ Point3f eye; /* position de l'observateur */ Point3f target; /* point vise */ float focal; /* focale de la camera */ @@ -160,17 +162,20 @@ typedef struct { float speed; /* vitesse sur l'axe de visee */ } Camera_parameters; -typedef struct { +typedef struct +{ float umin, umax; /* bords gauche et droit */ float vmin, vmax; /* bords inferieur et superieur */ } View_window; -typedef struct { +typedef struct +{ float front; /* plan avant ("hither") */ float back; /* plan arriere ("yon") */ } View_depth; -typedef struct { +typedef struct +{ Type type; /* type de la projection */ Point3f cop; /* centre de projection */ Point3f vrp; /* point de reference de visee */ @@ -179,6 +184,6 @@ typedef struct { View_window vwd; /* fenetre de projection */ View_depth depth; /* profondeurs de decoupages */ } View_parameters; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpViewio.cpp b/modules/robot/src/wireframe-simulator/vpViewio.cpp index 29bd02a610..27064e3bc3 100644 --- a/modules/robot/src/wireframe-simulator/vpViewio.cpp +++ b/modules/robot/src/wireframe-simulator/vpViewio.cpp @@ -53,6 +53,7 @@ #include "vpToken.h" #include "vpViewio.h" +BEGIN_VISP_NAMESPACE /* * La procedure "fscanf_Remove" lit en ascii les parametres d'elimination * des faces. @@ -163,5 +164,5 @@ void fscanf_View_parameters(View_parameters *vp) fscanf_float(&vp->depth.back); poperr(); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpViewio.h b/modules/robot/src/wireframe-simulator/vpViewio.h index 09eaa9b5d8..2233f8e488 100644 --- a/modules/robot/src/wireframe-simulator/vpViewio.h +++ b/modules/robot/src/wireframe-simulator/vpViewio.h @@ -50,8 +50,9 @@ #include "vpMy.h" #include "vpView.h" +BEGIN_VISP_NAMESPACE void fscanf_Remove(Byte *bp); void fscanf_View_parameters(View_parameters *vp); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpVwstack.cpp b/modules/robot/src/wireframe-simulator/vpVwstack.cpp index 2bf5ec895c..0dbe98cb07 100644 --- a/modules/robot/src/wireframe-simulator/vpVwstack.cpp +++ b/modules/robot/src/wireframe-simulator/vpVwstack.cpp @@ -54,7 +54,8 @@ #define STACKSIZE 4 -static View_parameters stack[STACKSIZE] = {vpDEFAULT_VIEW}; +BEGIN_VISP_NAMESPACE +static View_parameters stack[STACKSIZE] = { vpDEFAULT_VIEW }; static View_parameters *sp = stack; /* @@ -147,7 +148,8 @@ void pop_vwstack(void) static char proc_name[] = "pop_vwstack"; fprintf(stderr, "%s: stack underflow\n", proc_name); return; - } else + } + else sp--; } @@ -197,15 +199,18 @@ void add_vwstack(const char *path, ...) if (strcmp(argv, "cop") == 0) { /* initialise le centre de projection */ SET_COORD3(sp->cop, (float)va_arg(ap, double), (float)va_arg(ap, double), (float)va_arg(ap, double)); - } else if (strcmp(argv, "depth") == 0) { - /* initialise les distances des plans de decoupage */ + } + else if (strcmp(argv, "depth") == 0) { + /* initialise les distances des plans de decoupage */ sp->depth.front = (float)va_arg(ap, double); sp->depth.back = (float)va_arg(ap, double); - } else if (strcmp(argv, "type") == 0) { - /* initialise le type de projection */ + } + else if (strcmp(argv, "type") == 0) { + /* initialise le type de projection */ sp->type = (Type)va_arg(ap, int); - } else if (strcmp(argv, "vpn") == 0) { - /* initialise le vecteur normal au plan */ + } + else if (strcmp(argv, "vpn") == 0) { + /* initialise le vecteur normal au plan */ float x = (float)va_arg(ap, double); float y = (float)va_arg(ap, double); float z = (float)va_arg(ap, double); @@ -216,14 +221,17 @@ void add_vwstack(const char *path, ...) std::fabs(z) <= std::numeric_limits::epsilon()) { static char proc_name[] = "add_vwstack"; fprintf(stderr, "%s: bad vpn\n", proc_name); - } else { + } + else { SET_COORD3(sp->vpn, x, y, z); } - } else if (strcmp(argv, "vrp") == 0) { - /* initialise le vecteur de reference */ + } + else if (strcmp(argv, "vrp") == 0) { + /* initialise le vecteur de reference */ SET_COORD3(sp->vrp, (float)va_arg(ap, double), (float)va_arg(ap, double), (float)va_arg(ap, double)); - } else if (strcmp(argv, "vup") == 0) { - /* initialise le vecteur haut du plan */ + } + else if (strcmp(argv, "vup") == 0) { + /* initialise le vecteur haut du plan */ float x = (float)va_arg(ap, double); float y = (float)va_arg(ap, double); float z = (float)va_arg(ap, double); @@ -234,20 +242,23 @@ void add_vwstack(const char *path, ...) std::fabs(z) <= std::numeric_limits::epsilon()) { static char proc_name[] = "add_vwstack"; fprintf(stderr, "%s: bad vup\n", proc_name); - } else { + } + else { SET_COORD3(sp->vup, x, y, z); } - } else if (strcmp(argv, "window") == 0) { - /* initialise la fenetre de projection */ + } + else if (strcmp(argv, "window") == 0) { + /* initialise la fenetre de projection */ sp->vwd.umin = (float)va_arg(ap, double); sp->vwd.umax = (float)va_arg(ap, double); sp->vwd.vmin = (float)va_arg(ap, double); sp->vwd.vmax = (float)va_arg(ap, double); - } else { + } + else { static char proc_name[] = "add_vwstack"; fprintf(stderr, "%s: bad argument\n", proc_name); } va_end(ap); } - +END_VISP_NAMESPACE #endif diff --git a/modules/robot/src/wireframe-simulator/vpVwstack.h b/modules/robot/src/wireframe-simulator/vpVwstack.h index 41c54f3cef..0d572109ab 100644 --- a/modules/robot/src/wireframe-simulator/vpVwstack.h +++ b/modules/robot/src/wireframe-simulator/vpVwstack.h @@ -47,6 +47,7 @@ #include "vpView.h" +BEGIN_VISP_NAMESPACE void fprintf_vwstack(FILE *fp, char *argv); View_parameters *get_vwstack(void); void load_vwstack(View_parameters *vp); @@ -54,6 +55,6 @@ void pop_vwstack(void); void push_vwstack(void); void swap_vwstack(void); void add_vwstack(const char *path, ...); - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/robot/src/wireframe-simulator/vpWireFrameSimulator.cpp b/modules/robot/src/wireframe-simulator/vpWireFrameSimulator.cpp index ebb3d2bef6..dacb00a618 100644 --- a/modules/robot/src/wireframe-simulator/vpWireFrameSimulator.cpp +++ b/modules/robot/src/wireframe-simulator/vpWireFrameSimulator.cpp @@ -66,6 +66,7 @@ #include #include +BEGIN_VISP_NAMESPACE extern Point2i *point2i; extern Point2i *listpoint2i; @@ -1608,3 +1609,4 @@ vpImagePoint vpWireFrameSimulator::projectCameraTrajectory(const vpImage] [--hd-resolution] [--verbose] [-v]" - << " [--help] [-h]\n" - << std::endl - << "Description:\n" - << " --ip \n" - << " IP address of the drone to which you want to connect (default : 192.168.42.1).\n\n" - << " --hd-resolution\n" - << " Enables HD 720p video instead of default 480p.\n\n" - << " --verbose, -v\n" - << " Enables verbose (drone information messages are then displayed).\n\n" - << " --help, -h\n" - << " Print help message.\n\n" - << std::endl; + << " " << argv[0] << " [--ip ] [--hd-resolution] [--verbose] [-v]" + << " [--help] [-h]\n" + << std::endl + << "Description:\n" + << " --ip \n" + << " IP address of the drone to which you want to connect (default : 192.168.42.1).\n\n" + << " --hd-resolution\n" + << " Enables HD 720p video instead of default 480p.\n\n" + << " --verbose, -v\n" + << " Enables verbose (drone information messages are then displayed).\n\n" + << " --help, -h\n" + << " Print help message.\n\n" + << std::endl; return EXIT_SUCCESS; - } else { + } + else { std::cout << "Error : unknown parameter " << argv[i] << std::endl - << "See " << argv[0] << " --help" << std::endl; + << "See " << argv[0] << " --help" << std::endl; return EXIT_FAILURE; } } @@ -132,12 +139,14 @@ int main(int argc, char **argv) drone.land(); - } else { + } + else { std::cout << "Error : failed to setup drone control" << std::endl; } std::cout << "-- End of test --" << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Caught an exception: " << e << std::endl; } #else diff --git a/modules/robot/test/qbdevice/testQbSoftHand.cpp b/modules/robot/test/qbdevice/testQbSoftHand.cpp index d0e5e7408e..0eaacccd47 100644 --- a/modules/robot/test/qbdevice/testQbSoftHand.cpp +++ b/modules/robot/test/qbdevice/testQbSoftHand.cpp @@ -46,6 +46,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if defined(VISP_HAVE_QBDEVICE) && defined(VISP_HAVE_THREADS) std::cout << "Test qbSoftHand device" << std::endl; try { diff --git a/modules/robot/test/servo-afma4/testAfma4.cpp b/modules/robot/test/servo-afma4/testAfma4.cpp index 0b0fa6182c..298b3b78a0 100644 --- a/modules/robot/test/servo-afma4/testAfma4.cpp +++ b/modules/robot/test/servo-afma4/testAfma4.cpp @@ -49,6 +49,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::cout << "a test for vpAfma4 class..." << std::endl; @@ -58,7 +61,8 @@ int main() std::cout << afma4 << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-afma4/testRobotAfma4.cpp b/modules/robot/test/servo-afma4/testRobotAfma4.cpp index 97ca657036..8e65e317ce 100644 --- a/modules/robot/test/servo-afma4/testRobotAfma4.cpp +++ b/modules/robot/test/servo-afma4/testRobotAfma4.cpp @@ -50,6 +50,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::cout << "A test for vpRobotAfma4 class..." << std::endl; @@ -58,7 +61,8 @@ int main() std::cout << afma4 << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-afma6/testAfma6.cpp b/modules/robot/test/servo-afma6/testAfma6.cpp index ef4810b823..257d5146d6 100644 --- a/modules/robot/test/servo-afma6/testAfma6.cpp +++ b/modules/robot/test/servo-afma6/testAfma6.cpp @@ -49,6 +49,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::cout << "a test for vpAfma6 class..." << std::endl; @@ -88,7 +91,8 @@ int main() std::cout << cam << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-afma6/testRobotAfma6.cpp b/modules/robot/test/servo-afma6/testRobotAfma6.cpp index 7e80d7cbc5..1630015582 100644 --- a/modules/robot/test/servo-afma6/testRobotAfma6.cpp +++ b/modules/robot/test/servo-afma6/testRobotAfma6.cpp @@ -50,6 +50,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::cout << "a test for vpRobotAfma6 class..." << std::endl; @@ -88,7 +91,8 @@ int main() afma6.getCameraParameters(cam, 640, 480); std::cout << cam << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-afma6/testRobotAfma6Pose.cpp b/modules/robot/test/servo-afma6/testRobotAfma6Pose.cpp index b5815aa50f..550171b4bd 100644 --- a/modules/robot/test/servo-afma6/testRobotAfma6Pose.cpp +++ b/modules/robot/test/servo-afma6/testRobotAfma6Pose.cpp @@ -60,6 +60,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { // Create an image B&W container vpImage I; @@ -169,10 +172,10 @@ int main() cMo.extract(R); r.build(R); std::cout << " rotation: " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) << " deg" - << std::endl - << std::endl; + << std::endl + << std::endl; - // Get the robot position in the reference frame +// Get the robot position in the reference frame vpHomogeneousMatrix rMc; vpColVector p; // position x,y,z,rx,ry,rz robot.getPosition(vpRobotAfma6::REFERENCE_FRAME, p); @@ -190,8 +193,8 @@ int main() rMc.extract(R); r.build(R); std::cout << " rotation: " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) << " deg" - << std::endl - << std::endl; + << std::endl + << std::endl; robot.getPosition(vpRobotAfma6::ARTICULAR_FRAME, p); std::cout << "Robot pose in articular: " << p << std::endl; @@ -201,8 +204,8 @@ int main() rMc.extract(R); r.build(R); std::cout << " rotation: " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) << " deg" - << std::endl - << std::endl; + << std::endl + << std::endl; vpHomogeneousMatrix rMo; rMo = rMc * cMo; @@ -210,10 +213,11 @@ int main() rMo.extract(R); r.build(R); std::cout << " rotation: " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) << " deg" - << std::endl - << std::endl; + << std::endl + << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-flir-ptu/testRobotFlirPtu.cpp b/modules/robot/test/servo-flir-ptu/testRobotFlirPtu.cpp index 4413a2edc5..a7f55c3f4f 100644 --- a/modules/robot/test/servo-flir-ptu/testRobotFlirPtu.cpp +++ b/modules/robot/test/servo-flir-ptu/testRobotFlirPtu.cpp @@ -49,6 +49,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string opt_portname; int opt_baudrate = 9600; bool opt_network = false; diff --git a/modules/robot/test/servo-franka/testFrankaCartForceTorque-2.cpp b/modules/robot/test/servo-franka/testFrankaCartForceTorque-2.cpp index 2a380f1dae..5003faf60a 100644 --- a/modules/robot/test/servo-franka/testFrankaCartForceTorque-2.cpp +++ b/modules/robot/test/servo-franka/testFrankaCartForceTorque-2.cpp @@ -49,17 +49,22 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; std::string log_folder; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { log_folder = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--log_folder ] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -70,10 +75,10 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " << std::endl - << "- Please make sure to have the user stop button at hand!" << std::endl - << "- Please make also sure the end-effector is in contact with a flat surface such as a foam board!" - << std::endl - << "Press Enter to continue..." << std::endl; + << "- Please make sure to have the user stop button at hand!" << std::endl + << "- Please make also sure the end-effector is in contact with a flat surface such as a foam board!" + << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -97,7 +102,7 @@ int main(int argc, char **argv) static bool change_ft = true; if (change_ft) { std::cout << "Apply cartesian force/torque in a loop for " << delta_t / 2. << " sec : " << ft_d.t() - << std::endl; + << std::endl; } change_ft = false; } @@ -106,16 +111,19 @@ int main(int argc, char **argv) robot.setRobotState(vpRobot::STATE_STOP); vpTime::wait(100); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaCartForceTorque.cpp b/modules/robot/test/servo-franka/testFrankaCartForceTorque.cpp index 94d30fd499..f20f4a4c4d 100644 --- a/modules/robot/test/servo-franka/testFrankaCartForceTorque.cpp +++ b/modules/robot/test/servo-franka/testFrankaCartForceTorque.cpp @@ -49,17 +49,22 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; std::string log_folder; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { log_folder = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--log_folder ] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -70,10 +75,10 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " << std::endl - << "- Please make sure to have the user stop button at hand!" << std::endl - << "- Please make also sure the end-effector is in contact with a flat surface such as a foam board!" - << std::endl - << "Press Enter to continue..." << std::endl; + << "- Please make sure to have the user stop button at hand!" << std::endl + << "- Please make also sure the end-effector is in contact with a flat surface such as a foam board!" + << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -94,7 +99,7 @@ int main(int argc, char **argv) static bool change_ft = true; if (change_ft) { std::cout << "Apply cartesian force/torque in a loop for " << delta_t / 2. << " sec : " << ft_d.t() - << std::endl; + << std::endl; } change_ft = false; } @@ -103,16 +108,19 @@ int main(int argc, char **argv) robot.setRobotState(vpRobot::STATE_STOP); vpTime::wait(100); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaCartVelocity-2.cpp b/modules/robot/test/servo-franka/testFrankaCartVelocity-2.cpp index 1a5f61f9ac..532cf35159 100644 --- a/modules/robot/test/servo-franka/testFrankaCartVelocity-2.cpp +++ b/modules/robot/test/servo-franka/testFrankaCartVelocity-2.cpp @@ -49,17 +49,22 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; std::string log_folder; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { log_folder = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--log_folder ] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -70,8 +75,8 @@ int main(int argc, char **argv) robot.setLogFolder(log_folder); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -140,16 +145,19 @@ int main(int argc, char **argv) std::cout << "Ask to stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaCartVelocity-3.cpp b/modules/robot/test/servo-franka/testFrankaCartVelocity-3.cpp index c67ea1f358..2c0de38e77 100644 --- a/modules/robot/test/servo-franka/testFrankaCartVelocity-3.cpp +++ b/modules/robot/test/servo-franka/testFrankaCartVelocity-3.cpp @@ -49,17 +49,22 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; std::string log_folder; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { log_folder = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--log_folder ] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -70,8 +75,8 @@ int main(int argc, char **argv) robot.setLogFolder(log_folder); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -124,16 +129,19 @@ int main(int argc, char **argv) std::cout << "Ask to stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaCartVelocity.cpp b/modules/robot/test/servo-franka/testFrankaCartVelocity.cpp index 4eaa455b06..f24d927899 100644 --- a/modules/robot/test/servo-franka/testFrankaCartVelocity.cpp +++ b/modules/robot/test/servo-franka/testFrankaCartVelocity.cpp @@ -49,17 +49,22 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; std::string log_folder; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { log_folder = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--log_folder ] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -70,8 +75,8 @@ int main(int argc, char **argv) robot.setLogFolder(log_folder); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -121,16 +126,19 @@ int main(int argc, char **argv) std::cout << "Ask to stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaGetPose.cpp b/modules/robot/test/servo-franka/testFrankaGetPose.cpp index 6c9e464d7e..5a356bf0f2 100644 --- a/modules/robot/test/servo-franka/testFrankaGetPose.cpp +++ b/modules/robot/test/servo-franka/testFrankaGetPose.cpp @@ -49,14 +49,18 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -78,16 +82,19 @@ int main(int argc, char **argv) robot.getPosition(vpRobot::END_EFFECTOR_FRAME, fPe); std::cout << "fMe pose vector: " << fPe.t() << std::endl; std::cout << "fMe pose matrix: \n" << vpHomogeneousMatrix(fPe) << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -127,16 +134,19 @@ int main(int argc, char **argv) } } std::cout << "eeMk: \n" << eeMk << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " - << std::endl; + << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " + << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -157,16 +167,19 @@ int main(int argc, char **argv) vpColVector coriolis; robot.getCoriolis(coriolis); std::cout << "Coriolis vector: " << coriolis.t() << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " - << std::endl; + << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " + << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } @@ -193,16 +206,19 @@ int main(int argc, char **argv) robot.get_eJe(q, eJe); std::cout << "Jacobian eJe:\n" << eJe << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " - << std::endl; + << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " + << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaJointPosition.cpp b/modules/robot/test/servo-franka/testFrankaJointPosition.cpp index 3ae5f10392..6d49f7741c 100644 --- a/modules/robot/test/servo-franka/testFrankaJointPosition.cpp +++ b/modules/robot/test/servo-franka/testFrankaJointPosition.cpp @@ -49,14 +49,18 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -66,8 +70,8 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -80,16 +84,19 @@ int main(int argc, char **argv) robot.setRobotState(vpRobot::STATE_POSITION_CONTROL); std::cout << "Move to joint position: " << q.t() << std::endl; robot.setPosition(vpRobot::JOINT_STATE, q); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaJointTorque.cpp b/modules/robot/test/servo-franka/testFrankaJointTorque.cpp index 0a551f6838..6a373e73f7 100644 --- a/modules/robot/test/servo-franka/testFrankaJointTorque.cpp +++ b/modules/robot/test/servo-franka/testFrankaJointTorque.cpp @@ -49,17 +49,22 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; std::string log_folder; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { log_folder = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--log_folder ] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -70,10 +75,10 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " << std::endl - << "- Please make sure to have the user stop button at hand!" << std::endl - << "- Please make also sure the end-effector is in contact with a flat surface such as a foam board!" - << std::endl - << "Press Enter to continue..." << std::endl; + << "- Please make sure to have the user stop button at hand!" << std::endl + << "- Please make also sure the end-effector is in contact with a flat surface such as a foam board!" + << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -95,16 +100,19 @@ int main(int argc, char **argv) robot.setRobotState(vpRobot::STATE_STOP); vpTime::wait(100); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaJointVelocity-2.cpp b/modules/robot/test/servo-franka/testFrankaJointVelocity-2.cpp index f6d7eaa401..a10e021803 100644 --- a/modules/robot/test/servo-franka/testFrankaJointVelocity-2.cpp +++ b/modules/robot/test/servo-franka/testFrankaJointVelocity-2.cpp @@ -49,14 +49,18 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -66,8 +70,8 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -111,16 +115,19 @@ int main(int argc, char **argv) std::cout << "Ask to stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaJointVelocity-3.cpp b/modules/robot/test/servo-franka/testFrankaJointVelocity-3.cpp index bc9bd87071..39698a41b2 100644 --- a/modules/robot/test/servo-franka/testFrankaJointVelocity-3.cpp +++ b/modules/robot/test/servo-franka/testFrankaJointVelocity-3.cpp @@ -49,14 +49,18 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -66,8 +70,8 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -127,16 +131,19 @@ int main(int argc, char **argv) std::cout << "Ask to stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaJointVelocity.cpp b/modules/robot/test/servo-franka/testFrankaJointVelocity.cpp index 9e81c7807f..8f543f6704 100644 --- a/modules/robot/test/servo-franka/testFrankaJointVelocity.cpp +++ b/modules/robot/test/servo-franka/testFrankaJointVelocity.cpp @@ -49,17 +49,22 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; std::string log_folder; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--log_folder" && i + 1 < argc) { log_folder = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--log_folder ] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -70,8 +75,8 @@ int main(int argc, char **argv) robot.setLogFolder(log_folder); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -114,16 +119,19 @@ int main(int argc, char **argv) std::cout << "Ask to stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-franka/testFrankaJointVelocityLimits.cpp b/modules/robot/test/servo-franka/testFrankaJointVelocityLimits.cpp index ba61bd7796..e895283946 100644 --- a/modules/robot/test/servo-franka/testFrankaJointVelocityLimits.cpp +++ b/modules/robot/test/servo-franka/testFrankaJointVelocityLimits.cpp @@ -49,14 +49,18 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.1.1"; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--ip" && i + 1 < argc) { robot_ip = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << argv[0] << " [--ip 192.168.1.1] [--help] [-h]" - << "\n"; + << "\n"; return EXIT_SUCCESS; } } @@ -66,8 +70,8 @@ int main(int argc, char **argv) robot.connect(robot_ip); std::cout << "WARNING: This example will move the robot! " - << "Please make sure to have the user stop button at hand!" << std::endl - << "Press Enter to continue..." << std::endl; + << "Please make sure to have the user stop button at hand!" << std::endl + << "Press Enter to continue..." << std::endl; std::cin.ignore(); /* @@ -92,7 +96,7 @@ int main(int argc, char **argv) double delta_t = 10.0; // Time in second std::cout << "Modify the maximum allowed joint velocity to: " << vel << " rad/s or " << vpMath::deg(vel) << " deg/s" - << std::endl; + << std::endl; robot.setMaxRotationVelocity(vel); std::cout << "Apply joint vel " << dq_d.t() << " for " << delta_t << " sec " << std::endl; robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL); @@ -122,16 +126,19 @@ int main(int argc, char **argv) std::cout << "Stop the robot " << std::endl; robot.setRobotState(vpRobot::STATE_STOP); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "ViSP exception: " << e.what() << std::endl; return EXIT_FAILURE; - } catch (const franka::NetworkException &e) { + } + catch (const franka::NetworkException &e) { std::cout << "Franka network exception: " << e.what() << std::endl; std::cout << "Check if you are connected to the Franka robot" - << " or if you specified the right IP using --ip command" - << " line option set by default to 192.168.1.1. " << std::endl; + << " or if you specified the right IP using --ip command" + << " line option set by default to 192.168.1.1. " << std::endl; return EXIT_FAILURE; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { std::cout << "Franka exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-pixhawk/testPixhawkDroneKeyboard.cpp b/modules/robot/test/servo-pixhawk/testPixhawkDroneKeyboard.cpp index 3881565ce2..bbf582366e 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkDroneKeyboard.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkDroneKeyboard.cpp @@ -54,6 +54,9 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif bool handleKeyboardInput(vpRobotMavsdk &drone, int key, bool &flying, double &lastCommandTime) { bool running = true; diff --git a/modules/robot/test/servo-pixhawk/testPixhawkDronePositionAbsoluteControl.cpp b/modules/robot/test/servo-pixhawk/testPixhawkDronePositionAbsoluteControl.cpp index 4b652acf43..a07cab8a38 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkDronePositionAbsoluteControl.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkDronePositionAbsoluteControl.cpp @@ -64,6 +64,9 @@ void usage(const std::string &bin_name) int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif if (argc != 2) { usage(argv[0]); return EXIT_SUCCESS; diff --git a/modules/robot/test/servo-pixhawk/testPixhawkDronePositionRelativeControl.cpp b/modules/robot/test/servo-pixhawk/testPixhawkDronePositionRelativeControl.cpp index 519e82574c..160a9842bc 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkDronePositionRelativeControl.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkDronePositionRelativeControl.cpp @@ -64,6 +64,9 @@ void usage(const std::string &bin_name) int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif if (argc != 2) { usage(argv[0]); return EXIT_SUCCESS; diff --git a/modules/robot/test/servo-pixhawk/testPixhawkDroneTakeoff.cpp b/modules/robot/test/servo-pixhawk/testPixhawkDroneTakeoff.cpp index c97e39649a..d3b6fc4bc2 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkDroneTakeoff.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkDroneTakeoff.cpp @@ -64,6 +64,9 @@ void usage(const std::string &bin_name) int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif if (argc != 2) { usage(argv[0]); return EXIT_SUCCESS; diff --git a/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp b/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp index fca58e6ac2..a5424fe836 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp @@ -69,6 +69,9 @@ void usage(const std::string &bin_name) int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif if (argc != 2) { usage(argv[0]); return EXIT_SUCCESS; diff --git a/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp b/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp index 26dcd0cea0..bb83c1fd9f 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp @@ -69,6 +69,9 @@ void usage(const std::string &bin_name) int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif if (argc != 2) { usage(argv[0]); return EXIT_SUCCESS; diff --git a/modules/robot/test/servo-pololu/testPololuPosition.cpp b/modules/robot/test/servo-pololu/testPololuPosition.cpp index deaf385e19..46d526aa69 100644 --- a/modules/robot/test/servo-pololu/testPololuPosition.cpp +++ b/modules/robot/test/servo-pololu/testPololuPosition.cpp @@ -49,6 +49,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char **argv, int error, const std::string &device, int baudrate, int channel, unsigned short pwm_min, unsigned short pwm_max, float angle_min, float angle_max) { diff --git a/modules/robot/test/servo-pololu/testPololuVelocity.cpp b/modules/robot/test/servo-pololu/testPololuVelocity.cpp index 97387918e0..01f23a7427 100644 --- a/modules/robot/test/servo-pololu/testPololuVelocity.cpp +++ b/modules/robot/test/servo-pololu/testPololuVelocity.cpp @@ -48,6 +48,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char **argv, int error, const std::string &device, int baudrate, int channel, unsigned short pwm_min, unsigned short pwm_max, float angle_min, float angle_max) { diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsCartPosition.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsCartPosition.cpp index 032adcbcd3..95e87ae733 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsCartPosition.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsCartPosition.cpp @@ -49,6 +49,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.0.100"; for (int i = 1; i < argc; i++) { diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsCartVelocity.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsCartVelocity.cpp index f1ca50e1b9..c28b4e0ae4 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsCartVelocity.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsCartVelocity.cpp @@ -49,6 +49,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.0.100"; for (int i = 1; i < argc; i++) { diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsGetData.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsGetData.cpp index b4efff7e50..aa4ecff68d 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsGetData.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsGetData.cpp @@ -49,6 +49,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.0.100"; for (int i = 1; i < argc; i++) { diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsJointPosition.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsJointPosition.cpp index 62512b5990..82b4225940 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsJointPosition.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsJointPosition.cpp @@ -49,6 +49,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.0.100"; for (int i = 1; i < argc; i++) { diff --git a/modules/robot/test/servo-universal-robots/testUniversalRobotsJointVelocity.cpp b/modules/robot/test/servo-universal-robots/testUniversalRobotsJointVelocity.cpp index 059ecf1a1a..e5d5ac688b 100644 --- a/modules/robot/test/servo-universal-robots/testUniversalRobotsJointVelocity.cpp +++ b/modules/robot/test/servo-universal-robots/testUniversalRobotsJointVelocity.cpp @@ -49,6 +49,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string robot_ip = "192.168.0.100"; for (int i = 1; i < argc; i++) { diff --git a/modules/robot/test/servo-viper/testRobotViper650-frames.cpp b/modules/robot/test/servo-viper/testRobotViper650-frames.cpp index cfb09e8490..e5f17dff01 100644 --- a/modules/robot/test/servo-viper/testRobotViper650-frames.cpp +++ b/modules/robot/test/servo-viper/testRobotViper650-frames.cpp @@ -44,6 +44,9 @@ #ifdef VISP_HAVE_VIPER650 +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif bool pose_equal(const vpHomogeneousMatrix &M1, const vpHomogeneousMatrix &M2, double epsilon = 1e-6) { vpTranslationVector t1, t2; @@ -364,7 +367,8 @@ int main() std::cout << "The end" << std::endl; std::cout << "Test succeed" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Test failed with exception: " << e.getMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-viper/testRobotViper850-frames.cpp b/modules/robot/test/servo-viper/testRobotViper850-frames.cpp index c39257f247..36095a38d1 100644 --- a/modules/robot/test/servo-viper/testRobotViper850-frames.cpp +++ b/modules/robot/test/servo-viper/testRobotViper850-frames.cpp @@ -43,7 +43,9 @@ #include #ifdef VISP_HAVE_VIPER850 - +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif bool pose_equal(const vpHomogeneousMatrix &M1, const vpHomogeneousMatrix &M2, double epsilon = 1e-6) { vpTranslationVector t1, t2; @@ -364,7 +366,8 @@ int main() std::cout << "The end" << std::endl; std::cout << "Test succeed" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Test failed with exception: " << e.getMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-viper/testRobotViper850.cpp b/modules/robot/test/servo-viper/testRobotViper850.cpp index 1132a41485..81905b60b5 100644 --- a/modules/robot/test/servo-viper/testRobotViper850.cpp +++ b/modules/robot/test/servo-viper/testRobotViper850.cpp @@ -49,6 +49,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::cout << "a test for vpRobotViper850 class..." << std::endl; @@ -62,8 +65,8 @@ int main() std::cout << cam << std::endl; std::cout << "-- Settings associated to the Marlin F033C camera without " - "distortion ---" - << std::endl; + "distortion ---" + << std::endl; viper850.init(vpViper850::TOOL_MARLIN_F033C_CAMERA); std::cout << viper850 << std::endl; @@ -71,8 +74,8 @@ int main() std::cout << cam << std::endl; std::cout << "-- Settings associated to the Marlin F033C camera with " - "distortion ------" - << std::endl; + "distortion ------" + << std::endl; viper850.init(vpViper850::TOOL_MARLIN_F033C_CAMERA, vpCameraParameters::perspectiveProjWithDistortion); std::cout << viper850 << std::endl; viper850.getCameraParameters(cam, 640, 480); @@ -95,11 +98,12 @@ int main() rzyz.build(R); std::cout << "fMe:" << std::endl - << "\tt: " << t.t() << std::endl - << "\trzyz (deg): " << vpMath::deg(rzyz[0]) << " " << vpMath::deg(rzyz[1]) << " " << vpMath::deg(rzyz[2]) - << std::endl; + << "\tt: " << t.t() << std::endl + << "\trzyz (deg): " << vpMath::deg(rzyz[0]) << " " << vpMath::deg(rzyz[1]) << " " << vpMath::deg(rzyz[2]) + << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-viper/testRobotViper850Pose.cpp b/modules/robot/test/servo-viper/testRobotViper850Pose.cpp index f16d8993c4..d86eee79de 100644 --- a/modules/robot/test/servo-viper/testRobotViper850Pose.cpp +++ b/modules/robot/test/servo-viper/testRobotViper850Pose.cpp @@ -61,6 +61,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { // Create an image B&W container vpImage I; @@ -171,10 +174,10 @@ int main() cMo.extract(R); r.build(R); std::cout << " rotation: " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) << " deg" - << std::endl - << std::endl; + << std::endl + << std::endl; - // Get the robot position in the reference frame +// Get the robot position in the reference frame vpHomogeneousMatrix rMc; vpColVector p; // position x,y,z,rx,ry,rz robot.getPosition(vpRobotViper850::REFERENCE_FRAME, p); @@ -192,8 +195,8 @@ int main() rMc.extract(R); r.build(R); std::cout << " rotation: " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) << " deg" - << std::endl - << std::endl; + << std::endl + << std::endl; robot.getPosition(vpRobotViper850::ARTICULAR_FRAME, p); std::cout << "Robot pose in articular: " << p << std::endl; @@ -203,8 +206,8 @@ int main() rMc.extract(R); r.build(R); std::cout << " rotation: " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) << " deg" - << std::endl - << std::endl; + << std::endl + << std::endl; vpHomogeneousMatrix rMo; rMo = rMc * cMo; @@ -212,10 +215,11 @@ int main() rMo.extract(R); r.build(R); std::cout << " rotation: " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) << " deg" - << std::endl - << std::endl; + << std::endl + << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-viper/testViper650.cpp b/modules/robot/test/servo-viper/testViper650.cpp index f69fb60cd3..9d378ade85 100644 --- a/modules/robot/test/servo-viper/testViper650.cpp +++ b/modules/robot/test/servo-viper/testViper650.cpp @@ -48,6 +48,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::cout << "a test for vpViper650 class..." << std::endl; @@ -61,8 +64,8 @@ int main() std::cout << cam << std::endl; std::cout << "-- Settings associated to the Marlin F033C camera without " - "distortion ---" - << std::endl; + "distortion ---" + << std::endl; viper650.init(vpViper650::TOOL_MARLIN_F033C_CAMERA); std::cout << viper650 << std::endl; @@ -70,8 +73,8 @@ int main() std::cout << cam << std::endl; std::cout << "-- Settings associated to the Marlin F033C camera with " - "distortion ------" - << std::endl; + "distortion ------" + << std::endl; viper650.init(vpViper650::TOOL_MARLIN_F033C_CAMERA, vpCameraParameters::perspectiveProjWithDistortion); std::cout << viper650 << std::endl; viper650.getCameraParameters(cam, 640, 480); @@ -104,13 +107,14 @@ int main() r.build(R); std::cout << "fMe:" << std::endl - << "\tt: " << t.t() << std::endl - << "\trzyz (rad): " << r.t() << std::endl - << "\trzyz (deg): " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) - << std::endl; + << "\tt: " << t.t() << std::endl + << "\trzyz (rad): " << r.t() << std::endl + << "\trzyz (deg): " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) + << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/servo-viper/testViper850.cpp b/modules/robot/test/servo-viper/testViper850.cpp index 4cc9f7ff6b..d358ff741a 100644 --- a/modules/robot/test/servo-viper/testViper850.cpp +++ b/modules/robot/test/servo-viper/testViper850.cpp @@ -48,6 +48,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::cout << "a test for vpViper850 class..." << std::endl; @@ -61,8 +64,8 @@ int main() std::cout << cam << std::endl; std::cout << "-- Settings associated to the Marlin F033C camera without " - "distortion ---" - << std::endl; + "distortion ---" + << std::endl; viper850.init(vpViper850::TOOL_MARLIN_F033C_CAMERA); std::cout << viper850 << std::endl; @@ -70,8 +73,8 @@ int main() std::cout << cam << std::endl; std::cout << "-- Settings associated to the Marlin F033C camera with " - "distortion ------" - << std::endl; + "distortion ------" + << std::endl; viper850.init(vpViper850::TOOL_MARLIN_F033C_CAMERA, vpCameraParameters::perspectiveProjWithDistortion); std::cout << viper850 << std::endl; viper850.getCameraParameters(cam, 640, 480); @@ -104,13 +107,14 @@ int main() r.build(R); std::cout << "fMe:" << std::endl - << "\tt: " << t.t() << std::endl - << "\trzyz (rad): " << r.t() << std::endl - << "\trzyz (deg): " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) - << std::endl; + << "\tt: " << t.t() << std::endl + << "\trzyz (rad): " << r.t() << std::endl + << "\trzyz (deg): " << vpMath::deg(r[0]) << " " << vpMath::deg(r[1]) << " " << vpMath::deg(r[2]) + << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/virtuose/testVirtuose.cpp b/modules/robot/test/virtuose/testVirtuose.cpp index 0aeb73fe53..5e3e9cc635 100644 --- a/modules/robot/test/virtuose/testVirtuose.cpp +++ b/modules/robot/test/virtuose/testVirtuose.cpp @@ -43,6 +43,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if defined(VISP_HAVE_VIRTUOSE) std::string opt_ip = "localhost"; int opt_port = 5000; @@ -90,7 +93,7 @@ int main(int argc, char **argv) catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; - } +} #else (void)argc; (void)argv; diff --git a/modules/robot/test/virtuose/testVirtuoseAfma6.cpp b/modules/robot/test/virtuose/testVirtuoseAfma6.cpp index 1fed2313f5..da2fabb95d 100644 --- a/modules/robot/test/virtuose/testVirtuoseAfma6.cpp +++ b/modules/robot/test/virtuose/testVirtuoseAfma6.cpp @@ -50,6 +50,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if defined(VISP_HAVE_VIRTUOSE) && defined(VISP_HAVE_AFMA6) vpRobotAfma6 robot; try { @@ -111,11 +114,13 @@ int main() force_feedback_robot[i] = (max[i] - robot_cart_position[i]) * force_increase_rate; if (force_feedback_robot[i] <= -force_limit) force_feedback_robot[i] = -force_limit; - } else if (robot_cart_position[i] <= min[i]) { + } + else if (robot_cart_position[i] <= min[i]) { force_feedback_robot[i] = (min[i] - robot_cart_position[i]) * force_increase_rate; if (force_feedback_robot[i] >= force_limit) force_feedback_robot[i] = force_limit; - } else + } + else force_feedback_robot[i] = 0; } vpColVector force_feedback_virt = rMv.getRotationMatrix().inverse() * force_feedback_robot; @@ -137,10 +142,11 @@ int main() robot.stopMotion(); virtuose.setPowerOff(); std::cout << "The end" << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { robot.stopMotion(); std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; - } +} #else std::cout << "You should install Virtuose SDK to use this binary..." << std::endl; #endif diff --git a/modules/robot/test/virtuose/testVirtuoseHapticBox.cpp b/modules/robot/test/virtuose/testVirtuoseHapticBox.cpp index 87f59f55a8..0f59d69555 100644 --- a/modules/robot/test/virtuose/testVirtuoseHapticBox.cpp +++ b/modules/robot/test/virtuose/testVirtuoseHapticBox.cpp @@ -49,6 +49,9 @@ #include #if defined(VISP_HAVE_VIRTUOSE) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif void CallBackVirtuose(VirtContext VC, void *ptr) { @@ -221,11 +224,13 @@ void CallBackVirtuose(VirtContext VC, void *ptr) forceFeedback[i] = (p_min[i] - localPosition[i]) * force_increase_rate; if (forceFeedback[i] >= force_limit) forceFeedback[i] = force_limit; - } else if ((p_max[i] <= localPosition[i])) { + } + else if ((p_max[i] <= localPosition[i])) { forceFeedback[i] = (p_max[i] - localPosition[i]) * force_increase_rate; if (forceFeedback[i] <= -force_limit) forceFeedback[i] = -force_limit; - } else + } + else forceFeedback[i] = 0; } @@ -249,19 +254,19 @@ int main(int argc, char **argv) opt_port = std::atoi(argv[i + 1]); else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] - << " [--ip ] [--port ]" - " [--help] [-h]\n" - << std::endl - << "Description: " << std::endl - << " --ip " << std::endl - << "\tHost IP address. Default value: \"localhost\"." << std::endl - << std::endl - << " --port " << std::endl - << "\tCommunication port. Default value: 5000." << std::endl - << "\tSuggested values: " << std::endl - << "\t- 5000 to communicate with the Virtuose." << std::endl - << "\t- 53210 to communicate with the Virtuose equipped with the Glove." << std::endl - << std::endl; + << " [--ip ] [--port ]" + " [--help] [-h]\n" + << std::endl + << "Description: " << std::endl + << " --ip " << std::endl + << "\tHost IP address. Default value: \"localhost\"." << std::endl + << std::endl + << " --port " << std::endl + << "\tCommunication port. Default value: 5000." << std::endl + << "\tSuggested values: " << std::endl + << "\t- 5000 to communicate with the Virtuose." << std::endl + << "\t- 53210 to communicate with the Virtuose equipped with the Glove." << std::endl + << std::endl; return EXIT_SUCCESS; } } @@ -288,7 +293,8 @@ int main(int argc, char **argv) vpTime::sleepMs(1000); } std::cout << "The end" << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } @@ -299,8 +305,8 @@ int main(int argc, char **argv) int main() { std::cout << "You should install pthread and/or Virtuose API to use this " - "binary..." - << std::endl; + "binary..." + << std::endl; return EXIT_SUCCESS; } #endif diff --git a/modules/robot/test/virtuose/testVirtuoseJointLimits.cpp b/modules/robot/test/virtuose/testVirtuoseJointLimits.cpp index cc30868670..1f468e66b5 100644 --- a/modules/robot/test/virtuose/testVirtuoseJointLimits.cpp +++ b/modules/robot/test/virtuose/testVirtuoseJointLimits.cpp @@ -49,20 +49,24 @@ #if defined(VISP_HAVE_VIRTUOSE) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void CallBackVirtuose(VirtContext VC, void *ptr) { (void)VC; vpVirtuose *p_virtuose = (vpVirtuose *)ptr; - float maxQ[6] = {0.7811045051f, -0.07668215036f, 2.481732368f, 2.819076777f, 1.044736624f, 2.687076807f}; - float minQ[6] = {-0.8011951447f, -1.648244739f, 0.7439950705f, -3.022218227f, -1.260564089f, -2.054088593f}; + float maxQ[6] = { 0.7811045051f, -0.07668215036f, 2.481732368f, 2.819076777f, 1.044736624f, 2.687076807f }; + float minQ[6] = { -0.8011951447f, -1.648244739f, 0.7439950705f, -3.022218227f, -1.260564089f, -2.054088593f }; unsigned int numJoint = 6; vpColVector feedbackRegion(numJoint, 0); vpColVector forceFeedback(numJoint, 0); int feedbackRegionFactor = 10; - float saturationForce[6] = {5, 5, 5, 2.5, 2.5, 2.5}; + float saturationForce[6] = { 5, 5, 5, 2.5, 2.5, 2.5 }; for (unsigned int iter = 0; iter < numJoint; iter++) feedbackRegion[iter] = (maxQ[iter] - minQ[iter]) / feedbackRegionFactor; @@ -73,13 +77,15 @@ void CallBackVirtuose(VirtContext VC, void *ptr) for (unsigned int iter = 0; iter < numJoint; iter++) { if (currentQ[iter] >= (maxQ[iter] - feedbackRegion[iter])) { forceFeedback[iter] = - -saturationForce[iter] * pow((currentQ[iter] - maxQ[iter] + feedbackRegion[iter]) / feedbackRegion[iter], 2); + -saturationForce[iter] * pow((currentQ[iter] - maxQ[iter] + feedbackRegion[iter]) / feedbackRegion[iter], 2); std::cout << "WARNING! Getting close to the maximum joint limit. Joint #" << iter + 1 << std::endl; - } else if (currentQ[iter] <= (minQ[iter] + feedbackRegion[iter])) { + } + else if (currentQ[iter] <= (minQ[iter] + feedbackRegion[iter])) { forceFeedback[iter] = - saturationForce[iter] * pow((minQ[iter] + feedbackRegion[iter] - currentQ[iter]) / feedbackRegion[iter], 2); + saturationForce[iter] * pow((minQ[iter] + feedbackRegion[iter] - currentQ[iter]) / feedbackRegion[iter], 2); std::cout << "WARNING! Getting close to the minimum joint limit. Joint #" << iter + 1 << std::endl; - } else { + } + else { forceFeedback[iter] = 0; std::cout << "Safe zone" << std::endl; } @@ -105,19 +111,19 @@ int main(int argc, char **argv) opt_port = std::atoi(argv[i + 1]); else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "\nUsage: " << argv[0] - << " [--ip ] [--port ]" - " [--help] [-h]\n" - << std::endl - << "Description: " << std::endl - << " --ip " << std::endl - << "\tHost IP address. Default value: \"localhost\"." << std::endl - << std::endl - << " --port " << std::endl - << "\tCommunication port. Default value: 5000." << std::endl - << "\tSuggested values: " << std::endl - << "\t- 5000 to communicate with the Virtuose." << std::endl - << "\t- 53210 to communicate with the Virtuose equipped with the Glove." << std::endl - << std::endl; + << " [--ip ] [--port ]" + " [--help] [-h]\n" + << std::endl + << "Description: " << std::endl + << " --ip " << std::endl + << "\tHost IP address. Default value: \"localhost\"." << std::endl + << std::endl + << " --port " << std::endl + << "\tCommunication port. Default value: 5000." << std::endl + << "\tSuggested values: " << std::endl + << "\t- 5000 to communicate with the Virtuose." << std::endl + << "\t- 53210 to communicate with the Virtuose equipped with the Glove." << std::endl + << std::endl; return EXIT_SUCCESS; ; } @@ -186,7 +192,8 @@ int main(int argc, char **argv) } std::cout << "The end" << std::endl; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getStringMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/robot/test/virtuose/testVirtuosePeriodicFunction.cpp b/modules/robot/test/virtuose/testVirtuosePeriodicFunction.cpp index 5f58664655..bc53164298 100644 --- a/modules/robot/test/virtuose/testVirtuosePeriodicFunction.cpp +++ b/modules/robot/test/virtuose/testVirtuosePeriodicFunction.cpp @@ -44,6 +44,10 @@ #if defined(VISP_HAVE_VIRTUOSE) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void CallBackVirtuose(VirtContext VC, void *ptr) { (void)VC; diff --git a/modules/robot/test/virtuose/testVirtuoseWithGlove.cpp b/modules/robot/test/virtuose/testVirtuoseWithGlove.cpp index 65d4551b2f..7c82ae79ba 100644 --- a/modules/robot/test/virtuose/testVirtuoseWithGlove.cpp +++ b/modules/robot/test/virtuose/testVirtuoseWithGlove.cpp @@ -58,6 +58,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif int port = 53210; std::string ip = "localhost"; @@ -77,11 +80,11 @@ int main() std::cout << "After init" << std::endl; #if 0 // Get joint position - for (size_t device=0; device < virtuose.size(); device ++) { + for (size_t device = 0; device < virtuose.size(); device++) { std::cout << "Number of joints: " << virtuose[device].getJointsNumber() - << " Joint position: " << virtuose[device].getArticularPosition().t() << std::endl - << " Cartesian position: " << virtuose[device].getAvatarPosition().t() << std::endl; - // std::cout << "Joint velocity: " << virtuose.getArticularVelocity().t() << std::endl; + << " Joint position: " << virtuose[device].getArticularPosition().t() << std::endl + << " Cartesian position: " << virtuose[device].getAvatarPosition().t() << std::endl; +// std::cout << "Joint velocity: " << virtuose.getArticularVelocity().t() << std::endl; } #endif bool end = false; diff --git a/modules/sensor/CMakeLists.txt b/modules/sensor/CMakeLists.txt index 8c32dc1e8c..ccd858c29c 100644 --- a/modules/sensor/CMakeLists.txt +++ b/modules/sensor/CMakeLists.txt @@ -132,87 +132,88 @@ configure_file(test/force-torque/configurationSettings.ini configurationSettings if(USE_FLYCAPTURE) # Add specific build flag to turn off warnings coming from PointGrey flycapture 3rd party - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unknown-pragmas) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-ignored-qualifiers) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unknown-pragmas") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-ignored-qualifiers") endif() if(USE_PYLON) # Add specific build flag to turn off warnings coming from Basler # pylon headers if(MSVC) - list(APPEND CXX_FLAGS_MUTE_WARNINGS /wd4244) - list(APPEND CXX_FLAGS_MUTE_WARNINGS /wd4267) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "/wd4244") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "/wd4267") else() - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unknown-pragmas) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unused-parameter) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-overloaded-virtual) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-deprecated-copy) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unused-variable) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unknown-pragmas") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-parameter") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-overloaded-virtual") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-deprecated-copy") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-variable") endif() endif() if(USE_REALSENSE) # Add specific build flag to turn off warnings coming from RealSense 3rd party - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-strict-aliasing) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-pessimizing-move) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unused-parameter) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-strict-aliasing") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-pessimizing-move") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-parameter") endif() if(USE_REALSENSE2) if(UNIX) # Add specific build flag to turn off warnings coming from PCL 3rd party - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-reorder) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unused-function) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-sign-compare) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-overloaded-virtual) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-deprecated-declarations) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-inconsistent-missing-override) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-sign-conversion) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-float-equal) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-pessimizing-move) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unused-parameter) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-comment) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-ignored-qualifiers) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-deprecated-copy) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unqualified-std-cast-call) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-reorder") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-function") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-compare") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-overloaded-virtual") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-deprecated-declarations") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-inconsistent-missing-override") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-conversion") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-float-equal") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-pessimizing-move") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-parameter") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-comment") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-ignored-qualifiers") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-deprecated-copy") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") else() - list(APPEND CXX_FLAGS_MUTE_WARNINGS /wd4244) - list(APPEND CXX_FLAGS_MUTE_WARNINGS /wd4267) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "/wd4244") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "/wd4267") endif() endif() if(USE_LIBFREENECT) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unused-parameter) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-parameter") endif() if(USE_UEYE) if(UNIX) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-deprecated-declarations) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-deprecated-declarations") else() - list(APPEND CXX_FLAGS_MUTE_WARNINGS /wd4996) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "/wd4996") endif() endif() if(USE_OPENCV) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-float-equal) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-float-equal") endif() if(USE_OCCIPITAL_STRUCTURE) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-reorder) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unused-function) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-unused-parameter) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-sign-compare) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-overloaded-virtual) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-ignored-qualifiers) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-maybe-uninitialized) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-deprecated-declarations) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-inconsistent-missing-override) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-sign-conversion) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-float-equal) - list(APPEND CXX_FLAGS_MUTE_WARNINGS -Wno-pessimizing-move) -endif() - -vp_set_source_file_compile_flag(src/force-torque/vpForceTorqueAtiNetFTSensor.cpp -Wno-strict-aliasing) + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-reorder") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-function") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-parameter") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-compare") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-overloaded-virtual") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-ignored-qualifiers") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-maybe-uninitialized") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-deprecated-declarations") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-inconsistent-missing-override") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-conversion") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-float-equal") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-pessimizing-move") +endif() + +vp_set_source_file_compile_flag(src/force-torque/vpForceTorqueAtiNetFTSensor.cpp "-Wno-strict-aliasing") if(CXX_FLAGS_MUTE_WARNINGS) # Add specific build flag to turn off warnings diff --git a/modules/sensor/include/visp3/sensor/vp1394CMUGrabber.h b/modules/sensor/include/visp3/sensor/vp1394CMUGrabber.h index c4674b5648..c6de07b3c4 100644 --- a/modules/sensor/include/visp3/sensor/vp1394CMUGrabber.h +++ b/modules/sensor/include/visp3/sensor/vp1394CMUGrabber.h @@ -37,6 +37,11 @@ * *****************************************************************************/ +/*! + \file vp1394CMUGrabber.h + \brief Firewire cameras video capture based on CMU 1394 Digital Camera SDK. +*/ + #ifndef vp1394CMUGrabber_h #define vp1394CMUGrabber_h @@ -55,11 +60,7 @@ #include #include -/*! - \file vp1394CMUGrabber.h - \brief Firewire cameras video capture based on CMU 1394 Digital Camera SDK. -*/ - +BEGIN_VISP_NAMESPACE /*! \class vp1394CMUGrabber @@ -237,7 +238,8 @@ class VISP_EXPORT vp1394CMUGrabber : public vpFrameGrabber color = vp1394CMUGrabber::MONO16; break; } - } else if (_format == 1) { + } + else if (_format == 1) { switch (_mode) { case 0: color = vp1394CMUGrabber::YUV422; @@ -264,7 +266,8 @@ class VISP_EXPORT vp1394CMUGrabber : public vpFrameGrabber color = vp1394CMUGrabber::MONO16; break; } - } else if (_format == 2) { + } + else if (_format == 2) { switch (_mode) { case 0: color = vp1394CMUGrabber::YUV422; @@ -332,6 +335,6 @@ class VISP_EXPORT vp1394CMUGrabber : public vpFrameGrabber private: void initCamera(); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vp1394TwoGrabber.h b/modules/sensor/include/visp3/sensor/vp1394TwoGrabber.h index 7344ac2f6f..7623bcea41 100644 --- a/modules/sensor/include/visp3/sensor/vp1394TwoGrabber.h +++ b/modules/sensor/include/visp3/sensor/vp1394TwoGrabber.h @@ -58,6 +58,20 @@ #if defined(VISP_HAVE_DC1394) +/* + * Interface with libdc1394 2.x + */ +#include + +#include +#include +#include + +#include +#include +#include + +BEGIN_VISP_NAMESPACE /*! \class vp1394TwoGrabber @@ -161,20 +175,6 @@ \endcode */ - -/* - * Interface with libdc1394 2.x - */ -#include - -#include -#include -#include - -#include -#include -#include - class VISP_EXPORT vp1394TwoGrabber : public vpFrameGrabber { @@ -460,6 +460,6 @@ class VISP_EXPORT vp1394TwoGrabber : public vpFrameGrabber dc1394camera_list_t *list; #endif }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpComedi.h b/modules/sensor/include/visp3/sensor/vpComedi.h index cb8a718065..7caa78f634 100644 --- a/modules/sensor/include/visp3/sensor/vpComedi.h +++ b/modules/sensor/include/visp3/sensor/vpComedi.h @@ -45,6 +45,7 @@ #include +BEGIN_VISP_NAMESPACE /*! \class vpComedi @@ -174,6 +175,6 @@ class VISP_EXPORT vpComedi std::vector m_chanlist; /*!< Channel list */ //@} }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpDirectShowDevice.h b/modules/sensor/include/visp3/sensor/vpDirectShowDevice.h index a1bc1b131b..9998487dd2 100644 --- a/modules/sensor/include/visp3/sensor/vpDirectShowDevice.h +++ b/modules/sensor/include/visp3/sensor/vpDirectShowDevice.h @@ -49,6 +49,7 @@ #include #include +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpDirectShowDevice { @@ -59,7 +60,7 @@ class VISP_EXPORT vpDirectShowDevice bool inUse; // true if the device is already used by a grabber public: - vpDirectShowDevice() : inUse(false) {} + vpDirectShowDevice() : inUse(false) { } explicit vpDirectShowDevice(const CComPtr &moniker) : inUse(false) { init(moniker); } bool init(const CComPtr &moniker); @@ -76,6 +77,7 @@ class VISP_EXPORT vpDirectShowDevice friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpDirectShowDevice &dev); }; +END_VISP_NAMESPACE #endif #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpDirectShowGrabber.h b/modules/sensor/include/visp3/sensor/vpDirectShowGrabber.h index a91492b014..c4651b89e0 100644 --- a/modules/sensor/include/visp3/sensor/vpDirectShowGrabber.h +++ b/modules/sensor/include/visp3/sensor/vpDirectShowGrabber.h @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE class vpDirectShowGrabberImpl; /*! @@ -110,5 +111,6 @@ class VISP_EXPORT vpDirectShowGrabber : public vpFrameGrabber // Get current capture MediaType int getMediaType(); }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpDirectShowGrabberImpl.h b/modules/sensor/include/visp3/sensor/vpDirectShowGrabberImpl.h index b525ed0f65..bd232eda72 100644 --- a/modules/sensor/include/visp3/sensor/vpDirectShowGrabberImpl.h +++ b/modules/sensor/include/visp3/sensor/vpDirectShowGrabberImpl.h @@ -51,6 +51,8 @@ #include #include #include + +BEGIN_VISP_NAMESPACE /*! \class vpDirectShowGrabberImpl \brief class for windows direct show devices - implementation @@ -208,7 +210,7 @@ class VISP_EXPORT vpDirectShowGrabberImpl : public vpFrameGrabber // Frees the format block in an AM_MEDIA_TYPE structure void MyFreeMediaType(AM_MEDIA_TYPE &mt); }; - +END_VISP_NAMESPACE #endif #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpDirectShowSampleGrabberI.h b/modules/sensor/include/visp3/sensor/vpDirectShowSampleGrabberI.h index 2b42fa9358..436a9fe5d5 100644 --- a/modules/sensor/include/visp3/sensor/vpDirectShowSampleGrabberI.h +++ b/modules/sensor/include/visp3/sensor/vpDirectShowSampleGrabberI.h @@ -51,6 +51,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! This class is needed in order to implement a callback function associated with the grabber @@ -96,7 +97,7 @@ class VISP_EXPORT vpDirectShowSampleGrabberI : public ISampleGrabberCB friend class vpDirectShowGrabberImpl; }; - +END_VISP_NAMESPACE #endif #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpFlyCaptureGrabber.h b/modules/sensor/include/visp3/sensor/vpFlyCaptureGrabber.h index 415902323a..db29e48308 100644 --- a/modules/sensor/include/visp3/sensor/vpFlyCaptureGrabber.h +++ b/modules/sensor/include/visp3/sensor/vpFlyCaptureGrabber.h @@ -33,6 +33,12 @@ * *****************************************************************************/ +/*! + \file vpFlyCaptureGrabber.h + \brief Wrapper over PointGrey FlyCapture SDK to capture images from + PointGrey cameras. +*/ + #ifndef _vpFlyCaptureGrabber_h_ #define _vpFlyCaptureGrabber_h_ @@ -44,11 +50,8 @@ #include -/*! - \file vpFlyCaptureGrabber.h - \brief Wrapper over PointGrey FlyCapture SDK to capture images from - PointGrey cameras. -*/ +BEGIN_VISP_NAMESPACE + /*! \class vpFlyCaptureGrabber \ingroup group_sensor_camera @@ -115,40 +118,40 @@ int main() example shows how to capture simultaneously images from multiple cameras. \code -#include -#include -#include + #include + #include + #include -int main() -{ -#if defined(VISP_HAVE_FLYCAPTURE) - int nframes = 100; - char filename[FILENAME_MAX]; - unsigned int numCameras = vpFlyCaptureGrabber::getNumCameras(); - - std::cout << "Number of cameras detected: " << numCameras << std::endl; + int main() + { + #if defined(VISP_HAVE_FLYCAPTURE) + int nframes = 100; + char filename[FILENAME_MAX]; + unsigned int numCameras = vpFlyCaptureGrabber::getNumCameras(); - vpFlyCaptureGrabber *g = new vpFlyCaptureGrabber [numCameras]; - std::vector< vpImage > I(numCameras); + std::cout << "Number of cameras detected: " << numCameras << std::endl; - for(unsigned int cam=0; cam < numCameras; cam++) { - g[cam].setCameraIndex(cam); // Default camera is the first on the bus - g[cam].getCameraInfo(std::cout); - g[cam].open(I[cam]); - } + vpFlyCaptureGrabber *g = new vpFlyCaptureGrabber [numCameras]; + std::vector< vpImage > I(numCameras); - for(int i=0; i< nframes; i++) { for(unsigned int cam=0; cam < numCameras; cam++) { - g[cam].acquire(I[cam]); - snprintf(filename, FILENAME_MAX, "image-camera%d-%04d.pgm", cam, i); - vpImageIo::write(I[cam], filename); + g[cam].setCameraIndex(cam); // Default camera is the first on the bus + g[cam].getCameraInfo(std::cout); + g[cam].open(I[cam]); + } + + for(int i=0; i< nframes; i++) { + for(unsigned int cam=0; cam < numCameras; cam++) { + g[cam].acquire(I[cam]); + snprintf(filename, FILENAME_MAX, "image-camera%d-%04d.pgm", cam, i); + vpImageIo::write(I[cam], filename); + } } + delete [] g; + #endif } - delete [] g; -#endif -} \endcode - */ +*/ class VISP_EXPORT vpFlyCaptureGrabber : public vpFrameGrabber { public: @@ -231,6 +234,6 @@ class VISP_EXPORT vpFlyCaptureGrabber : public vpFrameGrabber bool m_connected; //!< true if camera connected bool m_capture; //!< true is capture started }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h index f4dcd6e53f..dd8bc5e085 100644 --- a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h +++ b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h @@ -45,6 +45,7 @@ // is not supported on win XP #ifdef VISP_HAVE_FUNC_INET_NTOP +BEGIN_VISP_NAMESPACE /*! * \class vpForceTorqueAtiNetFTSensor * @@ -96,7 +97,7 @@ * ... * \endcode * where 3 first values are forces Fx, Fy, Fz in N and the 3 last are torques Tx, Ty, Tz in Nm. - */ +*/ class VISP_EXPORT vpForceTorqueAtiNetFTSensor : public vpUDPClient { public: @@ -159,6 +160,6 @@ class VISP_EXPORT vpForceTorqueAtiNetFTSensor : public vpUDPClient vpColVector m_ft; bool m_is_streaming_started; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h index e743a158bc..855bcad166 100644 --- a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h +++ b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpForceTorqueAtiSensor * @@ -80,7 +81,7 @@ * #endif * } * \endcode - */ +*/ class VISP_EXPORT vpForceTorqueAtiSensor : public vpComedi { public: @@ -113,6 +114,6 @@ class VISP_EXPORT vpForceTorqueAtiSensor : public vpComedi unsigned short m_num_channels; //!< Number of channels available from the sensor vpColVector m_sample_bias; //!< Sample value used for bias }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h index 6923c6be71..628bdf994f 100644 --- a/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h +++ b/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h @@ -55,6 +55,8 @@ #include +BEGIN_VISP_NAMESPACE + /*! \class vpForceTorqueIitSensor \ingroup group_sensor_ft @@ -142,7 +144,7 @@ LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$VISP_WS/3rdparty/FT_SDK_01_4/linux/ubuntu16.04 To configure the sensor, you may access the sensor through the web interface using uour favorite browser. \image html vpForceTorqueIitSensor-ethernet.png - */ +*/ class VISP_EXPORT vpForceTorqueIitSensor { public: @@ -168,7 +170,7 @@ class VISP_EXPORT vpForceTorqueIitSensor vpColVector m_ft; vpColVector m_ft_filt; - ftSensorsConnected m_ftSensorsData{}; + ftSensorsConnected m_ftSensorsData {}; std::atomic m_acquisitionEnabled; std::atomic m_dataValid; @@ -180,6 +182,6 @@ class VISP_EXPORT vpForceTorqueIitSensor std::mutex m_mutex; int m_warmupMilliseconds; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpKinect.h b/modules/sensor/include/visp3/sensor/vpKinect.h index d5f73273e3..8d3d8ab9a9 100644 --- a/modules/sensor/include/visp3/sensor/vpKinect.h +++ b/modules/sensor/include/visp3/sensor/vpKinect.h @@ -54,6 +54,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpKinect @@ -121,7 +122,8 @@ class VISP_EXPORT vpKinect : public Freenect::FreenectDevice /*! Depth map resolution. */ - typedef enum { + typedef enum + { DMAP_LOW_RES, /*!< Depth map has a resolution of 320 by 240. */ DMAP_MEDIUM_RES /*!< Depth map has a resolution of 640 by 480. */ } vpDMResolution; @@ -175,7 +177,7 @@ class VISP_EXPORT vpKinect : public Freenect::FreenectDevice unsigned int height; // height of the rgb image unsigned int width; // width of the rgb image }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpLaserScan.h b/modules/sensor/include/visp3/sensor/vpLaserScan.h index bd63f47772..bfac4b39d1 100644 --- a/modules/sensor/include/visp3/sensor/vpLaserScan.h +++ b/modules/sensor/include/visp3/sensor/vpLaserScan.h @@ -32,8 +32,6 @@ * Laser scan data structure. * *****************************************************************************/ -#ifndef vpLaserScan_h -#define vpLaserScan_h /*! \file vpLaserScan.h @@ -42,10 +40,15 @@ */ +#ifndef vpLaserScan_h +#define vpLaserScan_h + +#include #include "visp3/sensor/vpScanPoint.h" #include +BEGIN_VISP_NAMESPACE /*! \class vpLaserScan @@ -57,7 +60,7 @@ Other data as the start/stop angle, the start/end timestamp are also considered. - */ +*/ class /*VISP_EXPORT*/ vpLaserScan { public: @@ -122,5 +125,5 @@ class /*VISP_EXPORT*/ vpLaserScan short stopAngle; unsigned short numPoints; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/sensor/include/visp3/sensor/vpLaserScanner.h b/modules/sensor/include/visp3/sensor/vpLaserScanner.h index 2800588bb4..6b46e42a80 100644 --- a/modules/sensor/include/visp3/sensor/vpLaserScanner.h +++ b/modules/sensor/include/visp3/sensor/vpLaserScanner.h @@ -32,10 +32,6 @@ * Generic laser scanner. * *****************************************************************************/ -#ifndef vpLaserScanner_h -#define vpLaserScanner_h - -#include "visp3/core/vpConfig.h" /*! @@ -44,13 +40,19 @@ \brief Implements a generic laser scanner. */ +#ifndef vpLaserScanner_h +#define vpLaserScanner_h + +#include "visp3/core/vpConfig.h" + +BEGIN_VISP_NAMESPACE /*! \class vpLaserScanner \ingroup group_sensor_laserscanner \brief Class that defines a generic laser scanner. - */ +*/ class /*VISP_EXPORT*/ vpLaserScanner { public: @@ -72,5 +74,5 @@ class /*VISP_EXPORT*/ vpLaserScanner std::string ip; int port; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/sensor/include/visp3/sensor/vpMocap.h b/modules/sensor/include/visp3/sensor/vpMocap.h index 0d60744f64..d353ffb27d 100644 --- a/modules/sensor/include/visp3/sensor/vpMocap.h +++ b/modules/sensor/include/visp3/sensor/vpMocap.h @@ -41,22 +41,23 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpMocap * \ingroup group_sensor_mocap * Generic motion capture wrapper. - */ +*/ class VISP_EXPORT vpMocap { public: /*! * Default constructor that turns off the verbose mode. */ - vpMocap() : m_verbose(false), m_serverAddr(){}; + vpMocap() : m_verbose(false), m_serverAddr() { }; /*! * Destructor. */ - virtual ~vpMocap(){}; + virtual ~vpMocap() { }; /*! * Close connexion with the motion capture device. @@ -104,5 +105,5 @@ class VISP_EXPORT vpMocap bool m_verbose; std::string m_serverAddr; }; - +END_VISP_NAMESPACE #endif // vpMocap_h diff --git a/modules/sensor/include/visp3/sensor/vpMocapQualisys.h b/modules/sensor/include/visp3/sensor/vpMocapQualisys.h index 255f9da79d..e941045872 100644 --- a/modules/sensor/include/visp3/sensor/vpMocapQualisys.h +++ b/modules/sensor/include/visp3/sensor/vpMocapQualisys.h @@ -41,11 +41,12 @@ #include +BEGIN_VISP_NAMESPACE /*! * \class vpMocapQualisys * \ingroup group_sensor_mocap * Qualisys motion capture wrapper. - */ +*/ class VISP_EXPORT vpMocapQualisys : public vpMocap { public: @@ -67,6 +68,6 @@ class VISP_EXPORT vpMocapQualisys : public vpMocap class vpMocapQualisysImpl; vpMocapQualisysImpl *m_impl; }; - +END_VISP_NAMESPACE #endif #endif // vpMocapQualisys_h diff --git a/modules/sensor/include/visp3/sensor/vpMocapVicon.h b/modules/sensor/include/visp3/sensor/vpMocapVicon.h index aa44ec1605..94dedc892e 100644 --- a/modules/sensor/include/visp3/sensor/vpMocapVicon.h +++ b/modules/sensor/include/visp3/sensor/vpMocapVicon.h @@ -41,11 +41,13 @@ #include +BEGIN_VISP_NAMESPACE + /*! *\class vpMocapVicon * \ingroup group_sensor_mocap * Vicon motion capture wrapper. - */ +*/ class VISP_EXPORT vpMocapVicon : public vpMocap { public: @@ -67,6 +69,6 @@ class VISP_EXPORT vpMocapVicon : public vpMocap class vpMocapViconImpl; vpMocapViconImpl *m_impl; }; - +END_VISP_NAMESPACE #endif #endif // vpMocapVicon_h diff --git a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h index cb1cbca048..43a60d9f7c 100644 --- a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h +++ b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h @@ -54,6 +54,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpOccipitalStructure @@ -359,6 +360,6 @@ class VISP_EXPORT vpOccipitalStructure void getColoredPointcloud(pcl::PointCloud::Ptr &pointcloud); #endif }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpPylonFactory.h b/modules/sensor/include/visp3/sensor/vpPylonFactory.h index d2ddcd010d..5ba56eaf16 100644 --- a/modules/sensor/include/visp3/sensor/vpPylonFactory.h +++ b/modules/sensor/include/visp3/sensor/vpPylonFactory.h @@ -35,6 +35,12 @@ * *****************************************************************************/ +/*! + \file vpPylonFactory.h + \brief Description: Factory class used to create vpPylonGrabber + instances. +*/ + #ifndef _vpPylonFactory_h_ #define _vpPylonFactory_h_ @@ -44,12 +50,7 @@ #ifdef VISP_HAVE_PYLON -/*! - \file vpPylonFactory.h - \brief Description: Factory class used to create vpPylonGrabber - instances. -*/ - +BEGIN_VISP_NAMESPACE /*! \brief Factory singleton class to create vpPylonGrabber subclass instances. @@ -64,7 +65,7 @@ vpPylonFactory &factory = vpPylonFactory::instance(); vpPylonGrabber *g = factory.createPylonGrabber(vpPylonFactory::BASLER_GIGE); \endcode - */ +*/ class VISP_EXPORT vpPylonFactory { public: @@ -72,7 +73,8 @@ class VISP_EXPORT vpPylonFactory /*! Device class of cameras. */ - enum DeviceClass { + enum DeviceClass + { BASLER_GIGE, //!< Basler GigE camera. BASLER_USB //!< Basler USB camera. }; @@ -81,12 +83,12 @@ class VISP_EXPORT vpPylonFactory private: //! Default constructor. - vpPylonFactory(){}; + vpPylonFactory() { }; vpPylonFactory(vpPylonFactory const &); void operator=(vpPylonFactory const &); Pylon::PylonAutoInitTerm m_autoInitTerm; //!< Auto initialize and terminate object for pylon SDK. }; - +END_VISP_NAMESPACE #endif // #ifdef VISP_HAVE_PYLON #endif // #ifndef _vpPylonFactory_h_ diff --git a/modules/sensor/include/visp3/sensor/vpPylonGrabber.h b/modules/sensor/include/visp3/sensor/vpPylonGrabber.h index 726b7064ba..0c601e4c5a 100644 --- a/modules/sensor/include/visp3/sensor/vpPylonGrabber.h +++ b/modules/sensor/include/visp3/sensor/vpPylonGrabber.h @@ -36,6 +36,12 @@ * *****************************************************************************/ +/*! + \file vpPylonGrabber.h + \brief Wrapper over Basler Pylon SDK to capture images from Basler + cameras. +*/ + #ifndef _vpPylonGrabber_h_ #define _vpPylonGrabber_h_ @@ -58,12 +64,7 @@ #include -/*! - \file vpPylonGrabber.h - \brief Wrapper over Basler Pylon SDK to capture images from Basler - cameras. -*/ - +BEGIN_VISP_NAMESPACE /*! \class vpPylonGrabber \ingroup group_sensor_camera @@ -92,18 +93,19 @@ - acA1600-60gm This class is inspired by vpFlyCaptureGrabber with much simplified methods. - */ +*/ class VISP_EXPORT vpPylonGrabber : public vpFrameGrabber { public: /*! Default destructor. */ - virtual ~vpPylonGrabber(){}; + virtual ~vpPylonGrabber() { }; /*! Valid values for user set names. */ - enum UserSetName { + enum UserSetName + { USERSET_DEFAULT, //!< The default user set. USERSET_USERSET1, //!< User set 1. USERSET_USERSET2, //!< User set 2. @@ -390,6 +392,6 @@ class VISP_EXPORT vpPylonGrabber : public vpFrameGrabber */ virtual void stopCapture() = 0; }; - +END_VISP_NAMESPACE #endif // #ifdef VISP_HAVE_PYLON #endif // #ifndef _vpPylonGrabber_h_ diff --git a/modules/sensor/include/visp3/sensor/vpRealSense.h b/modules/sensor/include/visp3/sensor/vpRealSense.h index cc27cd0235..58824b0bbd 100644 --- a/modules/sensor/include/visp3/sensor/vpRealSense.h +++ b/modules/sensor/include/visp3/sensor/vpRealSense.h @@ -55,6 +55,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! \class vpRealSense @@ -456,6 +457,6 @@ class VISP_EXPORT vpRealSense void initStream(); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpRealSense2.h b/modules/sensor/include/visp3/sensor/vpRealSense2.h index 9c0e40158b..eb1996230f 100644 --- a/modules/sensor/include/visp3/sensor/vpRealSense2.h +++ b/modules/sensor/include/visp3/sensor/vpRealSense2.h @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpRealSense2 @@ -283,7 +284,7 @@ \note Additional information can be found in the [librealsense wiki](https://github.com/IntelRealSense/librealsense/wiki/). - */ +*/ class VISP_EXPORT vpRealSense2 { public: @@ -405,6 +406,6 @@ class VISP_EXPORT vpRealSense2 pcl::PointCloud::Ptr &pointcloud); #endif }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpScanPoint.h b/modules/sensor/include/visp3/sensor/vpScanPoint.h index 28904ce659..954f17d56d 100644 --- a/modules/sensor/include/visp3/sensor/vpScanPoint.h +++ b/modules/sensor/include/visp3/sensor/vpScanPoint.h @@ -32,9 +32,17 @@ * Single laser scanner point. * *****************************************************************************/ + +/*! + \file vpScanPoint.h + + \brief Implements a single laser scanner point. +*/ + #ifndef vpScanPoint_h #define vpScanPoint_h +#include #include #include // std::fabs @@ -43,12 +51,7 @@ #include #include -/*! - \file vpScanPoint.h - - \brief Implements a single laser scanner point. -*/ - +BEGIN_VISP_NAMESPACE /*! \class vpScanPoint @@ -244,5 +247,5 @@ inline std::ostream &operator<<(std::ostream &s, const vpScanPoint &p) return s; } - +END_VISP_NAMESPACE #endif diff --git a/modules/sensor/include/visp3/sensor/vpSickLDMRS.h b/modules/sensor/include/visp3/sensor/vpSickLDMRS.h index a1bddca0c2..e5019cee25 100644 --- a/modules/sensor/include/visp3/sensor/vpSickLDMRS.h +++ b/modules/sensor/include/visp3/sensor/vpSickLDMRS.h @@ -32,6 +32,13 @@ * Sick LD-MRS laser driver. * *****************************************************************************/ + +/*! + * \file vpSickLDMRS.h + * + * \brief Driver for the Sick LD-MRS laser scanner. + */ + #ifndef vpSickLDMRS_h #define vpSickLDMRS_h @@ -50,12 +57,7 @@ #include #include -/*! - * \file vpSickLDMRS.h - * - * \brief Driver for the Sick LD-MRS laser scanner. - */ - +BEGIN_VISP_NAMESPACE /*! * \class vpSickLDMRS * @@ -98,7 +100,7 @@ * #endif * } * \endcode - */ +*/ class VISP_EXPORT vpSickLDMRS : public vpLaserScanner { public: @@ -156,7 +158,7 @@ class VISP_EXPORT vpSickLDMRS : public vpLaserScanner bool isFirstMeasure; size_t maxlen_body; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpUeyeGrabber.h b/modules/sensor/include/visp3/sensor/vpUeyeGrabber.h index 2a0370c23b..6ab52d0d6b 100644 --- a/modules/sensor/include/visp3/sensor/vpUeyeGrabber.h +++ b/modules/sensor/include/visp3/sensor/vpUeyeGrabber.h @@ -41,6 +41,7 @@ #ifdef VISP_HAVE_UEYE +BEGIN_VISP_NAMESPACE /*! * \class vpUeyeGrabber * \ingroup group_sensor_camera @@ -79,7 +80,7 @@ * g.acquire(I); * } * \endcode - */ +*/ class VISP_EXPORT vpUeyeGrabber { public: @@ -120,6 +121,6 @@ class VISP_EXPORT vpUeyeGrabber class vpUeyeGrabberImpl; vpUeyeGrabberImpl *m_impl; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h b/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h index d335e16f68..acd7815937 100644 --- a/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h +++ b/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h @@ -54,6 +54,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpV4l2Grabber @@ -346,6 +347,6 @@ class VISP_EXPORT vpV4l2Grabber : public vpFrameGrabber vpV4l2FrameFormatType m_frameformat; vpV4l2PixelFormatType m_pixelformat; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/sensor/src/force-torque/vpComedi.cpp b/modules/sensor/src/force-torque/vpComedi.cpp index f02ed55a17..7919a988b4 100644 --- a/modules/sensor/src/force-torque/vpComedi.cpp +++ b/modules/sensor/src/force-torque/vpComedi.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Default constructor. */ @@ -170,7 +171,7 @@ std::string vpComedi::getPhyDataUnits() const } return units; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vpComedi.cpp.o) has symbols void dummy_vpComedi() { }; diff --git a/modules/sensor/src/force-torque/vpForceTorqueAtiNetFTSensor.cpp b/modules/sensor/src/force-torque/vpForceTorqueAtiNetFTSensor.cpp index 60034baf8f..485ee2b4cf 100644 --- a/modules/sensor/src/force-torque/vpForceTorqueAtiNetFTSensor.cpp +++ b/modules/sensor/src/force-torque/vpForceTorqueAtiNetFTSensor.cpp @@ -46,7 +46,8 @@ #ifdef VISP_HAVE_FUNC_INET_NTOP #ifndef DOXYGEN_SHOULD_SKIP_THIS -typedef struct response_struct { +typedef struct response_struct +{ uint32_t rdt_sequence; uint32_t ft_sequence; uint32_t status; @@ -54,6 +55,7 @@ typedef struct response_struct { } RESPONSE; #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE /*! * Default constructor that set counts per force to 1000000, counts per torque to 1000000000 and scaling factor to 1. * Note that counts per force, counts per torque and scaling factor are used to transform force / torque in user units @@ -62,9 +64,8 @@ typedef struct response_struct { */ vpForceTorqueAtiNetFTSensor::vpForceTorqueAtiNetFTSensor() : vpUDPClient(), m_counts_per_force(1000000), m_counts_per_torque(1000000000), m_scaling_factor(1), m_ft_bias(6, 0), - m_data_count(0), m_data_count_prev(0), m_ft(6, 0), m_is_streaming_started(false) -{ -} + m_data_count(0), m_data_count_prev(0), m_ft(6, 0), m_is_streaming_started(false) +{ } /*! * Constructor that initializes an Eternet UDP connection to a given hostname and port. @@ -73,9 +74,8 @@ vpForceTorqueAtiNetFTSensor::vpForceTorqueAtiNetFTSensor() */ vpForceTorqueAtiNetFTSensor::vpForceTorqueAtiNetFTSensor(const std::string &hostname, int port) : vpUDPClient(hostname, port), m_counts_per_force(1000000), m_counts_per_torque(1000000000), m_scaling_factor(1), - m_ft_bias(6, 0), m_data_count(0), m_data_count_prev(0), m_ft(6, 0), m_is_streaming_started(false) -{ -} + m_ft_bias(6, 0), m_data_count(0), m_data_count_prev(0), m_ft(6, 0), m_is_streaming_started(false) +{ } /*! * Start high-speed real-time Net F/T streaming. @@ -175,7 +175,8 @@ void vpForceTorqueAtiNetFTSensor::bias(unsigned int n_counts) if (n_counts == 0) { m_ft_bias = getForceTorque(); - } else { + } + else { for (unsigned int i = 0; i < n_counts; i++) { ft_bias_tmp += getForceTorque(); waitForNewData(); @@ -272,5 +273,5 @@ bool vpForceTorqueAtiNetFTSensor::waitForNewData(unsigned int timeout) return false; } - +END_VISP_NAMESPACE #endif diff --git a/modules/sensor/src/force-torque/vpForceTorqueAtiSensor.cpp b/modules/sensor/src/force-torque/vpForceTorqueAtiSensor.cpp index b65ca6e197..d7df89e60c 100644 --- a/modules/sensor/src/force-torque/vpForceTorqueAtiSensor.cpp +++ b/modules/sensor/src/force-torque/vpForceTorqueAtiSensor.cpp @@ -44,13 +44,13 @@ static Calibration *s_calibinfo = nullptr; //!< Struct containing calibration information +BEGIN_VISP_NAMESPACE /*! * Default constructor. */ vpForceTorqueAtiSensor::vpForceTorqueAtiSensor() : m_calibfile(""), m_index(1), m_num_axes(6), m_num_channels(6), m_sample_bias() -{ -} +{ } /*! * Open the connection to the device. @@ -255,7 +255,8 @@ std::ostream &operator<<(std::ostream &os, const vpForceTorqueAtiSensor &ati) char *units; if ((s_calibinfo->AxisNames[i])[0] == 'F') { units = s_calibinfo->ForceUnits; - } else + } + else units = s_calibinfo->TorqueUnits; os << s_calibinfo->AxisNames[i] << ": " << s_calibinfo->MaxLoads[i] << " " << units << std::endl; } @@ -276,9 +277,9 @@ std::ostream &operator<<(std::ostream &os, const vpForceTorqueAtiSensor &ati) return os; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: // libvisp_sensor.a(vpForceTorqueAtiSensor.cpp.o) has no symbols -void dummy_vpForceTorqueAtiSensor(){}; +void dummy_vpForceTorqueAtiSensor() { }; #endif diff --git a/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp b/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp index d111f26664..0648db04b4 100644 --- a/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp +++ b/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp @@ -45,6 +45,7 @@ #if defined(VISP_HAVE_FT_IIT_SDK) && defined(VISP_HAVE_THREADS) +BEGIN_VISP_NAMESPACE /*! Default constructor. @@ -52,8 +53,8 @@ */ vpForceTorqueIitSensor::vpForceTorqueIitSensor() : m_ftLib(), m_numSensorsInLib(0), m_ft(6, 0), m_ft_filt(6, 0), m_ftSensorsData(), m_acquisitionEnabled(false), - m_dataValid(false), m_connected(false), m_acquisitionThread(), m_timeCur(), m_timePrev(), m_mutex(), - m_warmupMilliseconds(500) + m_dataValid(false), m_connected(false), m_acquisitionThread(), m_timeCur(), m_timePrev(), m_mutex(), + m_warmupMilliseconds(500) { // Get number of connected in library sensors m_numSensorsInLib = m_ftLib._getNumberOfConnectedSensors(); @@ -140,7 +141,8 @@ void vpForceTorqueIitSensor::acquisitionLoop() auto warmup_milliseconds = std::chrono::duration_cast(m_timeCur - time_init).count(); if (warmup_milliseconds > m_warmupMilliseconds) { m_dataValid = true; - } else { + } + else { continue; } @@ -207,7 +209,8 @@ vpColVector vpForceTorqueIitSensor::getForceTorque(bool filtered) const std::lock_guard lock(m_mutex); if (filtered) { return m_ft_filt; - } else { + } + else { return m_ft; } } @@ -235,9 +238,9 @@ void vpForceTorqueIitSensor::stopStreaming() m_acquisitionThread.join(); } } - +END_VISP_NAMESPACE #else // Work around to avoid warning: // libvisp_sensor.a(vpForceTorqueIitSensor.cpp.o) has no symbols -void dummy_vpForceTorqueIitSensor(){}; +void dummy_vpForceTorqueIitSensor() { }; #endif diff --git a/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp b/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp index a2364259b1..255db1e089 100644 --- a/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp +++ b/modules/sensor/src/framegrabber/1394/vp1394CMUGrabber.cpp @@ -42,13 +42,14 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Basic constructor. */ vp1394CMUGrabber::vp1394CMUGrabber() : index(0), // If a camera was not selected the first one (index = 0) will // be used - _format(-1), _mode(-1), _fps(-1), _modeauto(true), _gain(0), _shutter(0), _color(vp1394CMUGrabber::UNKNOWN) + _format(-1), _mode(-1), _fps(-1), _modeauto(true), _gain(0), _shutter(0), _color(vp1394CMUGrabber::UNKNOWN) { // public members init = false; @@ -244,7 +245,7 @@ void vp1394CMUGrabber::acquire(vpImage &I) close(); vpERROR_TRACE("Format conversion not implemented. Acquisition failed."); throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Format conversion not implemented. " - "Acquisition failed.")); + "Acquisition failed.")); break; }; @@ -308,7 +309,7 @@ void vp1394CMUGrabber::acquire(vpImage &I) close(); vpERROR_TRACE("Format conversion not implemented. Acquisition failed."); throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Format conversion not implemented. " - "Acquisition failed.")); + "Acquisition failed.")); break; }; } @@ -397,20 +398,21 @@ void vp1394CMUGrabber::setGain(unsigned short gain) if (_gain < min) { _gain = min; std::cout << "vp1394CMUGrabber warning: Desired gain register value of " - "IEEE 1394 camera number " - << index << " can't be less than " << _gain << std::endl; - } else if (_gain > max) { + "IEEE 1394 camera number " + << index << " can't be less than " << _gain << std::endl; + } + else if (_gain > max) { _gain = max; std::cout << "vp1394CMUGrabber warning: Desired gain register value of " - "IEEE 1394 camera number " - << index << " can't be greater than " << _gain << std::endl; + "IEEE 1394 camera number " + << index << " can't be greater than " << _gain << std::endl; } Control->SetAutoMode(false); if (Control->SetValue(_gain) != CAM_SUCCESS) { std::cout << "vp1394CMUGrabber warning: Can't set gain register value of " - "IEEE 1394 camera number " - << index << std::endl; + "IEEE 1394 camera number " + << index << std::endl; } } @@ -460,19 +462,20 @@ void vp1394CMUGrabber::setShutter(unsigned short shutter) if (_shutter < min) { _shutter = min; std::cout << "vp1394CMUGrabber warning: Desired exposure time register " - "value of IEEE 1394 camera number " - << index << " can't be less than " << _shutter << std::endl; - } else if (_shutter > max) { + "value of IEEE 1394 camera number " + << index << " can't be less than " << _shutter << std::endl; + } + else if (_shutter > max) { _shutter = max; std::cout << "vp1394CMUGrabber warning: Desired exposure time register " - "value of IEEE 1394 camera number " - << index << " can't be greater than " << _shutter << std::endl; + "value of IEEE 1394 camera number " + << index << " can't be greater than " << _shutter << std::endl; } Control->SetAutoMode(false); if (Control->SetValue(_shutter) != CAM_SUCCESS) { std::cout << "vp1394CMUGrabber warning: Can't set exposure time register " - "value of IEEE 1394 camera number " - << index << std::endl; + "value of IEEE 1394 camera number " + << index << std::endl; } } @@ -486,7 +489,8 @@ void vp1394CMUGrabber::displayCameraDescription(int cam_id) camera->GetNodeDescription(cam_id, buf, 512); std::cout << "Camera " << cam_id << ": " << buf << std::endl; - } else { + } + else { std::cout << "Camera " << cam_id << ": camera not found" << std::endl; } } @@ -749,9 +753,9 @@ vp1394CMUGrabber &vp1394CMUGrabber::operator>>(vpImage &I) this->acquire(I); return *this; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vp1394CMUGrabber.cpp.o) has // no symbols -void dummy_vp1394CMUGrabber(){}; +void dummy_vp1394CMUGrabber() { }; #endif diff --git a/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp b/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp index fec67e35d9..ec30aa3f75 100644 --- a/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp +++ b/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp @@ -52,6 +52,7 @@ #include #include +BEGIN_VISP_NAMESPACE const char *vp1394TwoGrabber::strVideoMode[DC1394_VIDEO_MODE_NUM] = { "MODE_160x120_YUV444", "MODE_320x240_YUV422", "MODE_640x480_YUV411", "MODE_640x480_YUV422", "MODE_640x480_RGB8", "MODE_640x480_MONO8", "MODE_640x480_MONO16", "MODE_800x600_YUV422", @@ -1278,22 +1279,22 @@ void vp1394TwoGrabber::setFormat7ROI(unsigned int left, unsigned int top, unsign setCapture(DC1394_ON); setTransmission(DC1394_ON); + } } -} -/*! + /*! - Open ohci and asign handle to it and get the camera nodes and - describe them as we find them. + Open ohci and asign handle to it and get the camera nodes and + describe them as we find them. - \param reset : If "true", reset the bus attached to the first - camera found. Bus reset may help to make firewire working if the - program was not properly stopped by a CTRL-C. + \param reset : If "true", reset the bus attached to the first + camera found. Bus reset may help to make firewire working if the + program was not properly stopped by a CTRL-C. - \exception initializationError : If a raw1394 handle can't be aquired, - or if no camera is found. + \exception initializationError : If a raw1394 handle can't be aquired, + or if no camera is found. - \sa close() - */ + \sa close() + */ void vp1394TwoGrabber::initialize(bool reset) { if (init == false) { @@ -1359,7 +1360,7 @@ void vp1394TwoGrabber::initialize(bool reset) "`ohci1394' are loaded \n" " - if you have read/write access to /dev/raw1394\n\n"); throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Unable to look for cameras")); - } + } #endif if (num_cameras == 0) { @@ -1397,7 +1398,7 @@ void vp1394TwoGrabber::initialize(bool reset) } init = true; - } +} } /*! @@ -1429,23 +1430,23 @@ void vp1394TwoGrabber::open() else { if (status == DC1394_ON) { vpTRACE("ISO transmission refuses to stop"); - } + } #ifdef VISP_HAVE_DC1394_FIND_CAMERAS // old API <= libdc1394-2.0.0-rc7 // No yet in the new API cameras[camera_id]->is_iso_on = status; #endif - } - //#ifdef VISP_HAVE_DC1394_CAMERA_ENUMERATE // new API > - // libdc1394-2.0.0-rc7 } - //#endif + //#ifdef VISP_HAVE_DC1394_CAMERA_ENUMERATE // new API > + // libdc1394-2.0.0-rc7 } + //#endif + } setCamera(camera_id); // setIsoSpeed(DC1394_ISO_SPEED_400); setCapture(DC1394_ON); setTransmission(DC1394_ON); camIsOpen[camera_id] = true; - } +} } /*! @@ -1495,8 +1496,8 @@ void vp1394TwoGrabber::close() #elif defined VISP_HAVE_DC1394_FIND_CAMERAS // old API <= libdc1394-2.0.0-rc7 dc1394_free_camera(cameras[i]); #endif + } } - } if (camIsOpen != nullptr) { delete[] camIsOpen; camIsOpen = nullptr; @@ -1537,21 +1538,21 @@ void vp1394TwoGrabber::close() } init = false; - } -} + } + } -/*! + /*! - Set the ring buffer size used for the capture. - To know the current ring buffer size see getRingBufferSize(). + Set the ring buffer size used for the capture. + To know the current ring buffer size see getRingBufferSize(). - \param size : Ring buffer size. + \param size : Ring buffer size. - \exception vpFrameGrabberException::settingError : If ring buffer size is - not valid. + \exception vpFrameGrabberException::settingError : If ring buffer size is + not valid. - \sa getRingBufferSize() -*/ + \sa getRingBufferSize() + */ void vp1394TwoGrabber::setRingBufferSize(unsigned int size) { if (size < 1) { @@ -2767,22 +2768,22 @@ void vp1394TwoGrabber::printCameraInfo() #elif defined VISP_HAVE_DC1394_FIND_CAMERAS // old API <= libdc1394-2.0.0-rc7 dc1394_print_feature_set(&features); #endif - } - std::cout << "----------------------------------------------------------" << std::endl; } + std::cout << "----------------------------------------------------------" << std::endl; + } -/*! + /*! - Converts the video mode identifier into a string containing the description - of the mode. + Converts the video mode identifier into a string containing the description + of the mode. - \param videomode : The camera capture video mode. + \param videomode : The camera capture video mode. - \return A string describing the mode, an empty string if the mode is not - supported. + \return A string describing the mode, an empty string if the mode is not + supported. - \sa string2videoMode() -*/ + \sa string2videoMode() + */ std::string vp1394TwoGrabber::videoMode2string(vp1394TwoVideoModeType videomode) { std::string _str = ""; @@ -3399,7 +3400,7 @@ vp1394TwoGrabber &vp1394TwoGrabber::operator>>(vpImage &I) this->acquire(I); return *this; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vp1394TwoGrabber.cpp.o) has // no symbols diff --git a/modules/sensor/src/framegrabber/directshow/vpDirectShowDevice.cpp b/modules/sensor/src/framegrabber/directshow/vpDirectShowDevice.cpp index aaeb7b171d..0d979bdd0a 100644 --- a/modules/sensor/src/framegrabber/directshow/vpDirectShowDevice.cpp +++ b/modules/sensor/src/framegrabber/directshow/vpDirectShowDevice.cpp @@ -41,6 +41,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Initialize the vpDirectShowDevice with the moniker's information \param pMoniker The moniker that contains the device's information @@ -111,10 +112,10 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpDirectShowDevice &dev) { return os << dev.name << std::endl << dev.desc << std::endl << dev.devPath; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vpDirectShowDevice.cpp.o) // has no symbols -void dummy_vpDirectShowDevice(){}; +void dummy_vpDirectShowDevice() { }; #endif #endif diff --git a/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabber.cpp b/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabber.cpp index 4fd5d3123f..9a7bdbdda3 100644 --- a/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabber.cpp +++ b/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabber.cpp @@ -43,6 +43,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Returns the number of rows in the grabbed image */ @@ -188,9 +189,9 @@ bool vpDirectShowGrabber::setMediaType(int mediaTypeID) { return grabber->setMed \return the current mediaTypeID */ int vpDirectShowGrabber::getMediaType() { return grabber->getMediaType(); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vpDirectShowGrabber.cpp.o) // has no symbols -void dummy_vpDirectShowGrabber(){}; +void dummy_vpDirectShowGrabber() { }; #endif diff --git a/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabberImpl.cpp b/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabberImpl.cpp index a1603b4244..d43bc90f0f 100644 --- a/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabberImpl.cpp +++ b/modules/sensor/src/framegrabber/directshow/vpDirectShowGrabberImpl.cpp @@ -40,6 +40,7 @@ #include +BEGIN_VISP_NAMESPACE vpDirectShowDevice *vpDirectShowGrabberImpl::deviceList = nullptr; unsigned int vpDirectShowGrabberImpl::nbDevices; @@ -237,7 +238,8 @@ bool vpDirectShowGrabberImpl::createDeviceList(CComPtr &ppVideoInp // if we can't get the device properties, skip to the next device j++; nbDevices--; - } else { + } + else { i++; j++; } @@ -288,7 +290,8 @@ bool vpDirectShowGrabberImpl::getDevice(unsigned int n, CComPtr &pp // now the device is in use deviceList[n].setInUse(); deviceFound = true; - } else { + } + else { break; } // we can't get the device's filter, quit } @@ -438,16 +441,16 @@ bool vpDirectShowGrabberImpl::checkSourceType(CComPtr &pCapSourcePin) // get the fourcc code format = ((bmpInfo.biCompression & 0xFF000000) >> 24) | ((bmpInfo.biCompression & 0x00FF0000) >> 8) | - ((bmpInfo.biCompression & 0x0000FF00) << 8) | (bmpInfo.biCompression & 0x000000FF) << 24; + ((bmpInfo.biCompression & 0x0000FF00) << 8) | (bmpInfo.biCompression & 0x000000FF) << 24; std::cout << "This format is not one of the standard YUV or RGB format " - "supported by DirectShow.\n" - << "FourCC : " << (char)(bmpInfo.biCompression & 0x000000FF) - << (char)((bmpInfo.biCompression & 0x0000FF00) >> 8) << (char)((bmpInfo.biCompression & 0x00FF0000) >> 16) - << (char)((bmpInfo.biCompression & 0xFF000000) >> 24) << std::endl; + "supported by DirectShow.\n" + << "FourCC : " << (char)(bmpInfo.biCompression & 0x000000FF) + << (char)((bmpInfo.biCompression & 0x0000FF00) >> 8) << (char)((bmpInfo.biCompression & 0x00FF0000) >> 16) + << (char)((bmpInfo.biCompression & 0xFF000000) >> 24) << std::endl; - // Y800 is top-down oriented so the image doesn't have to be flipped - // vertically +// Y800 is top-down oriented so the image doesn't have to be flipped +// vertically if (format == 'Y800') { sgCB.invertedSource = false; } @@ -461,8 +464,8 @@ bool vpDirectShowGrabberImpl::checkSourceType(CComPtr &pCapSourcePin) // needs invertedSource sets to true else { std::cout << "Unknown FourCC compression type, assuming top-down " - "orientation. Image may be inverted." - << std::endl; + "orientation. Image may be inverted." + << std::endl; sgCB.invertedSource = false; // consider that the image is topdown oriented by default } } @@ -812,17 +815,18 @@ bool vpDirectShowGrabberImpl::setFormat(unsigned int width, unsigned int height, LONGLONG ActualFrameDuration; if (FAILED(hr = pVideoControl->GetCurrentActualFrameRate(pCapSourcePin, &ActualFrameDuration))) std::cout << "Current format (not sure): " << width << " x " << height << " at " - << 10000000 / pVih->AvgTimePerFrame << " fps" << std::endl - << std::endl; + << 10000000 / pVih->AvgTimePerFrame << " fps" << std::endl + << std::endl; else { std::cout << "Current format : " << width << " x " << height << " at " << 10000000 / ActualFrameDuration - << " fps" << std::endl - << std::endl; + << " fps" << std::endl + << std::endl; pVih->AvgTimePerFrame = ActualFrameDuration; } found = true; } - } else { + } + else { if ((unsigned int)lWidth == width && (unsigned int)lHeight == height) { pVih->AvgTimePerFrame = scc.MinFrameInterval; // set the capture media type and the grabber media type @@ -834,8 +838,8 @@ bool vpDirectShowGrabberImpl::setFormat(unsigned int width, unsigned int height, pVih = (VIDEOINFOHEADER *)sgCB.connectedMediaType.pbFormat; found = true; std::cout << "Current format : " << width << " x " << height << " at " - << (10000000 / pVih->AvgTimePerFrame) << " fps" << std::endl - << std::endl; + << (10000000 / pVih->AvgTimePerFrame) << " fps" << std::endl + << std::endl; } } } @@ -847,11 +851,11 @@ bool vpDirectShowGrabberImpl::setFormat(unsigned int width, unsigned int height, if (!found) if (framerate != nullptr) std::cout << "The " << width << " x " << height << " at " << framerate - << " fps source image format is not available. " << std::endl - << std::endl; + << " fps source image format is not available. " << std::endl + << std::endl; else std::cout << "The " << width << " x " << height << "source image size is not available. " << std::endl - << std::endl; + << std::endl; return found; } @@ -947,29 +951,29 @@ bool vpDirectShowGrabberImpl::getStreamCapabilities() std::cout << "subtype : I420" << std::endl; else std::cout << "subtype (not supported) :" << (char)(pVih->bmiHeader.biCompression & 0x000000FF) - << (char)((pVih->bmiHeader.biCompression & 0x0000FF00) >> 8) - << (char)((pVih->bmiHeader.biCompression & 0x00FF0000) >> 16) - << (char)((pVih->bmiHeader.biCompression & 0xFF000000) >> 24) << std::endl; + << (char)((pVih->bmiHeader.biCompression & 0x0000FF00) >> 8) + << (char)((pVih->bmiHeader.biCompression & 0x00FF0000) >> 16) + << (char)((pVih->bmiHeader.biCompression & 0xFF000000) >> 24) << std::endl; std::cout << "image size : " << pVih->bmiHeader.biWidth << " x " << pVih->bmiHeader.biHeight << std::endl; std::cout << "framerate range: [" << 10000000 / scc.MaxFrameInterval << "," << 10000000 / scc.MinFrameInterval - << "]" << std::endl - << std::endl; + << "]" << std::endl + << std::endl; - /* - long frameRateNum; - LONGLONG *frameRateList; - if(FAILED(hr = - pVideoControl->GetFrameRateList(pCapSourcePin,iFormat,dimensions, - //inputs &frameRateNum, &frameRateList))) //outputs return false; - for(int i=0; i<(int)frameRateNum ; - i++) - { - std::cout<<(float)(10000000/frameRateList[i])<<" - fps"<GetFrameRateList(pCapSourcePin,iFormat,dimensions, + //inputs &frameRateNum, &frameRateList))) //outputs return false; + for(int i=0; i<(int)frameRateNum ; + i++) + { + std::cout<<(float)(10000000/frameRateList[i])<<" + fps"< #if (defined(VISP_HAVE_DIRECTSHOW)) +BEGIN_VISP_NAMESPACE /*! Constructor - creates the semaphore */ @@ -116,7 +117,8 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo flip); // reset the demand boolean acqRGBaDemand = false; - } else // if it was a grayscale image demand + } + else // if it was a grayscale image demand { // first, resizes the image as needed grayIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -125,11 +127,12 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo // reset the demand boolean acqGrayDemand = false; } - } else { + } + else { unsigned long FourCC; FourCC = ((bmpInfo.biCompression & 0xFF000000) >> 24) | ((bmpInfo.biCompression & 0x00FF0000) >> 8) | - ((bmpInfo.biCompression & 0x0000FF00) << 8) | (bmpInfo.biCompression & 0x000000FF) << 24; - // if the buffer contains a like YUV420 image + ((bmpInfo.biCompression & 0x0000FF00) << 8) | (bmpInfo.biCompression & 0x000000FF) << 24; + // if the buffer contains a like YUV420 image if (connectedMediaType.subtype == MEDIASUBTYPE_IYUV || FourCC == 'I420') { // if it was an RGBa image demand if (acqRGBaDemand) { @@ -140,7 +143,8 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo rgbaIm->getHeight()); // reset the demand boolean acqRGBaDemand = false; - } else // if it was a grayscale image demand + } + else // if it was a grayscale image demand { // first, resizes the image as needed grayIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -150,8 +154,9 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo acqGrayDemand = false; } - } else if (connectedMediaType.subtype == MEDIASUBTYPE_YV12) { - // if it was an RGBa image demand + } + else if (connectedMediaType.subtype == MEDIASUBTYPE_YV12) { + // if it was an RGBa image demand if (acqRGBaDemand) { // first, resizes the image as needed rgbaIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -160,7 +165,8 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo rgbaIm->getHeight()); // reset the demand boolean acqRGBaDemand = false; - } else // if it was a grayscale image demand + } + else // if it was a grayscale image demand { // first, resizes the image as needed grayIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -169,8 +175,9 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo // reset the demand boolean acqGrayDemand = false; } - } else if (connectedMediaType.subtype == MEDIASUBTYPE_YVU9) { - // if it was an RGBa image demand + } + else if (connectedMediaType.subtype == MEDIASUBTYPE_YVU9) { + // if it was an RGBa image demand if (acqRGBaDemand) { // first, resizes the image as needed rgbaIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -179,7 +186,8 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo rgbaIm->getHeight()); // reset the demand boolean acqRGBaDemand = false; - } else // if it was a grayscale image demand + } + else // if it was a grayscale image demand { // first, resizes the image as needed grayIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -188,8 +196,9 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo // reset the demand boolean acqGrayDemand = false; } - } else if (connectedMediaType.subtype == MEDIASUBTYPE_YUY2 || connectedMediaType.subtype == MEDIASUBTYPE_YUYV) { - // if it was an RGBa image demand + } + else if (connectedMediaType.subtype == MEDIASUBTYPE_YUY2 || connectedMediaType.subtype == MEDIASUBTYPE_YUYV) { + // if it was an RGBa image demand if (acqRGBaDemand) { // first, resizes the image as needed rgbaIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -198,7 +207,8 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo rgbaIm->getWidth() * rgbaIm->getHeight()); // reset the demand boolean acqRGBaDemand = false; - } else // if it was a grayscale image demand + } + else // if it was a grayscale image demand { // first, resizes the image as needed grayIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -207,8 +217,9 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo // reset the demand boolean acqGrayDemand = false; } - } else if (connectedMediaType.subtype == MEDIASUBTYPE_YVYU) { - // if it was an RGBa image demand + } + else if (connectedMediaType.subtype == MEDIASUBTYPE_YVYU) { + // if it was an RGBa image demand if (acqRGBaDemand) { // first, resizes the image as needed rgbaIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -217,7 +228,8 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo rgbaIm->getWidth() * rgbaIm->getHeight()); // reset the demand boolean acqRGBaDemand = false; - } else // if it was a grayscale image demand + } + else // if it was a grayscale image demand { // first, resizes the image as needed grayIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -226,8 +238,9 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo // reset the demand boolean acqGrayDemand = false; } - } else if (connectedMediaType.subtype == MEDIASUBTYPE_UYVY) { - // if it was an RGBa image demand + } + else if (connectedMediaType.subtype == MEDIASUBTYPE_UYVY) { + // if it was an RGBa image demand if (acqRGBaDemand) { // first, resizes the image as needed rgbaIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -236,7 +249,8 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo rgbaIm->getWidth() * rgbaIm->getHeight()); // reset the demand boolean acqRGBaDemand = false; - } else // if it was a grayscale image demand + } + else // if it was a grayscale image demand { // first, resizes the image as needed grayIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -245,8 +259,9 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo // reset the demand boolean acqGrayDemand = false; } - } else if (connectedMediaType.subtype == MEDIASUBTYPE_RGB32) { - // if it was an RGBa image demand + } + else if (connectedMediaType.subtype == MEDIASUBTYPE_RGB32) { + // if it was an RGBa image demand if (acqRGBaDemand) { // first, resizes the image as needed rgbaIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -256,7 +271,8 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo memcpy(rgbaIm->bitmap, pBuffer, 4 * rgbaIm->getWidth() * rgbaIm->getHeight()); // reset the demand boolean acqRGBaDemand = false; - } else // if it was a grayscale image demand + } + else // if it was a grayscale image demand { // first, resizes the image as needed grayIm->resize(abs(bmpInfo.biHeight), bmpInfo.biWidth); @@ -274,11 +290,11 @@ STDMETHODIMP vpDirectShowSampleGrabberI::BufferCB(double Time, BYTE *pBuffer, lo } return S_OK; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: // libvisp_sensor.a(vpDirectShowSampleGrabberI.cpp.o) has no symbols -void dummy_vpDirectShowSampleGrabberI(){}; +void dummy_vpDirectShowSampleGrabberI() { }; #endif #endif diff --git a/modules/sensor/src/framegrabber/flycapture/vpFlyCaptureGrabber.cpp b/modules/sensor/src/framegrabber/flycapture/vpFlyCaptureGrabber.cpp index a96ae4e684..45bd42d247 100644 --- a/modules/sensor/src/framegrabber/flycapture/vpFlyCaptureGrabber.cpp +++ b/modules/sensor/src/framegrabber/flycapture/vpFlyCaptureGrabber.cpp @@ -46,6 +46,8 @@ #include +BEGIN_VISP_NAMESPACE + /*! Default constructor that consider the first camera found on the bus as active. @@ -1401,7 +1403,7 @@ vpFlyCaptureGrabber &vpFlyCaptureGrabber::operator>>(vpImage &I) this->acquire(I); return *this; } - +END_VISP_NAMESPACE #else // Work around to avoid warning: // libvisp_flycapture.a(vpFlyCaptureGrabber.cpp.o) has no symbols diff --git a/modules/sensor/src/framegrabber/pylon/vpPylonFactory.cpp b/modules/sensor/src/framegrabber/pylon/vpPylonFactory.cpp index 68320a1fe5..51e11531b0 100644 --- a/modules/sensor/src/framegrabber/pylon/vpPylonFactory.cpp +++ b/modules/sensor/src/framegrabber/pylon/vpPylonFactory.cpp @@ -48,6 +48,7 @@ #include "vpPylonGrabberGigE.h" #include "vpPylonGrabberUsb.h" +BEGIN_VISP_NAMESPACE /*! \brief Get the vpPylonFactory singleton. */ @@ -81,9 +82,9 @@ vpPylonGrabber *vpPylonFactory::createPylonGrabber(DeviceClass dev_class) break; } } - +END_VISP_NAMESPACE #else // Work around to avoid warning: // libvisp_pylon.a(vpPylonFactory.cpp.o) has no symbols -void dummy_vpPylonFactory(){}; +void dummy_vpPylonFactory() { }; #endif // #ifdef VISP_HAVE_PYLON diff --git a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.cpp b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.cpp index 88217022fe..66b205ffcc 100644 --- a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.cpp +++ b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.cpp @@ -48,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Default constructor that consider the first camera found on the bus as active. @@ -116,7 +117,8 @@ Pylon::CInstantCamera *vpPylonGrabberGigE::getCameraHandler() if (m_connected == true) { return &m_camera; - } else { + } + else { return nullptr; } } @@ -379,10 +381,12 @@ float vpPylonGrabberGigE::setGain(bool gain_auto, float gain_value) if (GenApi::IsWritable(m_camera.GainAbs)) { m_camera.GainAbs.SetValue(gain_value); return m_camera.GainAbs.GetValue(); - } else if (GenApi::IsWritable(m_camera.GainRaw)) { + } + else if (GenApi::IsWritable(m_camera.GainRaw)) { m_camera.GainRaw.SetValue(gain_value); return m_camera.GainRaw.GetValue(); - } else + } + else throw vpException(vpException::notImplementedError, "Don't know how to set gain."); } @@ -407,10 +411,12 @@ float vpPylonGrabberGigE::setBlackLevel(float blacklevel_value) if (GenApi::IsWritable(m_camera.BlackLevelAbs)) { m_camera.BlackLevelAbs.SetValue(blacklevel_value); return m_camera.BlackLevelAbs.GetValue(); - } else if (GenApi::IsWritable(m_camera.BlackLevelRaw)) { + } + else if (GenApi::IsWritable(m_camera.BlackLevelRaw)) { m_camera.BlackLevelRaw.SetValue(blacklevel_value); return m_camera.BlackLevelRaw.GetValue(); - } else + } + else throw vpException(vpException::notImplementedError, "Don't know how to set blacklevel."); } @@ -448,10 +454,12 @@ float vpPylonGrabberGigE::setExposure(bool exposure_on, bool exposure_auto, floa if (GenApi::IsWritable(m_camera.ExposureTimeAbs)) { m_camera.ExposureTimeAbs.SetValue(exposure_value * 1000); return m_camera.ExposureTimeAbs.GetValue() * 0.001; - } else if (GenApi::IsWritable(m_camera.ExposureTimeRaw)) { + } + else if (GenApi::IsWritable(m_camera.ExposureTimeRaw)) { m_camera.ExposureTimeRaw.SetValue(exposure_value); return m_camera.ExposureTimeRaw.GetValue(); - } else + } + else throw vpException(vpException::notImplementedError, "Don't know how to set exposure."); } @@ -477,7 +485,8 @@ float vpPylonGrabberGigE::setGamma(bool gamma_on, float gamma_value) if (GenApi::IsWritable(m_camera.Gamma)) { m_camera.Gamma.SetValue(gamma_value); return m_camera.Gamma.GetValue(); - } else + } + else throw vpException(vpException::notImplementedError, "Don't know how to set gamma."); } @@ -802,9 +811,9 @@ vpPylonGrabber &vpPylonGrabberGigE::operator>>(vpImage &I) acquire(I); return *this; } - +END_VISP_NAMESPACE #else // Work around to avoid warning: // libvisp_pylon.a(vpPylonGrabberGigE.cpp.o) has no symbols -void dummy_vpPylonGrabberGigE(){}; +void dummy_vpPylonGrabberGigE() { }; #endif // #ifdef VISP_HAVE_PYLON diff --git a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.h b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.h index 90e12ad8f3..1de7a134b2 100644 --- a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.h +++ b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberGigE.h @@ -52,6 +52,7 @@ #include +BEGIN_VISP_NAMESPACE /*! \class vpPylonGrabberGigE @@ -61,7 +62,7 @@ vpPylonFactory::createPylonGrabber() instead. \headerfile vpPylonGrabberGigE.h "" - */ +*/ class VISP_EXPORT vpPylonGrabberGigE : public vpPylonGrabber { public: @@ -122,6 +123,6 @@ class VISP_EXPORT vpPylonGrabberGigE : public vpPylonGrabber unsigned int m_numCameras; //!< Number of connected GigE cameras bool m_connected; //!< true if camera connected }; - +END_VISP_NAMESPACE #endif // #ifdef VISP_HAVE_PYLON #endif // #ifndef _vpPylonGrabberGigE_h_ diff --git a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.cpp b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.cpp index 114d1780d2..ffd2f68530 100644 --- a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.cpp +++ b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.cpp @@ -48,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Default constructor that consider the first camera found on the bus as active. @@ -116,7 +117,8 @@ Pylon::CInstantCamera *vpPylonGrabberUsb::getCameraHandler() if (m_connected == true) { return &m_camera; - } else { + } + else { return nullptr; } } @@ -373,7 +375,8 @@ float vpPylonGrabberUsb::setGain(bool gain_auto, float gain_value) if (GenApi::IsWritable(m_camera.Gain)) { m_camera.Gain.SetValue(gain_value); return m_camera.Gain.GetValue(); - } else + } + else throw vpException(vpException::notImplementedError, "Don't know how to set gain."); } @@ -398,7 +401,8 @@ float vpPylonGrabberUsb::setBlackLevel(float blacklevel_value) if (GenApi::IsWritable(m_camera.BlackLevel)) { m_camera.BlackLevel.SetValue(blacklevel_value); return m_camera.BlackLevel.GetValue(); - } else + } + else throw vpException(vpException::notImplementedError, "Don't know how to set blacklevel."); } @@ -436,7 +440,8 @@ float vpPylonGrabberUsb::setExposure(bool exposure_on, bool exposure_auto, float if (GenApi::IsWritable(m_camera.ExposureTime)) { m_camera.ExposureTime.SetValue(exposure_value * 1000); return m_camera.ExposureTime.GetValue() * 0.001; - } else + } + else throw vpException(vpException::notImplementedError, "Don't know how to set exposure."); } @@ -462,7 +467,8 @@ float vpPylonGrabberUsb::setGamma(bool gamma_on, float gamma_value) else m_camera.Gamma.SetValue(1); return m_camera.Gamma.GetValue(); - } else + } + else throw vpException(vpException::notImplementedError, "Don't know how to set gamma."); } @@ -787,9 +793,9 @@ vpPylonGrabber &vpPylonGrabberUsb::operator>>(vpImage &I) acquire(I); return *this; } - +END_VISP_NAMESPACE #else // Work around to avoid warning: // libvisp_pylon.a(vpPylonGrabberUsb.cpp.o) has no symbols -void dummy_vpPylonGrabberUsb(){}; +void dummy_vpPylonGrabberUsb() { }; #endif // #ifdef VISP_HAVE_PYLON diff --git a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.h b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.h index 2c6bdf3e57..180192c50f 100644 --- a/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.h +++ b/modules/sensor/src/framegrabber/pylon/vpPylonGrabberUsb.h @@ -52,6 +52,7 @@ #include +BEGIN_VISP_NAMESPACE /*! \class vpPylonGrabberUsb @@ -61,7 +62,7 @@ vpPylonFactory::createPylonGrabber() instead. \headerfile vpPylonGrabberUsb.h "" - */ +*/ class VISP_EXPORT vpPylonGrabberUsb : public vpPylonGrabber { public: @@ -122,6 +123,6 @@ class VISP_EXPORT vpPylonGrabberUsb : public vpPylonGrabber unsigned int m_numCameras; //!< Number of connected USB cameras bool m_connected; //!< true if camera connected }; - +END_VISP_NAMESPACE #endif // #ifdef VISP_HAVE_PYLON #endif // #ifndef _vpPylonGrabberUsb_h_ diff --git a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp index d82d1250b0..a76e713e1a 100644 --- a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp +++ b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp @@ -65,6 +65,7 @@ } \ } +BEGIN_VISP_NAMESPACE /*! \brief image buffer properties structure */ struct sBufferProps { @@ -1425,7 +1426,7 @@ void vpUeyeGrabber::setWhiteBalance(bool auto_wb) { m_impl->setWhiteBalance(auto * \param[in] verbose : true to enable, false to disable verbose mode. */ void vpUeyeGrabber::setVerbose(bool verbose) { m_impl->setVerbose(verbose); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vpUeyeGrabber.cpp.o) has no symbols void dummy_vpUeyeGrabber() { }; diff --git a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber_impl.h b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber_impl.h index 7f6e1c85de..393cf58ab4 100644 --- a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber_impl.h +++ b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber_impl.h @@ -35,6 +35,7 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE class CameraList { public: @@ -84,13 +85,16 @@ class CameraList if (is_GetCameraList(m_pCamList) == IS_SUCCESS) { // SelectCamera (0); ret = true; - } else { + } + else { ret = false; } - } else { + } + else { ret = false; } - } else { + } + else { ret = false; } @@ -173,7 +177,8 @@ class CameraList { if (m_pCamList) { return (unsigned int)m_pCamList->dwCount; - } else { + } + else { return 0; } } @@ -182,6 +187,7 @@ class CameraList PUEYE_CAMERA_LIST m_pCamList; UEYE_CAMERA_INFO m_CamInfo; }; +END_VISP_NAMESPACE /* ********************************************************************************************** diff --git a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp index c2016a70d4..b761eb2322 100644 --- a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp +++ b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp @@ -60,6 +60,7 @@ #include #include +BEGIN_VISP_NAMESPACE const unsigned int vpV4l2Grabber::DEFAULT_INPUT = 2; const unsigned int vpV4l2Grabber::DEFAULT_SCALE = 2; const __u32 vpV4l2Grabber::MAX_INPUTS = 16; @@ -1465,7 +1466,7 @@ vpV4l2Grabber &vpV4l2Grabber::operator>>(vpImage &I) this->acquire(I); return *this; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vpV4l2Grabber.cpp.o) has no symbols void dummy_vpV4l2Grabber() { }; diff --git a/modules/sensor/src/laserscanner/sick/vpSickLDMRS.cpp b/modules/sensor/src/laserscanner/sick/vpSickLDMRS.cpp index bd983c069a..419ee1cab1 100644 --- a/modules/sensor/src/laserscanner/sick/vpSickLDMRS.cpp +++ b/modules/sensor/src/laserscanner/sick/vpSickLDMRS.cpp @@ -33,6 +33,13 @@ * *****************************************************************************/ +/*! + + \file vpSickLDMRS.cpp + + \brief Driver for the Sick LD-MRS laser scanner. +*/ + #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) #include @@ -52,13 +59,7 @@ #include #include -/*! - - \file vpSickLDMRS.cpp - - \brief Driver for the Sick LD-MRS laser scanner. -*/ - +BEGIN_VISP_NAMESPACE /*! Default constructor that initialize the Ethernet address to @@ -139,9 +140,11 @@ bool vpSickLDMRS::setup() if (res < 0 && errno != EINTR) { fprintf(stderr, "Error connecting to server %d - %s\n", errno, strerror(errno)); return false; - } else if (res > 0) { + } + else if (res > 0) { fprintf(stderr, "ok"); - } else { + } + else { fprintf(stderr, "Timeout in select() - Cancelling!\n"); return false; } @@ -275,5 +278,5 @@ bool vpSickLDMRS::measure(vpLaserScan laserscan[4]) } return true; } - +END_VISP_NAMESPACE #endif diff --git a/modules/sensor/src/mocap/vpMocapQualisys.cpp b/modules/sensor/src/mocap/vpMocapQualisys.cpp index 6b88f638e8..0f48be1f2b 100644 --- a/modules/sensor/src/mocap/vpMocapQualisys.cpp +++ b/modules/sensor/src/mocap/vpMocapQualisys.cpp @@ -46,15 +46,15 @@ #include #include +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpMocapQualisys::vpMocapQualisysImpl { public: vpMocapQualisysImpl() : m_rtProtocol(), m_basePort(22222), m_udpPort(6734), m_majorVersion(1), m_minorVersion(19), m_bigEndian(false), - m_dataAvailable(false), m_streamFrames(false), m_verbose(false), m_serverAddr() - { - } + m_dataAvailable(false), m_streamFrames(false), m_verbose(false), m_serverAddr() + { } virtual ~vpMocapQualisysImpl() { close(); } @@ -75,7 +75,8 @@ class vpMocapQualisys::vpMocapQualisysImpl vpTime::sleepMs(1000); } - } else { + } + else { if (m_verbose) { std::cout << "Qualisys connected" << std::endl; } @@ -101,7 +102,8 @@ class vpMocapQualisys::vpMocapQualisysImpl vpTime::sleepMs(1000); } - } else { + } + else { if (m_verbose && !readSettingsOK) { std::cout << "Reading 6DOF settings succeded." << std::endl; } @@ -114,7 +116,8 @@ class vpMocapQualisys::vpMocapQualisysImpl std::cout << "Reading 6DOF settings timeout: " << std::endl; } return false; - } else { + } + else { for (auto i = 0; i < 6; i++) { if (!m_streamFrames) { if (!m_rtProtocol.StreamFrames(CRTProtocol::RateAllFrames, 0, m_udpPort, nullptr, CRTProtocol::cComponent6d)) { @@ -125,7 +128,8 @@ class vpMocapQualisys::vpMocapQualisysImpl vpTime::sleepMs(1000); } m_streamFrames = true; - } else { + } + else { if (m_verbose) { std::cout << "Starting to stream 6DOF data" << std::endl; } @@ -148,7 +152,8 @@ class vpMocapQualisys::vpMocapQualisysImpl const char *pTmpStr = m_rtProtocol.Get6DOFBodyName(iBody); if (pTmpStr) { name = std::string(pTmpStr); - } else { + } + else { if (m_verbose) { std::cout << "Unknown body" << std::endl; } @@ -167,7 +172,8 @@ class vpMocapQualisys::vpMocapQualisysImpl } return true; - } else { + } + else { return false; } } @@ -190,7 +196,8 @@ class vpMocapQualisys::vpMocapQualisysImpl } if (all_bodies) { bodies_pose[bodyName] = bodyPose; - } else if (bodyPose.isValid()) { + } + else if (bodyPose.isValid()) { bodies_pose[bodyName] = bodyPose; } } @@ -210,13 +217,15 @@ class vpMocapQualisys::vpMocapQualisysImpl std::cout << "I found bodyName" << body_name << std::endl; } return true; - } else { + } + else { std::cout << "The body " << body_name << " was not found in Qualisys. Please check the name you typed." - << std::endl; + << std::endl; return false; } - } else { + } + else { std::cout << "Error : could not process data from Qualisys" << std::endl; return false; @@ -248,7 +257,7 @@ class vpMocapQualisys::vpMocapQualisysImpl /*! * Default constructor. */ -vpMocapQualisys::vpMocapQualisys() : m_impl(new vpMocapQualisysImpl()) {} +vpMocapQualisys::vpMocapQualisys() : m_impl(new vpMocapQualisysImpl()) { } /*! * Destructor. @@ -302,9 +311,9 @@ void vpMocapQualisys::setServerAddress(const std::string &serverAddr) { m_impl-> * \param[in] verbose : When true enable verbose mode, otherwise disable verbose mode. */ void vpMocapQualisys::setVerbose(bool verbose) { m_impl->setVerbose(verbose); } - +END_VISP_NAMESPACE #else // Work around to avoid warning: // libvisp_sensor.a(vpMocapQualisys.cpp.o) has no symbols -void dummy_vpMocapQualisys(){}; +void dummy_vpMocapQualisys() { }; #endif diff --git a/modules/sensor/src/mocap/vpMocapVicon.cpp b/modules/sensor/src/mocap/vpMocapVicon.cpp index 480cb612c5..22482ac5e9 100644 --- a/modules/sensor/src/mocap/vpMocapVicon.cpp +++ b/modules/sensor/src/mocap/vpMocapVicon.cpp @@ -48,11 +48,12 @@ using namespace ViconDataStreamSDK::CPP; +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpMocapVicon::vpMocapViconImpl { public: - vpMocapViconImpl() : m_DirectClient(), m_verbose(false), m_serverAddr() {} + vpMocapViconImpl() : m_DirectClient(), m_verbose(false), m_serverAddr() { } virtual ~vpMocapViconImpl() { close(); } void close() @@ -126,7 +127,8 @@ class vpMocapVicon::vpMocapViconImpl std::cout << "Error : Could not get pose from body n°" << iBody << std::endl; return false; - } else { + } + else { bodyPose[0][3] = m_DirectClient.GetSegmentGlobalTranslation(bodyName, rootSegment).Translation[0] / 1000.0; bodyPose[1][3] = m_DirectClient.GetSegmentGlobalTranslation(bodyName, rootSegment).Translation[1] / 1000.0; bodyPose[2][3] = m_DirectClient.GetSegmentGlobalTranslation(bodyName, rootSegment).Translation[2] / 1000.0; @@ -142,7 +144,8 @@ class vpMocapVicon::vpMocapViconImpl } if (all_bodies) { bodies_pose[bodyName] = bodyPose; - } else if (bodyPose.isValid()) { + } + else if (bodyPose.isValid()) { bodies_pose[bodyName] = bodyPose; } } @@ -158,13 +161,15 @@ class vpMocapVicon::vpMocapViconImpl if (bodies_pose.find(body_name) != bodies_pose.end()) { body_pose = bodies_pose[body_name]; return true; - } else { + } + else { std::cout << "The body " << body_name << " was not found in Vicon. Please check the name you typed." - << std::endl; + << std::endl; return false; } - } else { + } + else { std::cout << "Error : could not process data from Vicon" << std::endl; return false; @@ -208,7 +213,7 @@ class vpMocapVicon::vpMocapViconImpl /*! * Default constructor that creates a direct client (not a multi-cast client). */ -vpMocapVicon::vpMocapVicon() : m_impl(new vpMocapViconImpl()) {} +vpMocapVicon::vpMocapVicon() : m_impl(new vpMocapViconImpl()) { } /*! * Destructor. @@ -263,9 +268,9 @@ void vpMocapVicon::setServerAddress(const std::string &serverAddr) { m_impl->set * \param[in] verbose : When true enable verbose mode, otherwise disable verbose mode. */ void vpMocapVicon::setVerbose(bool verbose) { m_impl->setVerbose(verbose); } - +END_VISP_NAMESPACE #else // Work around to avoid warning: // libvisp_sensor.a(vpMocapVicon.cpp.o) has no symbols -void dummy_vpMocapVicon(){}; +void dummy_vpMocapVicon() { }; #endif diff --git a/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp b/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp index b4970068b8..fd48e8a8b9 100644 --- a/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp +++ b/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Default constructor. */ @@ -290,7 +291,7 @@ void vpKinect::warpRGBFrame(const vpImage &Irgb, const vpImage &I } } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vpKinect.cpp.o) has no symbols void dummy_vpKinect() { }; diff --git a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp index 807dc70318..41558fde92 100644 --- a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp +++ b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp @@ -52,6 +52,7 @@ #define MANUAL_POINTCLOUD 1 +BEGIN_VISP_NAMESPACE /*! * Default constructor. */ @@ -1216,5 +1217,5 @@ void vpOccipitalStructure::getColoredPointcloud(pcl::PointCloud #endif +BEGIN_VISP_NAMESPACE template void vp_rs_get_frame_data_impl(const rs::device *m_device, const std::map &m_intrinsics, const rs::stream &stream, vpImage &data) @@ -443,4 +444,5 @@ void vp_rs_get_pointcloud_impl(const rs::device *m_device, const std::map] [--port ]" - << " [--no-display] [-d] [--help] [-h]\n" - << std::endl; + << " [--ip ] [--port ]" + << " [--no-display] [-d] [--help] [-h]\n" + << std::endl; return EXIT_SUCCESS; } } @@ -117,7 +120,8 @@ int main(int argc, char **argv) vpDisplay::displayText(plotter->I, 20, 80, "Left click to quit", vpColor::red); if (bias) { vpDisplay::displayText(plotter->I, 40, 80, "Right click to unbias", vpColor::red); - } else { + } + else { vpDisplay::displayText(plotter->I, 40, 80, "Right click to bias", vpColor::red); } vpMouseButton::vpMouseButtonType button; @@ -125,19 +129,22 @@ int main(int argc, char **argv) if (vpDisplay::getClick(plotter->I, button, false)) { if (button == vpMouseButton::button1) { end = true; - } else if (button == vpMouseButton::button3) { + } + else if (button == vpMouseButton::button3) { bias = !bias; if (bias) { std::cout << "Bias F/T sensor" << std::endl; ati_net_ft.bias(); - } else { + } + else { std::cout << "Unbias F/T sensor" << std::endl; ati_net_ft.unbias(); } } } vpDisplay::flush(plotter->I); - } else { + } + else { std::cout << "F/T: " << ft.t() << std::endl; if (nbacq > 30) { end = true; diff --git a/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp b/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp index ce6eea2e85..85960bf797 100644 --- a/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp +++ b/modules/sensor/test/force-torque/testForceTorqueIitSensor.cpp @@ -46,6 +46,9 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #ifdef VISP_HAVE_FT_IIT_SDK bool opt_no_display = false; bool opt_filtered = false; @@ -113,7 +116,8 @@ int main(int argc, char **argv) } } vpDisplay::flush(plotter->I); - } else { + } + else { std::cout << "F/T: " << ft.t() << std::endl; if (nbacq > 30) { end = true; diff --git a/modules/sensor/test/framegrabber/test1394TwoGrabber.cpp b/modules/sensor/test/framegrabber/test1394TwoGrabber.cpp index fa6b308793..5157b7f26b 100644 --- a/modules/sensor/test/framegrabber/test1394TwoGrabber.cpp +++ b/modules/sensor/test/framegrabber/test1394TwoGrabber.cpp @@ -30,14 +30,12 @@ * * Description: * Firewire cameras video capture. - * -*****************************************************************************/ + */ /*! \file test1394TwoGrabber.cpp \brief Aquire images using libdc1394-2.x library. - */ #include @@ -46,16 +44,18 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #if defined(VISP_HAVE_DC1394) #include #include #include + /*! \example test1394TwoGrabber.cpp - - - */ int main() { @@ -112,21 +112,16 @@ int main() filename = outputpath + "/imagetest2.pgm"; std::cout << "Write image: " << filename << std::endl; vpImageIo::write(I, filename); - } catch (...) { + } + catch (...) { vpCERROR << "Failure: exit" << std::endl; } } #else int main() { - vpTRACE("Ieee 1394 grabber capabilities are not available...\n" - "You should install libdc1394-2 to use this binary."); + vpTRACE("Ieee 1394 grabber capabilities are not available..."); + vpTRACE("You should install libdc1394-2 to use this binary."); } #endif - -/* - * Local variables: - * c-basic-offset: 2 - * End: - */ diff --git a/modules/sensor/test/framegrabber/test1394TwoResetBus.cpp b/modules/sensor/test/framegrabber/test1394TwoResetBus.cpp index 59924dcbf7..eaacbe8989 100644 --- a/modules/sensor/test/framegrabber/test1394TwoResetBus.cpp +++ b/modules/sensor/test/framegrabber/test1394TwoResetBus.cpp @@ -30,14 +30,12 @@ * * Description: * Firewire cameras video capture. - * -*****************************************************************************/ + */ /*! \file test1394TwoResetBus.cpp \brief Resets the IEEE1394 bus using libdc1394-2.x library. - */ #include @@ -45,6 +43,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #if defined(VISP_HAVE_DC1394) #include @@ -61,7 +63,6 @@ is if a program shuts down uncleanly and needs to free leftover ISO channels or bandwidth. A bus reset will free those things as a side effect. - */ int main() { @@ -75,21 +76,16 @@ int main() g.acquire(I); // std::cout << "write /tmp/test.pgm" << std::endl; // vpImageIo::write(I, "/tmp/test.pgm"); - } catch (...) { + } + catch (...) { vpCERROR << "Failure: exit" << std::endl; } } #else int main() { - vpTRACE("Ieee 1394 grabber capabilities are not available...\n" - "You should install libdc1394-2 to use this binary."); + vpTRACE("Ieee 1394 grabber capabilities are not available..."); + vpTRACE("You should install libdc1394-2 to use this binary."); } #endif - -/* - * Local variables: - * c-basic-offset: 2 - * End: - */ diff --git a/modules/sensor/test/framegrabber/testPylonGrabber.cpp b/modules/sensor/test/framegrabber/testPylonGrabber.cpp index d47bac33d6..569d189928 100644 --- a/modules/sensor/test/framegrabber/testPylonGrabber.cpp +++ b/modules/sensor/test/framegrabber/testPylonGrabber.cpp @@ -58,6 +58,9 @@ */ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::cout << "Basler camera test with Pylon in progress..." << std::endl; @@ -121,17 +124,23 @@ int main() filename = outputpath + "/imagetest2.pgm"; std::cout << "Write image: " << filename << std::endl; vpImageIo::write(I, filename); - } catch (const vpException &e) { + } + catch (const vpException &e) { vpCERROR << e.what() << std::endl; - } catch (const std::exception &e) { + } + catch (const std::exception &e) { vpCERROR << e.what() << std::endl; - } catch (...) { + } + catch (...) { vpCERROR << "Failure: exit" << std::endl; } } #else int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpTRACE("Basler Pylon grabber capabilities are not available...\n" "You should install pylon SDK to use this binary."); } diff --git a/modules/sensor/test/mocap/testMocapQualisys.cpp b/modules/sensor/test/mocap/testMocapQualisys.cpp index 4df6172314..599e879735 100644 --- a/modules/sensor/test/mocap/testMocapQualisys.cpp +++ b/modules/sensor/test/mocap/testMocapQualisys.cpp @@ -49,6 +49,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool g_quit = false; /*! diff --git a/modules/sensor/test/mocap/testMocapVicon.cpp b/modules/sensor/test/mocap/testMocapVicon.cpp index 0c8c3a8830..614e270424 100644 --- a/modules/sensor/test/mocap/testMocapVicon.cpp +++ b/modules/sensor/test/mocap/testMocapVicon.cpp @@ -51,6 +51,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool g_quit = false; /*! diff --git a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp index 5cb41fd510..7a9d40b793 100644 --- a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp +++ b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_images.cpp @@ -53,6 +53,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { double t; unsigned int display_scale = 1; diff --git a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp index 57f4f386b1..cd7eb66bfa 100644 --- a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp +++ b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_imu.cpp @@ -50,6 +50,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { double initial_ts, ts; vpOccipitalStructure sc; diff --git a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp index f8cfad120e..2bd8ff8efc 100644 --- a/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp +++ b/modules/sensor/test/rgb-depth/testOccipitalStructure_Core_pcl.cpp @@ -55,6 +55,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { unsigned int display_scale = 1; vpOccipitalStructure sc; diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp index a6e6ef61f8..cbd0b7848c 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435.cpp @@ -52,6 +52,9 @@ int main(int argc, char *argv[]) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif bool show_info = false; for (int i = 1; i < argc; i++) { diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp index 866839352a..9c85d173b4 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_align.cpp @@ -50,6 +50,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void createDepthHist(std::vector &histogram2, const pcl::PointCloud::Ptr &pointcloud, diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp index 40c5f3e4d4..ee66c39441 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_opencv.cpp @@ -155,6 +155,9 @@ void frame_to_mat(const rs2::frame &f, cv::Mat &img) int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif const int width = 640, height = 480, fps = 60; vpRealSense2 rs; rs2::config config; diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp index 85a54d5fbf..f934a202ac 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp @@ -54,6 +54,9 @@ int main(int argc, char *argv[]) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif bool opt_pcl_color = false; bool opt_show_infrared2 = false; bool display_helper = false; diff --git a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp index 961b7c9d2e..73911e5884 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp @@ -62,6 +62,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION) diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp index a72de4d844..35f90ba403 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_images.cpp @@ -51,6 +51,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { double ts; unsigned int display_scale = 2; 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 ab7ec4d130..91f62efa5f 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp @@ -54,6 +54,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpHomogeneousMatrix cMw, cMw_0; vpHomogeneousMatrix cextMw(0, 0, 2, 0, 0, 0); // External camera view for pose visualization vpColVector odo_vel, odo_acc, imu_acc, imu_vel; 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 77a54db24f..19cad8c1ef 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 @@ -55,6 +55,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpHomogeneousMatrix cMw, cMw_0; vpHomogeneousMatrix cextMw(0, 0, 2, 0, 0, 0); // External camera view for pose visualization. vpColVector odo_vel, odo_acc, imu_acc, imu_vel; diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp index a16868d488..104b458484 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_imu.cpp @@ -51,6 +51,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpColVector imu_acc, imu_vel; try { diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp index ec2ad878ba..4f71c7bcfe 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_odometry.cpp @@ -51,6 +51,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpHomogeneousMatrix cMw, cMw_0; vpHomogeneousMatrix cextMw(0, 0, 2, 0, 0, 0); // External camera view for pose visualization unsigned int confidence; diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp index 27210cc8e0..1a47dcd07d 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_undistort.cpp @@ -53,6 +53,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { vpCameraParameters cam_left; unsigned int display_scale = 2; diff --git a/modules/tracker/blob/include/visp3/blob/vpDot.h b/modules/tracker/blob/include/visp3/blob/vpDot.h index fb76621f56..5521783908 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot.h @@ -58,6 +58,8 @@ #pragma comment(linker, "/STACK:256000000") // Increase max recursion depth #endif +BEGIN_VISP_NAMESPACE + /*! * \class vpDot * @@ -107,7 +109,7 @@ * \endcode * * \sa vpDot2 - */ +*/ class VISP_EXPORT vpDot : public vpTracker { public: @@ -414,4 +416,5 @@ class VISP_EXPORT vpDot : public vpTracker vpColor color = vpColor::red, unsigned int thickness = 1); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/blob/include/visp3/blob/vpDot2.h b/modules/tracker/blob/include/visp3/blob/vpDot2.h index f8bbbdaf8e..24bb21bec7 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot2.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot2.h @@ -42,6 +42,7 @@ #define vpDot2_hh #include +#include #include #include #include @@ -51,6 +52,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpDot2 * @@ -119,7 +122,7 @@ * \ref tutorial-tracking-blob, section \ref tracking_blob_tracking. * * \sa vpDot - */ +*/ class VISP_EXPORT vpDot2 : public vpTracker { public: @@ -534,4 +537,5 @@ class VISP_EXPORT vpDot2 : public vpTracker }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/blob/src/dots/vpDot.cpp b/modules/tracker/blob/src/dots/vpDot.cpp index c87d4949d7..e641088202 100644 --- a/modules/tracker/blob/src/dots/vpDot.cpp +++ b/modules/tracker/blob/src/dots/vpDot.cpp @@ -48,6 +48,8 @@ #include +BEGIN_VISP_NAMESPACE + /* \class vpDot \brief Track a white dot @@ -947,3 +949,5 @@ void vpDot::display(const vpImage &I, const vpImagePoint &cog, const std documentation) to the stream \e os, and returns a reference to the stream. */ VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpDot &d) { return (os << "(" << d.getCog() << ")"); }; + +END_VISP_NAMESPACE diff --git a/modules/tracker/blob/src/dots/vpDot2.cpp b/modules/tracker/blob/src/dots/vpDot2.cpp index d4118dcc55..8098cb65ff 100644 --- a/modules/tracker/blob/src/dots/vpDot2.cpp +++ b/modules/tracker/blob/src/dots/vpDot2.cpp @@ -54,6 +54,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /****************************************************************************** * * CONSTRUCTORS AND DESTRUCTORS @@ -2357,16 +2359,20 @@ vpMatrix vpDot2::defineDots(vpDot2 dot[], const unsigned int &n, const std::stri vpDisplay::flush(I); // check that dots are far away ones from the other - for (i = 0; ((i < n) && fromFile); ++i) { + i = 0; + while ((i < n) && fromFile) { double d = sqrt(vpMath::sqr(dot[i].getHeight()) + vpMath::sqr(dot[i].getWidth())); - for (unsigned int j = 0; ((j < n) && fromFile); ++j) { + unsigned int j = 0; + while ((j < n) && fromFile) { if (j != i) { if (dot[i].getDistance(dot[j]) < d) { fromFile = false; std::cout << "Dots from file seem incoherent" << std::endl; } } + ++j; } + ++i; } } @@ -2506,3 +2512,5 @@ void vpDot2::display(const vpImage &I, const vpImagePoint &cog, const st documentation) to the stream \e os, and returns a reference to the stream. */ VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpDot2 &d) { return (os << "(" << d.getCog() << ")"); } + +END_VISP_NAMESPACE diff --git a/modules/tracker/blob/test/tracking-with-dataset/testTrackDot.cpp b/modules/tracker/blob/test/tracking-with-dataset/testTrackDot.cpp index ff04770ebb..443658b5c1 100644 --- a/modules/tracker/blob/test/tracking-with-dataset/testTrackDot.cpp +++ b/modules/tracker/blob/test/tracking-with-dataset/testTrackDot.cpp @@ -64,6 +64,10 @@ // List of allowed command line options #define GETOPTARGS "cdi:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool getOptions(int argc, const char **argv, std::string &ipath, bool &click_allowed, bool &display); void usage(const char *name, const char *badparam, std::string ipath); @@ -205,8 +209,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; } } @@ -215,9 +219,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath); 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; } @@ -237,11 +241,12 @@ int main(int argc, const char **argv) vpCTRACE << "Load: " << filename << std::endl; vpImageIo::read(I, filename); - } catch (...) { + } + catch (...) { std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot read " << filename << std::endl; std::cerr << " Check your -i " << ipath << " option " << std::endl - << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; + << " or VISP_INPUT_IMAGE_PATH environment variable." << std::endl; return EXIT_FAILURE; } @@ -276,7 +281,8 @@ int main(int argc, const char **argv) dot.initTracking(I, ip); if (opt_display) { dot.setGraphics(true); - } else { + } + else { dot.setGraphics(false); } dot.setComputeMoments(true); @@ -299,7 +305,8 @@ int main(int argc, const char **argv) } } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; return EXIT_FAILURE; } diff --git a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h index 7f1d4f9a33..d8f27c9b8a 100644 --- a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h +++ b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h @@ -51,6 +51,7 @@ #include +BEGIN_VISP_NAMESPACE /** * \class vpMegaPoseEstimate * \ingroup module_dnn_tracker @@ -132,7 +133,7 @@ inline void from_json(const nlohmann::json &j, vpMegaPoseEstimate &m) * For more information on how the model works, see The MegaPose Github page or the paper \cite Labbe2022Megapose. * * For instructions on how to install the Python server and an example usage, see \ref tutorial-tracking-megapose. - */ +*/ class VISP_EXPORT vpMegaPose { public: @@ -245,6 +246,6 @@ class VISP_EXPORT vpMegaPose static vpMegaPose::ServerMessage stringToMessage(const std::string &s); }; +END_VISP_NAMESPACE #endif // VISP_HAVE_NLOHMANN_JSON - #endif diff --git a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h index 5dc6026b89..7dd8a783cf 100644 --- a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h +++ b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h @@ -43,6 +43,7 @@ #include #include +BEGIN_VISP_NAMESPACE /** * \class vpMegaPoseTracker * \ingroup module_dnn_tracker @@ -94,7 +95,7 @@ * } * \endcode * For a more detailed usage see \ref tutorial-tracking-megapose. - */ +*/ class VISP_EXPORT vpMegaPoseTracker { public: @@ -119,7 +120,7 @@ class VISP_EXPORT vpMegaPoseTracker * @param[in] bb : The bounding box of the object. * @return A future object that will contain the result of the pose estimation. */ - std::future init(const vpImage &I, const vpRect & bb); + std::future init(const vpImage &I, const vpRect &bb); /** * @brief Initialize tracking from an initial pose. The initial pose should be in the neighborhood of the true pose. * The pose should be expressed in the camera frame. @@ -146,7 +147,7 @@ class VISP_EXPORT vpMegaPoseTracker * * @param[in] cTo : The new pose estimate. */ - void updatePose(const vpHomogeneousMatrix& cTo); + void updatePose(const vpHomogeneousMatrix &cTo); private: std::shared_ptr m_megapose; @@ -155,7 +156,7 @@ class VISP_EXPORT vpMegaPoseTracker int m_refinerIterations; bool m_initialized; }; - +END_VISP_NAMESPACE #endif // VISP_HAVE_NLOHMANN_JSON #endif diff --git a/modules/tracker/dnn/src/vpMegaPose.cpp b/modules/tracker/dnn/src/vpMegaPose.cpp index beb4685fdc..be446638e8 100644 --- a/modules/tracker/dnn/src/vpMegaPose.cpp +++ b/modules/tracker/dnn/src/vpMegaPose.cpp @@ -55,6 +55,8 @@ #include using json = nlohmann::json; //! json namespace shortcut +BEGIN_VISP_NAMESPACE + //// Network message utils /*Encode elements to a buffer of bytes*/ @@ -392,7 +394,7 @@ vpMegaPose::vpMegaPose(const std::string &host, int port, const vpCameraParamete throw vpException(vpException::ioError, "Could not connect to server at " + host + ":" + std::to_string(port)); } setIntrinsics(cam, height, width); - } +} vpMegaPose::~vpMegaPose() { @@ -615,7 +617,7 @@ std::vector vpMegaPose::getObjectNames() std::vector result = jsonValue; return result; } - +END_VISP_NAMESPACE #else // Work around to avoid libvisp_dnn_tracker library empty when threads are not used diff --git a/modules/tracker/dnn/src/vpMegaPoseTracker.cpp b/modules/tracker/dnn/src/vpMegaPoseTracker.cpp index 2edca7407d..968eea70fb 100644 --- a/modules/tracker/dnn/src/vpMegaPoseTracker.cpp +++ b/modules/tracker/dnn/src/vpMegaPoseTracker.cpp @@ -40,11 +40,12 @@ #include #include +BEGIN_VISP_NAMESPACE std::future vpMegaPoseTracker::init(const vpImage &I, const vpRect &bb) { return std::async(std::launch::async, [&I, &bb, this]() -> vpMegaPoseEstimate { - std::vector bbs = {bb}; - m_poseEstimate = m_megapose->estimatePoses(I, {m_objectLabel}, nullptr, 0.0, &bbs, nullptr)[0]; + std::vector bbs = { bb }; + m_poseEstimate = m_megapose->estimatePoses(I, { m_objectLabel }, nullptr, 0.0, &bbs, nullptr)[0]; m_initialized = true; return m_poseEstimate; }); @@ -65,8 +66,8 @@ std::future vpMegaPoseTracker::track(const vpImage & throw vpException(vpException::notInitialized, "MegaPose tracker was not initialized. Call init before calling track."); } return std::async(std::launch::async, [&I, this]() -> vpMegaPoseEstimate { - std::vector poses = {m_poseEstimate.cTo}; - m_poseEstimate = m_megapose->estimatePoses(I, {m_objectLabel}, nullptr, 0.0, nullptr, &poses, m_refinerIterations)[0]; + std::vector poses = { m_poseEstimate.cTo }; + m_poseEstimate = m_megapose->estimatePoses(I, { m_objectLabel }, nullptr, 0.0, nullptr, &poses, m_refinerIterations)[0]; return m_poseEstimate; }); } @@ -75,9 +76,9 @@ void vpMegaPoseTracker::updatePose(const vpHomogeneousMatrix &cTo) { m_poseEstimate.cTo = cTo; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_dnn_tracker.a(vpMegaPoseTracker.cpp.o) has no symbols -void dummy_vpMegaPoseTracker(){}; +void dummy_vpMegaPoseTracker() { }; #endif diff --git a/modules/tracker/klt/include/visp3/klt/vpKltOpencv.h b/modules/tracker/klt/include/visp3/klt/vpKltOpencv.h index 45e4dcc6a1..a4103e542b 100644 --- a/modules/tracker/klt/include/visp3/klt/vpKltOpencv.h +++ b/modules/tracker/klt/include/visp3/klt/vpKltOpencv.h @@ -52,6 +52,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpKltOpencv * @@ -68,7 +69,7 @@ * \include tutorial-klt-tracker.cpp * * A line by line explanation is provided in \ref tutorial-tracking-keypoint. - */ +*/ class VISP_EXPORT vpKltOpencv { public: @@ -400,6 +401,6 @@ class VISP_EXPORT vpKltOpencv long m_next_points_id; //!< Id for the newt keypoint bool m_initial_guess; //!< true when initial guess is provided }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/tracker/klt/src/vpKltOpencv.cpp b/modules/tracker/klt/src/vpKltOpencv.cpp index 6f74012751..9f137744d2 100644 --- a/modules/tracker/klt/src/vpKltOpencv.cpp +++ b/modules/tracker/klt/src/vpKltOpencv.cpp @@ -49,6 +49,7 @@ #include #include +BEGIN_VISP_NAMESPACE 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), @@ -321,7 +322,7 @@ void vpKltOpencv::suppressFeature(const int &index) m_points[1].erase(m_points[1].begin() + index); m_points_id.erase(m_points_id.begin() + index); } - +END_VISP_NAMESPACE #else // Work around to avoid visp_klt library empty when OpenCV is not installed or used diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthDenseTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthDenseTracker.h index c50db5f04d..e78feb3d07 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthDenseTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthDenseTracker.h @@ -34,6 +34,7 @@ #ifndef _vpMbDepthDenseTracker_h_ #define _vpMbDepthDenseTracker_h_ +#include #include #include #include @@ -43,6 +44,7 @@ #include #endif +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpMbDepthDenseTracker : public virtual vpMbTracker { public: @@ -170,4 +172,5 @@ class VISP_EXPORT vpMbDepthDenseTracker : public virtual vpMbTracker void segmentPointCloud(const std::vector &point_cloud, unsigned int width, unsigned int height); void segmentPointCloud(const vpMatrix &point_cloud, unsigned int width, unsigned int height); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h index cbced0aaaf..8871e3d9c6 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h @@ -43,6 +43,7 @@ #include #endif +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpMbDepthNormalTracker : public virtual vpMbTracker { public: @@ -185,4 +186,5 @@ class VISP_EXPORT vpMbDepthNormalTracker : public virtual vpMbTracker void segmentPointCloud(const std::vector &point_cloud, unsigned int width, unsigned int height); void segmentPointCloud(const vpMatrix &point_cloud, unsigned int width, unsigned int height); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h index e2c0508b4e..4a0f0f1178 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeKltTracker.h @@ -52,6 +52,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpMbEdgeKltTracker * \ingroup group_mbt_trackers @@ -202,7 +203,7 @@ * return 0; * } * \endcode - */ +*/ class VISP_EXPORT vpMbEdgeKltTracker : #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) public vpMbKltTracker, @@ -350,7 +351,7 @@ class VISP_EXPORT vpMbEdgeKltTracker : void trackSecondLoop(const vpImage &I, vpMatrix &L, vpColVector &_error, const vpHomogeneousMatrix &cMo, unsigned int lvl = 0); }; - +END_VISP_NAMESPACE #endif #endif // VISP_HAVE_OPENCV diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h index 866a3fdb36..bd80dc5f42 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbEdgeTracker.h @@ -39,6 +39,7 @@ #ifndef vpMbEdgeTracker_HH #define vpMbEdgeTracker_HH +#include #include #include #include @@ -73,6 +74,8 @@ #include #endif +BEGIN_VISP_NAMESPACE + /*! * \class vpMbEdgeTracker * \ingroup group_mbt_trackers @@ -233,7 +236,7 @@ * return 0; * } $ \endcode - */ +*/ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker { protected: @@ -518,5 +521,5 @@ class VISP_EXPORT vpMbEdgeTracker : public virtual vpMbTracker void visibleFace(const vpImage &_I, const vpHomogeneousMatrix &_cMo, bool &newvisibleline); //@} }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h index 2a20a2b9a3..5ff490bebc 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h @@ -50,6 +50,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! * \class vpMbGenericTracker * \ingroup group_mbt_trackers @@ -195,7 +196,7 @@ * "version": "1.0" * } * \endcode - */ +*/ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker { public: @@ -866,7 +867,7 @@ NLOHMANN_JSON_SERIALIZE_ENUM(vpMbGenericTracker::vpTrackerType, { {vpMbGenericTracker::EDGE_TRACKER, "edge"}, {vpMbGenericTracker::DEPTH_DENSE_TRACKER, "depthDense"}, {vpMbGenericTracker::DEPTH_NORMAL_TRACKER, "depthNormal"} - }); +}); #endif /** @@ -1072,4 +1073,6 @@ inline void from_json(const nlohmann::json &j, vpMbGenericTracker::TrackerWrappe #endif +END_VISP_NAMESPACE + #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbHiddenFaces.h b/modules/tracker/mbt/include/visp3/mbt/vpMbHiddenFaces.h index 38c233e647..c034d91265 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbHiddenFaces.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbHiddenFaces.h @@ -31,11 +31,11 @@ * Generic model based tracker. This class declares the methods to implement * in order to have a model based tracker. */ -#pragma once #ifndef vpMbHiddenFaces_HH #define vpMbHiddenFaces_HH +#include #include #include #include @@ -49,10 +49,14 @@ #include #include +BEGIN_VISP_NAMESPACE template class vpMbHiddenFaces; +// Forward declaration to have the operator in the global namespace template void swap(vpMbHiddenFaces &first, vpMbHiddenFaces &second); +END_VISP_NAMESPACE +BEGIN_VISP_NAMESPACE /*! * \class vpMbHiddenFaces * @@ -60,7 +64,7 @@ template void swap(vpMbHiddenFaces &first, vpMb * trackers. * * \ingroup group_mbt_faces - */ +*/ template class vpMbHiddenFaces { private: @@ -938,6 +942,7 @@ bool vpMbHiddenFaces::isVisibleOgre(const vpTranslationVector &came return Lpol[index]->isvisible; } -#endif // VISP_HAVE_OGRE +#endif // VISP_HAVE_OGRE +END_VISP_NAMESPACE #endif // vpMbHiddenFaces diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbKltTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbKltTracker.h index bc9910aea2..a2d4415298 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbKltTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbKltTracker.h @@ -55,6 +55,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpMbKltTracker * \ingroup group_mbt_trackers @@ -201,7 +202,7 @@ * #endif * } * \endcode - */ +*/ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker { protected: @@ -472,6 +473,6 @@ class VISP_EXPORT vpMbKltTracker : public virtual vpMbTracker const vpHomogeneousMatrix &cdMo); //@} }; - +END_VISP_NAMESPACE #endif #endif // VISP_HAVE_OPENCV diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbScanLine.h b/modules/tracker/mbt/include/visp3/mbt/vpMbScanLine.h index 35f3b4b984..1151cbd322 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbScanLine.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbScanLine.h @@ -47,6 +47,7 @@ #include #include +#include #include #include #include @@ -61,13 +62,14 @@ #endif #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE /*! \class vpMbScanLine \ingroup group_mbt_faces - */ +*/ class VISP_EXPORT vpMbScanLine { public: @@ -80,8 +82,9 @@ class VISP_EXPORT vpMbScanLine typedef std::pair vpMbScanLineEdge; //! Structure to define a scanline intersection. - struct vpMbScanLineSegment { - vpMbScanLineSegment() : type(START), edge(), p(0), P1(0), P2(0), Z1(0), Z2(0), ID(0), b_sample_Y(false) {} + struct vpMbScanLineSegment + { + vpMbScanLineSegment() : type(START), edge(), p(0), P1(0), P2(0), Z1(0), Z2(0), ID(0), b_sample_Y(false) { } vpMbScanLineType type; vpMbScanLineEdge edge; double p; // This value can be either x or y-coordinate value depending if @@ -93,7 +96,8 @@ class VISP_EXPORT vpMbScanLine }; //! vpMbScanLineEdge Comparator. - struct vpMbScanLineEdgeComparator { + struct vpMbScanLineEdgeComparator + { inline bool operator()(const vpMbScanLineEdge &l0, const vpMbScanLineEdge &l1) const { for (unsigned int i = 0; i < 3; ++i) @@ -111,7 +115,8 @@ class VISP_EXPORT vpMbScanLine }; //! vpMbScanLineSegment Comparators. - struct vpMbScanLineSegmentComparator { + struct vpMbScanLineSegmentComparator + { inline bool operator()(const vpMbScanLineSegment &a, const vpMbScanLineSegment &b) const { // return a.p == b.p ? a.type < b.type : a.p < b.p; @@ -197,7 +202,7 @@ class VISP_EXPORT vpMbScanLine static vpPoint mix(const vpPoint &a, const vpPoint &b, double alpha); static double norm(const vpPoint &a, const vpPoint &b); }; - +END_VISP_NAMESPACE #endif // doxygen should skip this #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbTracker.h index 7d21b1216f..c9aa1ef66c 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbTracker.h @@ -49,6 +49,7 @@ #include #include +#include #include #include #include @@ -79,6 +80,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! \class vpMbTracker \ingroup group_mbt_trackers @@ -914,5 +916,5 @@ class VISP_EXPORT vpMbTracker bool samePoint(const vpPoint &P1, const vpPoint &P2) const; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCircle.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCircle.h index 1a2ed07bfe..0a7a318131 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCircle.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCircle.h @@ -41,6 +41,7 @@ #ifndef vpMbtDistanceCircle_HH #define vpMbtDistanceCircle_HH +#include #include #include #include @@ -48,6 +49,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpMbtDistanceCircle @@ -249,5 +251,5 @@ class VISP_EXPORT vpMbtDistanceCircle private: void project(const vpHomogeneousMatrix &cMo); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCylinder.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCylinder.h index 0e8787b932..5d61fd88ad 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCylinder.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceCylinder.h @@ -46,6 +46,7 @@ #define vpMbtDistanceCylinder_HH #include +#include #include #include #include @@ -54,6 +55,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpMbtDistanceCylinder @@ -281,5 +283,5 @@ class VISP_EXPORT vpMbtDistanceCylinder private: void project(const vpHomogeneousMatrix &cMo); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltCylinder.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltCylinder.h index f8ac56233c..983182afc6 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltCylinder.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltCylinder.h @@ -52,6 +52,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpMbtDistanceKltCylinder @@ -212,7 +213,7 @@ class VISP_EXPORT vpMbtDistanceKltCylinder void updateMask(cv::Mat &mask, unsigned char _nb = 255, unsigned int _shiftBorder = 0); }; - +END_VISP_NAMESPACE #endif #endif // VISP_HAVE_OPENCV diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltPoints.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltPoints.h index 16c69ae071..a64e753096 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltPoints.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceKltPoints.h @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpMbtDistanceKltPoints @@ -212,7 +213,7 @@ class VISP_EXPORT vpMbtDistanceKltPoints void updateMask(cv::Mat &mask, unsigned char _nb = 255, unsigned int _shiftBorder = 0); }; - +END_VISP_NAMESPACE #endif #endif // VISP_HAVE_OPENCV diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceLine.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceLine.h index ac64ea07dc..e8c385ef7e 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceLine.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtDistanceLine.h @@ -44,6 +44,7 @@ #ifndef vpMbtDistanceLine_HH #define vpMbtDistanceLine_HH +#include #include #include #include @@ -54,6 +55,7 @@ #include +BEGIN_VISP_NAMESPACE /*! \class vpMbtDistanceLine @@ -61,7 +63,7 @@ \ingroup group_mbt_features - */ +*/ class VISP_EXPORT vpMbtDistanceLine { private: @@ -266,5 +268,5 @@ class VISP_EXPORT vpMbtDistanceLine private: void project(const vpHomogeneousMatrix &cMo); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h index 68ec8f5dad..be98c30cba 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h @@ -50,6 +50,7 @@ #define DEBUG_DISPLAY_DEPTH_DENSE 0 +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpMbtFaceDepthDense { public: @@ -239,4 +240,5 @@ class VISP_EXPORT vpMbtFaceDepthDense bool samePoint(const vpPoint &P1, const vpPoint &P2) const; }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h index 6efddf40a6..9ed05fb77b 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h @@ -50,6 +50,7 @@ #define DEBUG_DISPLAY_DEPTH_NORMAL 0 +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpMbtFaceDepthNormal { public: @@ -312,19 +313,20 @@ class VISP_EXPORT vpMbtFaceDepthNormal bool samePoint(const vpPoint &P1, const vpPoint &P2) const; }; +END_VISP_NAMESPACE #ifdef VISP_HAVE_NLOHMANN_JSON #include #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_PCL_SEGMENTATION) && defined(VISP_HAVE_PCL_FILTERS) -NLOHMANN_JSON_SERIALIZE_ENUM(vpMbtFaceDepthNormal::vpFeatureEstimationType, { - {vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION, "robust"}, - {vpMbtFaceDepthNormal::ROBUST_SVD_PLANE_ESTIMATION, "robustSVD"}, - {vpMbtFaceDepthNormal::PCL_PLANE_ESTIMATION, "pcl"} +NLOHMANN_JSON_SERIALIZE_ENUM(VISP_NAMESPACE_ADDRESSING vpMbtFaceDepthNormal::vpFeatureEstimationType, { + {VISP_NAMESPACE_ADDRESSING vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION, "robust"}, + {VISP_NAMESPACE_ADDRESSING vpMbtFaceDepthNormal::ROBUST_SVD_PLANE_ESTIMATION, "robustSVD"}, + {VISP_NAMESPACE_ADDRESSING vpMbtFaceDepthNormal::PCL_PLANE_ESTIMATION, "pcl"} }); #else -NLOHMANN_JSON_SERIALIZE_ENUM(vpMbtFaceDepthNormal::vpFeatureEstimationType, { - {vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION, "robust"}, - {vpMbtFaceDepthNormal::ROBUST_SVD_PLANE_ESTIMATION, "robustSVD"} +NLOHMANN_JSON_SERIALIZE_ENUM(VISP_NAMESPACE_ADDRESSING vpMbtFaceDepthNormal::vpFeatureEstimationType, { + {VISP_NAMESPACE_ADDRESSING vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION, "robust"}, + {VISP_NAMESPACE_ADDRESSING vpMbtFaceDepthNormal::ROBUST_SVD_PLANE_ESTIMATION, "robustSVD"} }); #endif #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h index 9d74be7618..0d22ae9013 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeEllipse.h @@ -42,17 +42,18 @@ #include #include +#include #include #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE /*! * \class vpMbtMeEllipse * \ingroup group_mbt_features * * \brief Class that tracks an ellipse moving edges with specific capabilities for * model-based tracking. - */ +*/ class VISP_EXPORT vpMbtMeEllipse : public vpMeEllipse { public: @@ -77,6 +78,6 @@ class VISP_EXPORT vpMbtMeEllipse : public vpMeEllipse void sample(const vpImage &I, bool doNotTrack = false) vp_override; void suppressPoints(); }; - +END_VISP_NAMESPACE #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeLine.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeLine.h index 16d22ae8cc..4b1b87335d 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtMeLine.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtMeLine.h @@ -39,17 +39,19 @@ #ifndef vpMbtMeLine_HH #define vpMbtMeLine_HH +#include #include #include #include #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE /*! * \class vpMbtMeLine * \brief Implementation of a line used by the model-based tracker. * \ingroup group_mbt_features - */ +*/ class VISP_EXPORT vpMbtMeLine : public vpMeTracker { private: @@ -119,7 +121,7 @@ class VISP_EXPORT vpMbtMeLine : public vpMeTracker void reSample(const vpImage &image, const vpImagePoint &ip1, const vpImagePoint &ip2); void updateDelta(); }; - +END_VISP_NAMESPACE #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtPolygon.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtPolygon.h index 7b26bbd01c..93d5c583bd 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtPolygon.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtPolygon.h @@ -39,6 +39,7 @@ #ifndef vpMbtPolygon_HH #define vpMbtPolygon_HH +#include #include #include #include @@ -46,6 +47,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * \class vpMbtPolygon * @@ -53,7 +55,7 @@ * tracker. * * \ingroup group_mbt_faces - */ +*/ class VISP_EXPORT vpMbtPolygon : public vpPolygon3D { public: @@ -155,5 +157,5 @@ class VISP_EXPORT vpMbtPolygon : public vpPolygon3D */ inline void setIsPolygonOriented(const bool &oriented) { this->hasOrientation = oriented; } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h index 166c90bdba..4ae601c1f8 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h @@ -37,10 +37,12 @@ #define _vpMbtTukeyEstimator_h_ #include +#include #include #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE template class vpMbtTukeyEstimator { public: @@ -57,6 +59,7 @@ template class vpMbtTukeyEstimator std::vector m_normres; std::vector m_residues; }; +END_VISP_NAMESPACE #endif //#ifndef DOXYGEN_SHOULD_SKIP_THIS /* @@ -111,7 +114,7 @@ template class vpMbtTukeyEstimator #ifndef DOXYGEN_SHOULD_SKIP_THIS #if HAVE_TRANSFORM -namespace + namespace { // Check if std:c++14 or higher #if ((__cplusplus >= 201402L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201402L))) @@ -125,6 +128,7 @@ template struct AbsDiff : public std::binary_function } // namespace #endif +BEGIN_VISP_NAMESPACE template class vpMbtTukeyEstimator; template class vpMbtTukeyEstimator; @@ -471,6 +475,7 @@ template void vpMbtTukeyEstimator::psiTukey(const T sig, std::vecto } } } +END_VISP_NAMESPACE #endif //#ifndef DOXYGEN_SHOULD_SKIP_THIS #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtXmlGenericParser.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtXmlGenericParser.h index e9de44f18e..e95014a1ad 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtXmlGenericParser.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtXmlGenericParser.h @@ -49,6 +49,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpMbtXmlGenericParser \brief Parse an Xml file to extract configuration parameters of a mbtConfig @@ -57,7 +58,7 @@ Data parser for the model-based tracker. - */ +*/ class VISP_EXPORT vpMbtXmlGenericParser { public: @@ -164,6 +165,6 @@ class VISP_EXPORT vpMbtXmlGenericParser class Impl; Impl *m_impl; }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp b/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp index 34cb7b6f7f..5bf0cfbb8e 100644 --- a/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp +++ b/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp @@ -52,6 +52,7 @@ #include #endif +BEGIN_VISP_NAMESPACE vpMbDepthDenseTracker::vpMbDepthDenseTracker() : m_depthDenseHiddenFacesDisplay(), m_depthDenseListOfActiveFaces(), m_denseDepthNbFeatures(0), m_depthDenseFaces(), m_depthDenseSamplingStepX(2), m_depthDenseSamplingStepY(2), m_error_depthDense(), m_L_depthDense(), @@ -824,3 +825,4 @@ void vpMbDepthDenseTracker::initCylinder(const vpPoint & /*p1*/, const vpPoint & void vpMbDepthDenseTracker::initFaceFromCorners(vpMbtPolygon &polygon) { addFace(polygon, false); } void vpMbDepthDenseTracker::initFaceFromLines(vpMbtPolygon &polygon) { addFace(polygon, true); } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp b/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp index 8281bc58cd..9f6612e75b 100644 --- a/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp +++ b/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp @@ -52,6 +52,7 @@ #include #endif +BEGIN_VISP_NAMESPACE vpMbDepthNormalTracker::vpMbDepthNormalTracker() : m_depthNormalFeatureEstimationMethod(vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION), m_depthNormalHiddenFacesDisplay(), m_depthNormalListOfActiveFaces(), m_depthNormalListOfDesiredFeatures(), @@ -902,3 +903,4 @@ void vpMbDepthNormalTracker::initCylinder(const vpPoint & /*p1*/, const vpPoint void vpMbDepthNormalTracker::initFaceFromCorners(vpMbtPolygon &polygon) { addFace(polygon, false); } void vpMbDepthNormalTracker::initFaceFromLines(vpMbtPolygon &polygon) { addFace(polygon, true); } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp index 62993ff533..40d50572a1 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp @@ -157,6 +157,7 @@ inline float64x2_t v_fma(const float64x2_t &a, const float64x2_t &b, const float } #endif // !USE_OPENCV_HAL && (USE_SSE || USE_NEON) +BEGIN_VISP_NAMESPACE vpMbtFaceDepthDense::vpMbtFaceDepthDense() : m_cam(), m_clippingFlag(vpPolygon3D::NO_CLIPPING), m_distFarClip(100), m_distNearClip(0.001), m_hiddenFace(nullptr), m_planeObject(), m_polygon(nullptr), m_useScanLine(false), @@ -1000,3 +1001,4 @@ void vpMbtFaceDepthDense::setScanLineVisibilityTest(bool v) (*it)->useScanLine = v; } } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp index ad726e3af1..4c9e75caec 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp @@ -55,6 +55,7 @@ #define USE_SSE 0 #endif +BEGIN_VISP_NAMESPACE vpMbtFaceDepthNormal::vpMbtFaceDepthNormal() : m_cam(), m_clippingFlag(vpPolygon3D::NO_CLIPPING), m_distFarClip(100), m_distNearClip(0.001), m_hiddenFace(nullptr), m_planeObject(), m_polygon(nullptr), m_useScanLine(false), m_faceActivated(false), @@ -1834,3 +1835,4 @@ void vpMbtFaceDepthNormal::setScanLineVisibilityTest(bool v) (*it)->useScanLine = v; } } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp b/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp index bcf3ac8c3d..039d1039bc 100644 --- a/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp +++ b/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp @@ -58,6 +58,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Basic constructor */ @@ -2984,3 +2985,4 @@ void vpMbEdgeTracker::setUseEdgeTracking(const std::string &name, const bool &us } } } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp index c0d6e8563a..8ef70deb48 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCircle.cpp @@ -52,6 +52,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Basic constructor */ @@ -477,3 +478,4 @@ void vpMbtDistanceCircle::computeInteractionMatrixError(const vpHomogeneousMatri } } } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp index 3213e9b607..359b8f3560 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceCylinder.cpp @@ -56,6 +56,7 @@ #include +BEGIN_VISP_NAMESPACE /*! Basic constructor */ @@ -877,3 +878,4 @@ void vpMbtDistanceCylinder::computeInteractionMatrixError(const vpHomogeneousMat } } } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp index 78ea9a7e93..167a725265 100644 --- a/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtDistanceLine.cpp @@ -48,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE void buildPlane(vpPoint &P, vpPoint &Q, vpPoint &R, vpPlane &plane); void buildLine(vpPoint &P1, vpPoint &P2, vpPoint &P3, vpPoint &P4, vpLine &L); @@ -927,3 +928,4 @@ bool vpMbtDistanceLine::closeToImageBorder(const vpImage &I, cons } return false; } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp b/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp index 2329446c52..ffe8b37113 100644 --- a/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtMeEllipse.cpp @@ -47,6 +47,7 @@ #include // std::fabs #include // numeric_limits +BEGIN_VISP_NAMESPACE /*! Basic constructor that calls the constructor of the class vpMeTracker. */ @@ -372,5 +373,5 @@ void vpMbtMeEllipse::suppressPoints() ++it; } } - +END_VISP_NAMESPACE #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp index cada111ec9..23bb3c7cb0 100644 --- a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE //! Normalize an angle between -Pi and Pi static void normalizeAngle(double &delta) { @@ -730,5 +731,5 @@ void vpMbtMeLine::bubbleSortJ() #endif m_meList.sort(sortByJ); } - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp b/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp index 7b6f892e39..c17bf847aa 100644 --- a/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp +++ b/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp @@ -43,6 +43,7 @@ #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) +BEGIN_VISP_NAMESPACE vpMbEdgeKltTracker::vpMbEdgeKltTracker() : m_thresholdKLT(2.), m_thresholdMBT(2.), m_maxIterKlt(30), m_w_mbt(), m_w_klt(), m_error_hybrid(), m_w_hybrid() { @@ -1490,7 +1491,7 @@ void vpMbEdgeKltTracker::reInitModel(const vpImage &I, const std: m_cMo = cMo; init(I); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_mbt.a(vpMbEdgeKltTracker.cpp.o) has // no symbols diff --git a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp index 44b4835cdc..7f7ba01789 100644 --- a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp +++ b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp @@ -45,6 +45,7 @@ #include // To detect OSX or IOS using TARGET_OS_IPHONE or TARGET_OS_IOS macro #endif +BEGIN_VISP_NAMESPACE namespace { /*! @@ -1459,7 +1460,7 @@ void vpMbKltTracker::setUseKltTracking(const std::string &name, const bool &useK } } } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_mbt.a(vpMbKltTracker.cpp.o) has no symbols void dummy_vpMbKltTracker() { }; diff --git a/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp b/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp index f3faf464de..b611bfc99c 100644 --- a/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp +++ b/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp @@ -47,6 +47,7 @@ #include // To detect OSX or IOS using TARGET_OS_IPHONE or TARGET_OS_IOS macro #endif +BEGIN_VISP_NAMESPACE /*! Basic constructor. @@ -681,6 +682,7 @@ double vpMbtDistanceKltCylinder::computeZ(const double &x, const double &y) return cylinder.computeZ(x, y); } +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: // libvisp_mbt.a(vpMbtDistanceKltCylinder.cpp.o) has no symbols diff --git a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp index 3ba95f9011..14db544add 100644 --- a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp +++ b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp @@ -47,6 +47,7 @@ #include // To detect OSX or IOS using TARGET_OS_IPHONE or TARGET_OS_IOS macro #endif +BEGIN_VISP_NAMESPACE /*! Basic constructor. @@ -652,7 +653,7 @@ std::vector > vpMbtDistanceKltPoints::getModelForDisplay(con return models; } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_mbt.a(vpMbtDistanceKltPoints.cpp.o) // has no symbols diff --git a/modules/tracker/mbt/src/vpMbGenericTracker.cpp b/modules/tracker/mbt/src/vpMbGenericTracker.cpp index 4e9665ffa9..61e4218109 100644 --- a/modules/tracker/mbt/src/vpMbGenericTracker.cpp +++ b/modules/tracker/mbt/src/vpMbGenericTracker.cpp @@ -46,6 +46,7 @@ using json = nlohmann::json; //! json namespace shortcut #endif +BEGIN_VISP_NAMESPACE vpMbGenericTracker::vpMbGenericTracker() : m_error(), m_L(), m_mapOfCameraTransformationMatrix(), m_mapOfFeatureFactors(), m_mapOfTrackers(), m_percentageGdPt(0.4), m_referenceCameraName("Camera"), m_thresholdOutlier(0.5), m_w(), m_weightedError(), @@ -7423,3 +7424,4 @@ void vpMbGenericTracker::TrackerWrapper::track(const vpImage *con } } #endif +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/vpMbScanLine.cpp b/modules/tracker/mbt/src/vpMbScanLine.cpp index e8c7b6275f..5975284ceb 100644 --- a/modules/tracker/mbt/src/vpMbScanLine.cpp +++ b/modules/tracker/mbt/src/vpMbScanLine.cpp @@ -57,7 +57,7 @@ #endif #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE vpMbScanLine::vpMbScanLine() : w(0), h(0), K(), maskBorder(0), mask(), primitive_ids(), visibility_samples(), depthTreshold(1e-06) #if defined(DEBUG_DISP) @@ -771,5 +771,5 @@ double vpMbScanLine::norm(const vpPoint &a, const vpPoint &b) return sqrt(vpMath::sqr(a.get_X() - b.get_X()) + vpMath::sqr(a.get_Y() - b.get_Y()) + vpMath::sqr(a.get_Z() - b.get_Z())); } - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/mbt/src/vpMbTracker.cpp b/modules/tracker/mbt/src/vpMbTracker.cpp index 7782cca57e..60218a3177 100644 --- a/modules/tracker/mbt/src/vpMbTracker.cpp +++ b/modules/tracker/mbt/src/vpMbTracker.cpp @@ -97,8 +97,8 @@ #include #endif +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS - namespace { #if defined(VISP_HAVE_THREADS) @@ -3874,3 +3874,4 @@ void vpMbTracker::setProjectionErrorKernelSize(const unsigned int &size) m_SobelY.resize(size * 2 + 1, size * 2 + 1, false, false); vpImageFilter::getSobelKernelY(m_SobelY.data, size); } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/vpMbtPolygon.cpp b/modules/tracker/mbt/src/vpMbtPolygon.cpp index 3950b3760c..26f8a7bf15 100644 --- a/modules/tracker/mbt/src/vpMbtPolygon.cpp +++ b/modules/tracker/mbt/src/vpMbtPolygon.cpp @@ -48,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Basic constructor. */ @@ -268,3 +269,4 @@ int main() \sa setMinLineLengthThresh(), setMinPolygonAreaThresh() */ void vpMbtPolygon::setLod(bool use_lod) { this->useLod = use_lod; } +END_VISP_NAMESPACE diff --git a/modules/tracker/mbt/src/vpMbtXmlGenericParser.cpp b/modules/tracker/mbt/src/vpMbtXmlGenericParser.cpp index faf8cee7a3..c3c83b9efa 100644 --- a/modules/tracker/mbt/src/vpMbtXmlGenericParser.cpp +++ b/modules/tracker/mbt/src/vpMbtXmlGenericParser.cpp @@ -43,6 +43,7 @@ #if defined(VISP_HAVE_PUGIXML) #include +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpMbtXmlGenericParser::Impl @@ -1916,7 +1917,7 @@ void vpMbtXmlGenericParser::setProjectionErrorKernelSize(const unsigned int &siz \param verbose : verbose flag */ void vpMbtXmlGenericParser::setVerbose(bool verbose) { m_impl->setVerbose(verbose); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpMbtXmlGenericParser.cpp.o) has no symbols void dummy_vpMbtXmlGenericParser() { }; diff --git a/modules/tracker/mbt/test/generic-with-dataset/perfGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/perfGenericTracker.cpp index 94c13ca1a5..a89da3b411 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/perfGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/perfGenericTracker.cpp @@ -49,6 +49,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { bool runBenchmark = false; diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp index cc551630d4..47d4a6cf99 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp @@ -64,6 +64,10 @@ #define GETOPTARGS "i:dsclt:e:DmCh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void usage(const char *name, const char *badparam) @@ -709,7 +713,7 @@ int main(int argc, const char *argv[]) "KLT module or OpenCV is not available.\nTest is not run." << std::endl; return EXIT_SUCCESS; - } + } #endif // Test if an input path is set @@ -742,7 +746,7 @@ int main(int argc, const char *argv[]) std::cout << "Test succeed" << std::endl; return EXIT_SUCCESS; - } +} catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerCAOParsing.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerCAOParsing.cpp index f0163bbcaf..6dbf3e7668 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerCAOParsing.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerCAOParsing.cpp @@ -43,6 +43,10 @@ #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + static std::string ipath = vpIoTools::getViSPImagesDataPath(); TEST_CASE("vpMbGenericTracker load CAO model Linux line ending", "[vpMbGenericTracker CAO parsing]") @@ -64,7 +68,7 @@ TEST_CASE("vpMbGenericTracker load CAO model Linux line ending", "[vpMbGenericTr TEST_CASE("vpMbGenericTracker load CAO model Windows line ending", "[vpMbGenericTracker CAO parsing]") { const std::string cao_filename = - vpIoTools::createFilePath(ipath, "mbt-cao/cylinder_cao_model_windows_line_ending.cao"); + vpIoTools::createFilePath(ipath, "mbt-cao/cylinder_cao_model_windows_line_ending.cao"); vpMbGenericTracker tracker; const bool verbose = true; REQUIRE_NOTHROW(tracker.loadModel(cao_filename, verbose)); diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp index d331aacc41..1f8626364b 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDepth.cpp @@ -61,6 +61,10 @@ #define GETOPTARGS "i:dcle:mCh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { void usage(const char *name, const char *badparam) diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp index 95334199c3..12c818da42 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp @@ -51,6 +51,10 @@ #include #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { bool read_data(int cpt, vpImage &I) diff --git a/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp b/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp index bdbdd80fcf..614488462b 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp @@ -49,6 +49,10 @@ using json = nlohmann::json; //! json namespace shortcut #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + vpMbGenericTracker baseTrackerConstructor() { const std::vector names = { "C1", "C2" }; @@ -158,7 +162,7 @@ SCENARIO("MBT JSON Serialization", "[json]") json j = loadJson(jsonPath); modify(j); saveJson(j, jsonPath); - }; + }; REQUIRE_NOTHROW(t1.saveConfigFile(jsonPath)); THEN("Reloading this tracker has the same basic properties") diff --git a/modules/tracker/mbt/test/generic-with-dataset/testMbtXmlGenericParser.cpp b/modules/tracker/mbt/test/generic-with-dataset/testMbtXmlGenericParser.cpp index c78650c1bd..ad109fa5dc 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testMbtXmlGenericParser.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testMbtXmlGenericParser.cpp @@ -44,6 +44,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if defined(VISP_HAVE_PUGIXML) && (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) std::string visp_images_dir = vpIoTools::getViSPImagesDataPath(); if (vpIoTools::checkDirectory(visp_images_dir + "/xml")) { @@ -156,7 +159,7 @@ int main() return EXIT_FAILURE; } } - } + } #elif !(defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; #elif !(defined(VISP_HAVE_PUGIXML)) @@ -165,4 +168,4 @@ int main() std::cout << "Test succeed" << std::endl; return EXIT_SUCCESS; -} + } diff --git a/modules/tracker/mbt/test/testTukeyEstimator.cpp b/modules/tracker/mbt/test/testTukeyEstimator.cpp index 6b9aa248fa..b6ad7c55e0 100644 --- a/modules/tracker/mbt/test/testTukeyEstimator.cpp +++ b/modules/tracker/mbt/test/testTukeyEstimator.cpp @@ -49,6 +49,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif size_t nb_elements = 1000; int nb_iterations = 100; double stdev = 0.5, mean = 0.0, noise_threshold = 1e-3; @@ -88,8 +91,8 @@ int main() for (size_t i = 0; i < weights.size(); i++) { if (!vpMath::equal(weights[i], weights_col[(unsigned int)i], noise_threshold)) { std::cerr << "Difference between vpRobust::TUKEY and " - "vpMbtTukeyEstimator (double)!" - << std::endl; + "vpMbtTukeyEstimator (double)!" + << std::endl; std::cerr << "weights_col[" << i << "]=" << weights_col[(unsigned int)i] << std::endl; std::cerr << "weights[" << i << "]=" << weights[i] << std::endl; return EXIT_FAILURE; @@ -128,8 +131,8 @@ int main() for (size_t i = 0; i < weights.size(); i++) { if (!vpMath::equal(weights[i], weights_col[(unsigned int)i], noise_threshold)) { std::cerr << "Difference between vpRobust::TUKEY and " - "vpMbtTukeyEstimator (float)!" - << std::endl; + "vpMbtTukeyEstimator (float)!" + << std::endl; std::cerr << "weights_col[" << i << "]=" << weights_col[(unsigned int)i] << std::endl; std::cerr << "weights[" << i << "]=" << weights[i] << std::endl; return EXIT_FAILURE; @@ -164,8 +167,8 @@ int main() for (size_t i = 0; i < weights.size(); i++) { if (!vpMath::equal(weights[(unsigned int)i], weights_col[(unsigned int)i], noise_threshold)) { std::cerr << "Difference between vpRobust::TUKEY and " - "vpMbtTukeyEstimator (float)!" - << std::endl; + "vpMbtTukeyEstimator (float)!" + << std::endl; std::cerr << "weights_col[" << i << "]=" << weights_col[(unsigned int)i] << std::endl; std::cerr << "weights[" << i << "]=" << weights[(unsigned int)i] << std::endl; return EXIT_FAILURE; diff --git a/modules/tracker/me/include/visp3/me/vpMe.h b/modules/tracker/me/include/visp3/me/vpMe.h index 6bc6e11a5b..ea7e606bd0 100644 --- a/modules/tracker/me/include/visp3/me/vpMe.h +++ b/modules/tracker/me/include/visp3/me/vpMe.h @@ -39,10 +39,16 @@ #ifndef _vpMe_h_ #define _vpMe_h_ +#include #include #include #include +#ifdef VISP_HAVE_NLOHMANN_JSON +#include +#endif + +BEGIN_VISP_NAMESPACE /*! * \class vpMe * \ingroup module_me @@ -119,7 +125,7 @@ * {"maskSign":0,"maskSize":5,"minSampleStep":4.0,"mu":[0.5,0.5],"nMask":180,"ntotalSample":0,"pointsToTrack":200, * "range":5,"sampleStep":10.0,"strip":2,"threshold":20.0,"thresholdMarginRatio":-1.0,"minThreshold":-1.0,"thresholdType":"normalized"} * \endcode - */ +*/ class VISP_EXPORT vpMe { public: @@ -578,9 +584,8 @@ class VISP_EXPORT vpMe friend void from_json(const nlohmann::json &j, vpMe &me); #endif }; -#ifdef VISP_HAVE_NLOHMANN_JSON -#include +#ifdef VISP_HAVE_NLOHMANN_JSON NLOHMANN_JSON_SERIALIZE_ENUM(vpMe::vpLikelihoodThresholdType, { {vpMe::vpLikelihoodThresholdType::OLD_THRESHOLD, "old"}, {vpMe::vpLikelihoodThresholdType::NORMALIZED_THRESHOLD, "normalized"} @@ -620,7 +625,7 @@ inline void from_json(const nlohmann::json &j, vpMe &me) assert((mus.size() == 2)); me.setMu1(mus[0]); me.setMu2(mus[1]); -} + } me.setMinSampleStep(j.value("minSampleStep", me.getMinSampleStep())); me.setSampleStep(j.value("sampleStep", me.getSampleStep())); me.setRange(j.value("range", me.getRange())); @@ -644,4 +649,5 @@ inline void from_json(const nlohmann::json &j, vpMe &me) #endif +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/me/include/visp3/me/vpMeEllipse.h b/modules/tracker/me/include/visp3/me/vpMeEllipse.h index c0cdab267f..a84b0c418f 100644 --- a/modules/tracker/me/include/visp3/me/vpMeEllipse.h +++ b/modules/tracker/me/include/visp3/me/vpMeEllipse.h @@ -53,6 +53,8 @@ #include #endif +BEGIN_VISP_NAMESPACE + /*! * \class vpMeEllipse * \ingroup module_me @@ -89,7 +91,7 @@ * * \include tutorial-me-ellipse-tracker.cpp * - */ +*/ class VISP_EXPORT vpMeEllipse : public vpMeTracker { public: @@ -589,4 +591,6 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker void updateTheta(); }; +END_VISP_NAMESPACE + #endif diff --git a/modules/tracker/me/include/visp3/me/vpMeLine.h b/modules/tracker/me/include/visp3/me/vpMeLine.h index c3a833ffe8..e8fe3fab0b 100644 --- a/modules/tracker/me/include/visp3/me/vpMeLine.h +++ b/modules/tracker/me/include/visp3/me/vpMeLine.h @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpMeLine * @@ -142,7 +143,7 @@ * * \note It is possible to display the line as an overlay. For that you * must use the display function of the class vpMeLine. - */ +*/ class VISP_EXPORT vpMeLine : public vpMeTracker { private: @@ -458,5 +459,5 @@ class VISP_EXPORT vpMeLine : public vpMeTracker const vpColor &color = vpColor::green, unsigned int thickness = 1); #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/me/include/visp3/me/vpMeNurbs.h b/modules/tracker/me/include/visp3/me/vpMeNurbs.h index de056e67f1..3fd4f40ea4 100644 --- a/modules/tracker/me/include/visp3/me/vpMeNurbs.h +++ b/modules/tracker/me/include/visp3/me/vpMeNurbs.h @@ -50,6 +50,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpMeNurbs * @@ -123,7 +124,7 @@ * setEnableCannyDetection to enable it. * * \warning : This function requires OpenCV. - */ +*/ class VISP_EXPORT vpMeNurbs : public vpMeTracker { #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS @@ -337,5 +338,5 @@ class VISP_EXPORT vpMeNurbs : public vpMeTracker */ static void display(const vpImage &I, vpNurbs &n, const vpColor &color = vpColor::green, unsigned int thickness = 1); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/me/include/visp3/me/vpMeSite.h b/modules/tracker/me/include/visp3/me/vpMeSite.h index 97e85dac9e..e92989c638 100644 --- a/modules/tracker/me/include/visp3/me/vpMeSite.h +++ b/modules/tracker/me/include/visp3/me/vpMeSite.h @@ -39,11 +39,14 @@ #ifndef _vpMeSite_h_ #define _vpMeSite_h_ +#include #include #include #include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpMeSite * \ingroup module_me @@ -60,7 +63,7 @@ * amongst all edges found. * * - sample step. - */ +*/ class VISP_EXPORT vpMeSite { public: @@ -392,4 +395,6 @@ class VISP_EXPORT vpMeSite vpMeSiteState m_state; //!< Site state }; +END_VISP_NAMESPACE + #endif diff --git a/modules/tracker/me/include/visp3/me/vpMeTracker.h b/modules/tracker/me/include/visp3/me/vpMeTracker.h index fb1a5620d8..c7281b85ed 100644 --- a/modules/tracker/me/include/visp3/me/vpMeTracker.h +++ b/modules/tracker/me/include/visp3/me/vpMeTracker.h @@ -48,6 +48,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpMeTracker * @@ -55,7 +57,7 @@ * \brief Contains abstract elements for a Distance to Feature type feature. * * 2D state = list of points, 3D state = feature - */ +*/ class VISP_EXPORT vpMeTracker : public vpTracker { public: @@ -323,4 +325,6 @@ class VISP_EXPORT vpMeTracker : public vpTracker }; +END_VISP_NAMESPACE + #endif diff --git a/modules/tracker/me/include/visp3/me/vpNurbs.h b/modules/tracker/me/include/visp3/me/vpNurbs.h index ee9fad05f7..d94cbe8d06 100644 --- a/modules/tracker/me/include/visp3/me/vpNurbs.h +++ b/modules/tracker/me/include/visp3/me/vpNurbs.h @@ -49,6 +49,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * \class vpNurbs * \ingroup module_me @@ -87,7 +88,7 @@ * * You can find much more information about the B-Splines and the * implementation of all the methods in the Nurbs Book. - */ +*/ class VISP_EXPORT vpNurbs : public vpBSpline { protected: @@ -523,5 +524,5 @@ class VISP_EXPORT vpNurbs : public vpBSpline */ void globalCurveApprox(unsigned int n); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/me/src/moving-edges/vpMe.cpp b/modules/tracker/me/src/moving-edges/vpMe.cpp index d89476ca58..e4d32d4773 100644 --- a/modules/tracker/me/src/moving-edges/vpMe.cpp +++ b/modules/tracker/me/src/moving-edges/vpMe.cpp @@ -41,6 +41,8 @@ #include #include +BEGIN_VISP_NAMESPACE + #ifndef DOXYGEN_SHOULD_SKIP_THIS namespace { @@ -195,15 +197,19 @@ static bool clipping(vpPoint2Dt A, vpPoint2Dt B, double Xmin, double Ymin, doubl if (code_P[0] != 0) { n = 0; // c'est P[0] qu'on clippera bit_i = 1; - for (i = 0; !(code_P[0] & bit_i); ++i) { + i = 0; + while (!(code_P[0] & bit_i)) { bit_i <<= 1; + ++i; } } else { n = 1; // c'est P[1] qu'on clippera bit_i = 1; - for (i = 0; !(code_P[1] & bit_i); ++i) { + i = 0; + while (!(code_P[1] & bit_i)) { bit_i <<= 1; + ++i; } } @@ -498,3 +504,5 @@ void vpMe::setMaskSize(const unsigned int &mask_size) m_mask_size = mask_size; initMask(); } + +END_VISP_NAMESPACE diff --git a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp index 46fbc3896a..a9bc841e99 100644 --- a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp @@ -40,6 +40,8 @@ #include #include +BEGIN_VISP_NAMESPACE + // --comment: define the VP_ME_ELLIPSE_REGULAR_SAMPLING flag #ifndef VP_ME_ELLIPSE_REGULAR_SAMPLING #define VP_ME_ELLIPSE_TWO_CONCENTRIC_CIRCLES @@ -1438,3 +1440,5 @@ void vpMeEllipse::displayEllipse(const vpImage &I, const vpImagePoint &c { vpDisplay::displayEllipse(I, center, A, B, E, smallalpha, highalpha, false, color, thickness, true, true); } + +END_VISP_NAMESPACE diff --git a/modules/tracker/me/src/moving-edges/vpMeLine.cpp b/modules/tracker/me/src/moving-edges/vpMeLine.cpp index 39e01e785f..acc7c8226c 100644 --- a/modules/tracker/me/src/moving-edges/vpMeLine.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeLine.cpp @@ -51,6 +51,7 @@ #define INCR_MIN 1 +BEGIN_VISP_NAMESPACE void computeDelta(double &delta, int i1, int j1, int i2, int j2); static void normalizeAngle(double &delta) @@ -1204,3 +1205,4 @@ void vpMeLine::displayLine(const vpImage &I, const vpMeSite &PExt1, cons ip1.set_j(PExt2.m_jfloat); vpDisplay::displayCross(I, ip1, 10, vpColor::green, thickness); } +END_VISP_NAMESPACE diff --git a/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp b/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp index 5b1f17bf5f..6dd895580a 100644 --- a/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeNurbs.cpp @@ -56,6 +56,7 @@ #include #endif +BEGIN_VISP_NAMESPACE double computeDelta(double deltai, double deltaj); void findAngle(const vpImage &I, const vpImagePoint &iP, vpMe *me, double &angle, double &convlt); vpImagePoint findFirstBorder(const vpImage &Isub, const vpImagePoint &iP); @@ -1094,3 +1095,4 @@ void vpMeNurbs::display(const vpImage &I, vpNurbs &n, const vpColor &col u += 0.01; } } +END_VISP_NAMESPACE diff --git a/modules/tracker/me/src/moving-edges/vpMeSite.cpp b/modules/tracker/me/src/moving-edges/vpMeSite.cpp index 913805f3ad..3b5abdbb23 100644 --- a/modules/tracker/me/src/moving-edges/vpMeSite.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeSite.cpp @@ -43,6 +43,8 @@ #include #include +BEGIN_VISP_NAMESPACE + #ifndef DOXYGEN_SHOULD_SKIP_THIS static bool horsImage(int i, int j, int half, int rows, int cols) { @@ -377,11 +379,6 @@ void vpMeSite::track(const vpImage &I, const vpMe *me, const bool int vpMeSite::operator!=(const vpMeSite &m) { return ((m.m_i != m_i) || (m.m_j != m_j)); } -VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpMeSite &vpMeS) -{ - return (os << "Alpha: " << vpMeS.m_alpha << " Convolution: " << vpMeS.m_convlt << " Weight: " << vpMeS.m_weight << " Threshold: " << vpMeS.m_contrastThreshold); -} - void vpMeSite::display(const vpImage &I) { vpMeSite::display(I, m_ifloat, m_jfloat, m_state); } void vpMeSite::display(const vpImage &I) { vpMeSite::display(I, m_ifloat, m_jfloat, m_state); } @@ -444,3 +441,10 @@ void vpMeSite::display(const vpImage &I, const double &i, const double & vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::yellow, 1); } } + +VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpMeSite &vpMeS) +{ + return (os << "Alpha: " << vpMeS.m_alpha << " Convolution: " << vpMeS.m_convlt << " Weight: " << vpMeS.m_weight << " Threshold: " << vpMeS.m_contrastThreshold); +} + +END_VISP_NAMESPACE diff --git a/modules/tracker/me/src/moving-edges/vpMeTracker.cpp b/modules/tracker/me/src/moving-edges/vpMeTracker.cpp index dcbc578560..d6695b4e3c 100644 --- a/modules/tracker/me/src/moving-edges/vpMeTracker.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeTracker.cpp @@ -44,6 +44,8 @@ #include #include +BEGIN_VISP_NAMESPACE + #define DEBUG_LEVEL1 0 #define DEBUG_LEVEL2 0 @@ -291,3 +293,5 @@ void vpMeTracker::display(const vpImage &I, vpColVector &w, unsig #undef DEBUG_LEVEL1 #undef DEBUG_LEVEL2 + +END_VISP_NAMESPACE diff --git a/modules/tracker/me/src/moving-edges/vpNurbs.cpp b/modules/tracker/me/src/moving-edges/vpNurbs.cpp index 3eac4dff37..ffd7d2664d 100644 --- a/modules/tracker/me/src/moving-edges/vpNurbs.cpp +++ b/modules/tracker/me/src/moving-edges/vpNurbs.cpp @@ -35,6 +35,8 @@ #include // numeric_limits #include #include + +BEGIN_VISP_NAMESPACE /* Compute the distance d = |Pw1-Pw2| */ @@ -745,3 +747,4 @@ void vpNurbs::globalCurveApprox(unsigned int n) { globalCurveApprox(crossingPoints, p, n, knots, controlPoints, weights); } +END_VISP_NAMESPACE diff --git a/modules/tracker/me/test/testJsonMe.cpp b/modules/tracker/me/test/testJsonMe.cpp index 18edc7d6ea..a6d3c6b54f 100644 --- a/modules/tracker/me/test/testJsonMe.cpp +++ b/modules/tracker/me/test/testJsonMe.cpp @@ -51,6 +51,10 @@ using json = nlohmann::json; //! json namespace shortcut #define CATCH_CONFIG_RUNNER #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + template void checkProperties(const T &t1, const T &t2, C fn, const std::string &message) { THEN(message) { REQUIRE((t1.*fn)() == (t2.*fn)()); } diff --git a/modules/tracker/me/test/testNurbs.cpp b/modules/tracker/me/test/testNurbs.cpp index 49e853206a..6fcbb26581 100644 --- a/modules/tracker/me/test/testNurbs.cpp +++ b/modules/tracker/me/test/testNurbs.cpp @@ -59,6 +59,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -292,7 +296,8 @@ int main(int argc, const char **argv) display[1].init(I2, 100, 100, "Points interpolation"); vpDisplay::display(I2); vpDisplay::flush(I2); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error while displaying the image"); return EXIT_FAILURE; } @@ -321,7 +326,8 @@ int main(int argc, const char **argv) display[2].init(I3, 100, 100, "Points approximation"); vpDisplay::display(I3); vpDisplay::flush(I3); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error while displaying the image"); return EXIT_FAILURE; } @@ -354,7 +360,8 @@ int main(int argc, const char **argv) } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -370,8 +377,8 @@ int main() int main() { std::cout << "This example requires a video device. " << std::endl - << "You should install X11, GTK, OpenCV, GDI or Direct3D" << std::endl - << "to be able to execute this example." << std::endl; + << "You should install X11, GTK, OpenCV, GDI or Direct3D" << std::endl + << "to be able to execute this example." << std::endl; return EXIT_SUCCESS; } #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTracker.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTracker.h index 68e1bb1902..b8560651d4 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTracker.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTracker.h @@ -46,11 +46,13 @@ #include +#include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTracker \ingroup group_tt_tracker @@ -146,17 +148,16 @@ class VISP_EXPORT vpTemplateTracker //! Default constructor. vpTemplateTracker() : nbLvlPyr(0), l0Pyr(0), pyrInitialised(false), ptTemplate(nullptr), ptTemplatePyr(nullptr), ptTemplateInit(false), - templateSize(0), templateSizePyr(nullptr), ptTemplateSelect(nullptr), ptTemplateSelectPyr(nullptr), - ptTemplateSelectInit(false), templateSelectSize(0), ptTemplateSupp(nullptr), ptTemplateSuppPyr(nullptr), - ptTemplateCompo(nullptr), ptTemplateCompoPyr(nullptr), zoneTracked(nullptr), zoneTrackedPyr(nullptr), pyr_IDes(nullptr), H(), - Hdesire(), HdesirePyr(nullptr), HLM(), HLMdesire(), HLMdesirePyr(nullptr), HLMdesireInverse(), - HLMdesireInversePyr(nullptr), G(), gain(0), thresholdGradient(0), costFunctionVerification(false), blur(false), - useBrent(false), nbIterBrent(0), taillef(0), fgG(nullptr), fgdG(nullptr), ratioPixelIn(0), mod_i(0), mod_j(0), - nbParam(), lambdaDep(0), iterationMax(0), iterationGlobale(0), diverge(false), nbIteration(0), - useCompositionnal(false), useInverse(false), Warp(nullptr), p(), dp(), X1(), X2(), dW(), BI(), dIx(), dIy(), - zoneRef_() - { - } + templateSize(0), templateSizePyr(nullptr), ptTemplateSelect(nullptr), ptTemplateSelectPyr(nullptr), + ptTemplateSelectInit(false), templateSelectSize(0), ptTemplateSupp(nullptr), ptTemplateSuppPyr(nullptr), + ptTemplateCompo(nullptr), ptTemplateCompoPyr(nullptr), zoneTracked(nullptr), zoneTrackedPyr(nullptr), pyr_IDes(nullptr), H(), + Hdesire(), HdesirePyr(nullptr), HLM(), HLMdesire(), HLMdesirePyr(nullptr), HLMdesireInverse(), + HLMdesireInversePyr(nullptr), G(), gain(0), thresholdGradient(0), costFunctionVerification(false), blur(false), + useBrent(false), nbIterBrent(0), taillef(0), fgG(nullptr), fgdG(nullptr), ratioPixelIn(0), mod_i(0), mod_j(0), + nbParam(), lambdaDep(0), iterationMax(0), iterationGlobale(0), diverge(false), nbIteration(0), + useCompositionnal(false), useInverse(false), Warp(nullptr), p(), dp(), X1(), X2(), dW(), BI(), dIx(), dIy(), + zoneRef_() + { } explicit vpTemplateTracker(vpTemplateTrackerWarp *_warp); virtual ~vpTemplateTracker(); @@ -232,7 +233,7 @@ class VISP_EXPORT vpTemplateTracker l0Pyr = level_to_stop; if (l0Pyr >= nlevels) { std::cout << "Warning: level_to_stop: " << level_to_stop << " higher than level_to_start: " << nlevels - 1 - << " (nlevels-1)" << std::endl; + << " (nlevels-1)" << std::endl; std::cout << "Level to stop put to: " << nlevels - 1 << std::endl; l0Pyr = nlevels - 1; } @@ -297,4 +298,5 @@ class VISP_EXPORT vpTemplateTracker virtual void trackNoPyr(const vpImage &I) = 0; virtual void trackPyr(const vpImage &I); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerBSpline.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerBSpline.h index 3e5ff70055..6e979fb440 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerBSpline.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerBSpline.h @@ -49,7 +49,7 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpTemplateTrackerBSpline { public: @@ -57,5 +57,6 @@ class VISP_EXPORT vpTemplateTrackerBSpline static double getSubPixBspline4(const vpImage &I, double r, double t); }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerHeader.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerHeader.h index 23ca9507b0..ffb50b49b2 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerHeader.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerHeader.h @@ -45,49 +45,56 @@ #define vpTemplateTrackerHeader_hh #include +#include +BEGIN_VISP_NAMESPACE /*! \struct vpTemplateTrackerZPoint \ingroup group_tt_tools */ -struct vpTemplateTrackerZPoint { +struct vpTemplateTrackerZPoint +{ int x, y; - vpTemplateTrackerZPoint() : x(0), y(0) {} + vpTemplateTrackerZPoint() : x(0), y(0) { } }; /*! \struct vpTemplateTrackerDPoint \ingroup group_tt_tools */ -struct vpTemplateTrackerDPoint { +struct vpTemplateTrackerDPoint +{ double x, y; - vpTemplateTrackerDPoint() : x(0), y(0) {} + vpTemplateTrackerDPoint() : x(0), y(0) { } }; /*! \struct vpTemplateTrackerPoint \ingroup group_tt_tools */ -struct vpTemplateTrackerPoint { +struct vpTemplateTrackerPoint +{ int x, y; double dx, dy; double val; double *dW; double *HiG; - vpTemplateTrackerPoint() : x(0), y(0), dx(0), dy(0), val(0), dW(nullptr), HiG(nullptr) {} + vpTemplateTrackerPoint() : x(0), y(0), dx(0), dy(0), val(0), dW(nullptr), HiG(nullptr) { } }; /*! \struct vpTemplateTrackerPointCompo \ingroup group_tt_tools */ -struct vpTemplateTrackerPointCompo { +struct vpTemplateTrackerPointCompo +{ double *dW; - vpTemplateTrackerPointCompo() : dW(nullptr) {} + vpTemplateTrackerPointCompo() : dW(nullptr) { } }; #ifndef DOXYGEN_SHOULD_SKIP_THIS -struct vpTemplateTrackerPointSuppMIInv { +struct vpTemplateTrackerPointSuppMIInv +{ double et; int ct; double *BtInit; @@ -97,9 +104,9 @@ struct vpTemplateTrackerPointSuppMIInv { double *d2Wx; double *d2Wy; vpTemplateTrackerPointSuppMIInv() : et(0), ct(0), BtInit(nullptr), Bt(nullptr), dBt(nullptr), d2W(nullptr), d2Wx(nullptr), d2Wy(nullptr) - { - } + { } }; #endif // DOXYGEN_SHOULD_SKIP_THIS +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSD.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSD.h index 5fb26ad185..bfbcfc1d0e 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSD.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSD.h @@ -46,6 +46,7 @@ #include +#include #include #include #include @@ -55,6 +56,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerSSD \ingroup group_tt_tracker @@ -77,5 +79,5 @@ class VISP_EXPORT vpTemplateTrackerSSD : public vpTemplateTracker double getSSD(const vpImage &I, const vpColVector &tp); void setGain(double g) { gain = g; } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDESM.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDESM.h index f0f722fe6f..77d5372ea1 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDESM.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDESM.h @@ -44,8 +44,10 @@ #ifndef vpTemplateTrackerSSDESM_hh #define vpTemplateTrackerSSDESM_hh +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerSSDESM \ingroup group_tt_tracker @@ -69,4 +71,5 @@ class VISP_EXPORT vpTemplateTrackerSSDESM : public vpTemplateTrackerSSD public: explicit vpTemplateTrackerSSDESM(vpTemplateTrackerWarp *warp); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDForwardAdditional.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDForwardAdditional.h index 3eedfae3e0..980d9338cd 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDForwardAdditional.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDForwardAdditional.h @@ -44,13 +44,15 @@ #ifndef vpTemplateTrackerSSDForwardAdditional_hh #define vpTemplateTrackerSSDForwardAdditional_hh +#include #include +BEGIN_VISP_NAMESPACE /*! \ingroup group_tt_tracker The algorithm implemented in this class is described in \cite Baker04a and \cite Marchand16a. - */ +*/ class VISP_EXPORT vpTemplateTrackerSSDForwardAdditional : public vpTemplateTrackerSSD { public: @@ -65,7 +67,7 @@ class VISP_EXPORT vpTemplateTrackerSSDForwardAdditional : public vpTemplateTrack vpMatrix KQuasiNewton; protected: - void initHessienDesired(const vpImage & /*I*/) {} + void initHessienDesired(const vpImage & /*I*/) { } void trackNoPyr(const vpImage &I); public: @@ -73,4 +75,5 @@ class VISP_EXPORT vpTemplateTrackerSSDForwardAdditional : public vpTemplateTrack void setMinimizationMethod(vpMinimizationTypeSSDForwardAdditional method) { minimizationMethod = method; } }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDForwardCompositional.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDForwardCompositional.h index 562788881c..8673fb0ea4 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDForwardCompositional.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDForwardCompositional.h @@ -44,13 +44,15 @@ #ifndef vpTemplateTrackerSSDForwardCompositional_hh #define vpTemplateTrackerSSDForwardCompositional_hh +#include #include +BEGIN_VISP_NAMESPACE /*! \ingroup group_tt_tracker The algorithm implemented in this class is described in \cite Baker04a and \cite Marchand16a. - */ +*/ class VISP_EXPORT vpTemplateTrackerSSDForwardCompositional : public vpTemplateTrackerSSD { protected: @@ -64,4 +66,5 @@ class VISP_EXPORT vpTemplateTrackerSSDForwardCompositional : public vpTemplateTr public: explicit vpTemplateTrackerSSDForwardCompositional(vpTemplateTrackerWarp *warp); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDInverseCompositional.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDInverseCompositional.h index 3c0dad8f42..667ec1ef65 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDInverseCompositional.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerSSDInverseCompositional.h @@ -45,13 +45,15 @@ #include +#include #include +BEGIN_VISP_NAMESPACE /*! \ingroup group_tt_tracker The algorithm implemented in this class is described in \cite Baker04a and \cite Marchand16a. - */ +*/ class VISP_EXPORT vpTemplateTrackerSSDInverseCompositional : public vpTemplateTrackerSSD { protected: @@ -72,4 +74,5 @@ class VISP_EXPORT vpTemplateTrackerSSDInverseCompositional : public vpTemplateTr * this feature is disabled. */ void setUseTemplateSelect(bool b) { useTemplateSelect = b; } }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerTriangle.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerTriangle.h index e2a42be271..fabc0bd1ed 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerTriangle.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerTriangle.h @@ -48,11 +48,13 @@ #include #include +#include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerTriangle \ingroup group_tt_tools @@ -137,10 +139,12 @@ class VISP_EXPORT vpTemplateTrackerTriangle if (i == 0) { x = C1.x; y = C1.y; - } else if (i == 1) { + } + else if (i == 1) { x = C2.x; y = C2.y; - } else /*if(i==2)*/ { + } + else /*if(i==2)*/ { x = C3.x; y = C3.y; } @@ -164,4 +168,5 @@ class VISP_EXPORT vpTemplateTrackerTriangle vpTemplateTrackerTriangle &operator=(const vpTemplateTrackerTriangle &T); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarp.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarp.h index 9481490b90..37b6a58084 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarp.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarp.h @@ -44,12 +44,14 @@ #ifndef vpTemplateTrackerWarp_hh #define vpTemplateTrackerWarp_hh +#include #include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerWarp \ingroup group_tt_warp @@ -64,11 +66,11 @@ class VISP_EXPORT vpTemplateTrackerWarp /*! * Default constructor. */ - vpTemplateTrackerWarp() : denom(1.), nbParam(0) {} + vpTemplateTrackerWarp() : denom(1.), nbParam(0) { } /*! * Destructor. */ - virtual ~vpTemplateTrackerWarp() {} + virtual ~vpTemplateTrackerWarp() { } #ifndef DOXYGEN_SHOULD_SKIP_THIS virtual void computeCoeff(const vpColVector &p) = 0; @@ -255,5 +257,5 @@ class VISP_EXPORT vpTemplateTrackerWarp void warpZone(const vpTemplateTrackerZone &in, const vpColVector &p, vpTemplateTrackerZone &out); //@} }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpAffine.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpAffine.h index 2d30a78084..4d4cfb2409 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpAffine.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpAffine.h @@ -45,8 +45,10 @@ #ifndef vpTemplateTrackerWarpAffine_hh #define vpTemplateTrackerWarpAffine_hh +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerWarpAffine \ingroup group_tt_warp @@ -70,8 +72,8 @@ class VISP_EXPORT vpTemplateTrackerWarpAffine : public vpTemplateTrackerWarp vpTemplateTrackerWarpAffine(); #ifndef DOXYGEN_SHOULD_SKIP_THIS - void computeCoeff(const vpColVector &) {} - void computeDenom(vpColVector &, const vpColVector &) {} + void computeCoeff(const vpColVector &) { } + void computeDenom(vpColVector &, const vpColVector &) { } #endif void dWarp(const vpColVector &X, const vpColVector &, const vpColVector &, vpMatrix &dM); @@ -96,4 +98,5 @@ class VISP_EXPORT vpTemplateTrackerWarpAffine : public vpTemplateTrackerWarp void warpX(const int &v1, const int &u1, double &v2, double &u2, const vpColVector &p); void warpXInv(const vpColVector &X1, vpColVector &X2, const vpColVector &p); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpHomography.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpHomography.h index 93c6712f09..491455b21b 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpHomography.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpHomography.h @@ -45,9 +45,11 @@ #ifndef vpTemplateTrackerWarpHomography_hh #define vpTemplateTrackerWarpHomography_hh +#include #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerWarpHomography \ingroup group_tt_warp @@ -71,7 +73,7 @@ class VISP_EXPORT vpTemplateTrackerWarpHomography : public vpTemplateTrackerWarp vpTemplateTrackerWarpHomography(); #ifndef DOXYGEN_SHOULD_SKIP_THIS - void computeCoeff(const vpColVector &) {} + void computeCoeff(const vpColVector &) { } #endif void computeDenom(vpColVector &X, const vpColVector &p); @@ -103,4 +105,5 @@ class VISP_EXPORT vpTemplateTrackerWarpHomography : public vpTemplateTrackerWarp void warpX(const int &v1, const int &u1, double &v2, double &u2, const vpColVector &p); void warpXInv(const vpColVector &X1, vpColVector &X2, const vpColVector &p); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpHomographySL3.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpHomographySL3.h index 9a531b5efb..fe9ca999d2 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpHomographySL3.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpHomographySL3.h @@ -42,13 +42,15 @@ #include +#include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpTemplateTrackerWarpHomographySL3 * \ingroup group_tt_warp - */ +*/ class VISP_EXPORT vpTemplateTrackerWarpHomographySL3 : public vpTemplateTrackerWarp { protected: @@ -92,4 +94,5 @@ class VISP_EXPORT vpTemplateTrackerWarpHomographySL3 : public vpTemplateTrackerW void warpXInv(const vpColVector &, vpColVector &, const vpColVector &) { } #endif }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpRT.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpRT.h index b4e74b162a..e93e848c3e 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpRT.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpRT.h @@ -44,8 +44,10 @@ #ifndef vpTemplateTrackerWarpRT_hh #define vpTemplateTrackerWarpRT_hh +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerWarpRT \ingroup group_tt_warp @@ -68,8 +70,8 @@ class VISP_EXPORT vpTemplateTrackerWarpRT : public vpTemplateTrackerWarp vpTemplateTrackerWarpRT(); #ifndef DOXYGEN_SHOULD_SKIP_THIS - void computeCoeff(const vpColVector &) {} - void computeDenom(vpColVector &, const vpColVector &) {} + void computeCoeff(const vpColVector &) { } + void computeDenom(vpColVector &, const vpColVector &) { } #endif void dWarp(const vpColVector &X, const vpColVector &, const vpColVector &p, vpMatrix &dM); @@ -94,4 +96,5 @@ class VISP_EXPORT vpTemplateTrackerWarpRT : public vpTemplateTrackerWarp void warpX(const int &v1, const int &u1, double &v2, double &u2, const vpColVector &p); void warpXInv(const vpColVector &X1, vpColVector &X2, const vpColVector &p); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpSRT.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpSRT.h index 5bb8992260..8c17e22d2a 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpSRT.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpSRT.h @@ -44,8 +44,10 @@ #ifndef vpTemplateTrackerWarpSRT_hh #define vpTemplateTrackerWarpSRT_hh +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerWarpSRT \ingroup group_tt_warp @@ -69,8 +71,8 @@ class VISP_EXPORT vpTemplateTrackerWarpSRT : public vpTemplateTrackerWarp vpTemplateTrackerWarpSRT(); #ifndef DOXYGEN_SHOULD_SKIP_THIS - void computeCoeff(const vpColVector &) {} - void computeDenom(vpColVector &, const vpColVector &) {} + void computeCoeff(const vpColVector &) { } + void computeDenom(vpColVector &, const vpColVector &) { } #endif void dWarp(const vpColVector &X, const vpColVector &, const vpColVector &p, vpMatrix &dM); @@ -95,4 +97,5 @@ class VISP_EXPORT vpTemplateTrackerWarpSRT : public vpTemplateTrackerWarp void warpX(const int &v1, const int &u1, double &v2, double &u2, const vpColVector &p); void warpXInv(const vpColVector &X1, vpColVector &X2, const vpColVector &p); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpTranslation.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpTranslation.h index b6c676bbe5..0afac32e51 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpTranslation.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerWarpTranslation.h @@ -44,8 +44,10 @@ #ifndef vpTemplateTrackerWarpTranslation_hh #define vpTemplateTrackerWarpTranslation_hh +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerWarpTranslation \ingroup group_tt_warp @@ -69,8 +71,8 @@ class VISP_EXPORT vpTemplateTrackerWarpTranslation : public vpTemplateTrackerWar vpTemplateTrackerWarpTranslation(); #ifndef DOXYGEN_SHOULD_SKIP_THIS - void computeCoeff(const vpColVector &) {} - void computeDenom(vpColVector &, const vpColVector &) {} + void computeCoeff(const vpColVector &) { } + void computeDenom(vpColVector &, const vpColVector &) { } #endif void dWarp(const vpColVector &, const vpColVector &, const vpColVector &, vpMatrix &dM); @@ -95,4 +97,5 @@ class VISP_EXPORT vpTemplateTrackerWarpTranslation : public vpTemplateTrackerWar void warpX(const int &v1, const int &u1, double &v2, double &u2, const vpColVector &p); void warpXInv(const vpColVector &X1, vpColVector &X2, const vpColVector &p); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCC.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCC.h index 639407dbd5..9359c78285 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCC.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCC.h @@ -46,6 +46,7 @@ #include +#include #include #include #include @@ -57,6 +58,7 @@ #define APPROX_NCC +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerZNCC \ingroup group_tt_tracker @@ -82,4 +84,5 @@ class VISP_EXPORT vpTemplateTrackerZNCC : public vpTemplateTracker void setGain(double _gain) { gain = _gain; } }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCCForwardAdditional.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCCForwardAdditional.h index 5e5d73cf57..f32fd25593 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCCForwardAdditional.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCCForwardAdditional.h @@ -44,15 +44,17 @@ #ifndef vpTemplateTrackerZNCCForwardAdditional_hh #define vpTemplateTrackerZNCCForwardAdditional_hh +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerZNCCForwardAdditional \ingroup group_tt_tracker The algorithm implemented in this class is described in \cite Irani98a and \cite Marchand16a. - */ +*/ class VISP_EXPORT vpTemplateTrackerZNCCForwardAdditional : public vpTemplateTrackerZNCC { protected: @@ -62,4 +64,5 @@ class VISP_EXPORT vpTemplateTrackerZNCCForwardAdditional : public vpTemplateTrac public: explicit vpTemplateTrackerZNCCForwardAdditional(vpTemplateTrackerWarp *warp); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCCInverseCompositional.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCCInverseCompositional.h index faae1cf606..e8a350644c 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCCInverseCompositional.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZNCCInverseCompositional.h @@ -46,8 +46,10 @@ #include +#include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerZNCCInverseCompositional \ingroup group_tt_tracker @@ -68,4 +70,5 @@ class VISP_EXPORT vpTemplateTrackerZNCCInverseCompositional : public vpTemplateT public: explicit vpTemplateTrackerZNCCInverseCompositional(vpTemplateTrackerWarp *warp); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZone.h b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZone.h index cca9d9fb8b..8e131711dd 100644 --- a/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZone.h +++ b/modules/tracker/tt/include/visp3/tt/vpTemplateTrackerZone.h @@ -41,6 +41,7 @@ #include +#include #include #include #include @@ -48,6 +49,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerZone \ingroup group_tt_tools @@ -57,7 +59,7 @@ A zone can be initialized either by user interaction using mouse click in a display device throw initClick(), or by a list of points throw initFromPoints(). - */ +*/ class VISP_EXPORT vpTemplateTrackerZone { protected: @@ -119,4 +121,5 @@ class VISP_EXPORT vpTemplateTrackerZone vpTemplateTrackerZone &operator=(const vpTemplateTrackerZone &z); }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt/src/ssd/vpTemplateTrackerSSD.cpp b/modules/tracker/tt/src/ssd/vpTemplateTrackerSSD.cpp index 3c258df4ad..d38ca3d85b 100644 --- a/modules/tracker/tt/src/ssd/vpTemplateTrackerSSD.cpp +++ b/modules/tracker/tt/src/ssd/vpTemplateTrackerSSD.cpp @@ -39,6 +39,7 @@ #include +BEGIN_VISP_NAMESPACE vpTemplateTrackerSSD::vpTemplateTrackerSSD(vpTemplateTrackerWarp *warp) : vpTemplateTracker(warp), DI(), temp() { dW.resize(2, nbParam); @@ -120,3 +121,4 @@ double vpTemplateTrackerSSD::getSSD(const vpImage &I, const vpCol return 10e10; return erreur / Nbpoint; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/ssd/vpTemplateTrackerSSDESM.cpp b/modules/tracker/tt/src/ssd/vpTemplateTrackerSSDESM.cpp index f54de5075b..0716be8373 100644 --- a/modules/tracker/tt/src/ssd/vpTemplateTrackerSSDESM.cpp +++ b/modules/tracker/tt/src/ssd/vpTemplateTrackerSSDESM.cpp @@ -39,6 +39,7 @@ #include #include +BEGIN_VISP_NAMESPACE vpTemplateTrackerSSDESM::vpTemplateTrackerSSDESM(vpTemplateTrackerWarp *warp) : vpTemplateTrackerSSD(warp), compoInitialised(false), HDir(), HInv(), HLMDir(), HLMInv(), GDir(), GInv() { @@ -169,7 +170,8 @@ void vpTemplateTrackerSSDESM::trackNoPyr(const vpImage &I) try { dp = (HLMDir).inverseByLU() * (GDir); - } catch (const vpException &e) { + } + catch (const vpException &e) { delete[] tempt; throw(e); } @@ -199,3 +201,4 @@ void vpTemplateTrackerSSDESM::trackNoPyr(const vpImage &I) nbIteration = iteration; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/ssd/vpTemplateTrackerSSDForwardAdditional.cpp b/modules/tracker/tt/src/ssd/vpTemplateTrackerSSDForwardAdditional.cpp index aa87773162..a6c425fe05 100644 --- a/modules/tracker/tt/src/ssd/vpTemplateTrackerSSDForwardAdditional.cpp +++ b/modules/tracker/tt/src/ssd/vpTemplateTrackerSSDForwardAdditional.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE vpTemplateTrackerSSDForwardAdditional::vpTemplateTrackerSSDForwardAdditional(vpTemplateTrackerWarp *warp) : vpTemplateTrackerSSD(warp), minimizationMethod(USE_NEWTON), p_prec(), G_prec(), KQuasiNewton() { @@ -124,7 +125,8 @@ void vpTemplateTrackerSSDForwardAdditional::trackNoPyr(const vpImage #include +BEGIN_VISP_NAMESPACE vpTemplateTrackerSSDForwardCompositional::vpTemplateTrackerSSDForwardCompositional(vpTemplateTrackerWarp *warp) : vpTemplateTrackerSSD(warp), compoInitialised(false) -{ -} +{ } void vpTemplateTrackerSSDForwardCompositional::initCompo(const vpImage & /*I*/) { @@ -141,7 +141,8 @@ void vpTemplateTrackerSSDForwardCompositional::trackNoPyr(const vpImage #include +BEGIN_VISP_NAMESPACE vpTemplateTrackerSSDInverseCompositional::vpTemplateTrackerSSDInverseCompositional(vpTemplateTrackerWarp *warp) : vpTemplateTrackerSSD(warp), compoInitialised(false), HInv(), HCompInverse(), useTemplateSelect(false) { @@ -167,3 +168,4 @@ void vpTemplateTrackerSSDInverseCompositional::trackNoPyr(const vpImage std::fabs(evolRMS_init) * evolRMS_eps)); nbIteration = iteration; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/tools/vpTemplateTrackerBSpline.cpp b/modules/tracker/tt/src/tools/vpTemplateTrackerBSpline.cpp index eb5cbd505f..9f09c653e4 100644 --- a/modules/tracker/tt/src/tools/vpTemplateTrackerBSpline.cpp +++ b/modules/tracker/tt/src/tools/vpTemplateTrackerBSpline.cpp @@ -38,6 +38,7 @@ *****************************************************************************/ #include +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS double vpTemplateTrackerBSpline::getSubPixBspline4(const vpImage &I, double r, double t) @@ -67,11 +68,14 @@ double vpTemplateTrackerBSpline::Bspline4(double diff) double aDiff = vpMath::abs(diff); if (aDiff < 1.) { return (aDiff * aDiff * (aDiff / 2. - 1) + 4. / 6.); - } else if (aDiff < 2.) { + } + else if (aDiff < 2.) { double a = 2. - aDiff; return (a * a * a / 6.); - } else + } + else return 0; } #endif +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/tools/vpTemplateTrackerTriangle.cpp b/modules/tracker/tt/src/tools/vpTemplateTrackerTriangle.cpp index af34542cf5..d1a74d39d1 100644 --- a/modules/tracker/tt/src/tools/vpTemplateTrackerTriangle.cpp +++ b/modules/tracker/tt/src/tools/vpTemplateTrackerTriangle.cpp @@ -38,21 +38,21 @@ *****************************************************************************/ #include +BEGIN_VISP_NAMESPACE /*! Default constructor. */ vpTemplateTrackerTriangle::vpTemplateTrackerTriangle() : minx_temp(0), miny_temp(0), C1(), C2(), C3(), l_t(0), h_t(0), not_good(false), uvinv00(0.), uvinv01(0.), - uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) -{ -} + uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) +{ } /*! Copy constructor. */ vpTemplateTrackerTriangle::vpTemplateTrackerTriangle(const vpTemplateTrackerTriangle &T) : minx_temp(0), miny_temp(0), C1(), C2(), C3(), l_t(0), h_t(0), not_good(false), uvinv00(0.), uvinv01(0.), - uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) + uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) { *this = T; } @@ -104,7 +104,7 @@ vpTemplateTrackerTriangle &vpTemplateTrackerTriangle::operator=(const vpTemplate vpTemplateTrackerTriangle::vpTemplateTrackerTriangle(const vpColVector &c1, const vpColVector &c2, const vpColVector &c3) : minx_temp(0), miny_temp(0), C1(), C2(), C3(), l_t(0), h_t(0), not_good(false), uvinv00(0.), uvinv01(0.), - uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) + uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) { init(c1[0], c1[1], c2[0], c2[1], c3[0], c3[1]); } @@ -125,7 +125,7 @@ vpTemplateTrackerTriangle vpTemplateTrackerTriangle::getPyramidDown() const */ vpTemplateTrackerTriangle::vpTemplateTrackerTriangle(int x1, int y1, int x2, int y2, int x3, int y3) : minx_temp(0), miny_temp(0), C1(), C2(), C3(), l_t(0), h_t(0), not_good(false), uvinv00(0.), uvinv01(0.), - uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) + uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) { init(x1, y1, x2, y2, x3, y3); } @@ -139,7 +139,7 @@ vpTemplateTrackerTriangle::vpTemplateTrackerTriangle(int x1, int y1, int x2, int vpTemplateTrackerTriangle::vpTemplateTrackerTriangle(const vpImagePoint &c1, const vpImagePoint &c2, const vpImagePoint &c3) : minx_temp(0), miny_temp(0), C1(), C2(), C3(), l_t(0), h_t(0), not_good(false), uvinv00(0.), uvinv01(0.), - uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) + uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) { init(c1.get_u(), c1.get_v(), c2.get_u(), c2.get_v(), c3.get_u(), c3.get_v()); } @@ -151,7 +151,7 @@ vpTemplateTrackerTriangle::vpTemplateTrackerTriangle(const vpImagePoint &c1, con */ vpTemplateTrackerTriangle::vpTemplateTrackerTriangle(double x1, double y1, double x2, double y2, double x3, double y3) : minx_temp(0), miny_temp(0), C1(), C2(), C3(), l_t(0), h_t(0), not_good(false), uvinv00(0.), uvinv01(0.), - uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) + uvinv10(0.), uvinv11(0.), marge_triangle(0.00001), area(0) { init(x1, y1, x2, y2, x3, y3); } @@ -236,7 +236,8 @@ void vpTemplateTrackerTriangle::init(double x1, double y1, double x2, double y2, try { uvinv = uv.inverseByLU(); not_good = false; - } catch (...) { + } + catch (...) { not_good = true; std::cout << "Triangle vide" << std::endl; } @@ -423,3 +424,4 @@ double vpTemplateTrackerTriangle::getMaxx() const { return minx_temp + l_t + 1; that are in the triangle. \sa getMaxx() */ double vpTemplateTrackerTriangle::getMaxy() const { return miny_temp + h_t + 1; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/tools/vpTemplateTrackerZone.cpp b/modules/tracker/tt/src/tools/vpTemplateTrackerZone.cpp index f5dd658ead..1c50de3e1c 100644 --- a/modules/tracker/tt/src/tools/vpTemplateTrackerZone.cpp +++ b/modules/tracker/tt/src/tools/vpTemplateTrackerZone.cpp @@ -33,8 +33,6 @@ * *****************************************************************************/ -#include // numeric_limits - #include #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) @@ -43,14 +41,15 @@ #include +BEGIN_VISP_NAMESPACE /*! Default constructor. */ -vpTemplateTrackerZone::vpTemplateTrackerZone() : Zone(), min_x(-1), min_y(-1), max_x(-1), max_y(-1) {} + vpTemplateTrackerZone::vpTemplateTrackerZone() : Zone(), min_x(-1), min_y(-1), max_x(-1), max_y(-1) { } -/*! - Copy constructor. - */ + /*! + Copy constructor. + */ vpTemplateTrackerZone::vpTemplateTrackerZone(const vpTemplateTrackerZone &z) : Zone(), min_x(-1), min_y(-1), max_x(-1), max_y(-1) { @@ -123,7 +122,8 @@ void vpTemplateTrackerZone::initClick(const vpImage &I, bool dela if (delaunay) { // Draw a line between the 2 last points vpDisplay::displayLine(I, p, vip[vip.size() - 2], vpColor::blue, 3); - } else { + } + else { if (vip.size() % 3 == 2) // draw line between point 2-1 vpDisplay::displayLine(I, p, vip[vip.size() - 2], vpColor::blue, 3); @@ -166,7 +166,8 @@ void vpTemplateTrackerZone::initFromPoints(const vpImage &I, cons if (delaunay) { if (vip.size() == 3) { initFromPoints(I, vip, false); - } else if (vip.size() == 4) { + } + else if (vip.size() == 4) { std::vector vip_delaunay; vip_delaunay.push_back(vip[0]); vip_delaunay.push_back(vip[1]); @@ -175,7 +176,8 @@ void vpTemplateTrackerZone::initFromPoints(const vpImage &I, cons vip_delaunay.push_back(vip[3]); vip_delaunay.push_back(vip[0]); initFromPoints(I, vip_delaunay, false); - } else { + } + else { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) // Init Delaunay cv::Subdiv2D subdiv(cv::Rect(0, 0, (int)I.getWidth(), (int)I.getHeight())); @@ -213,7 +215,8 @@ void vpTemplateTrackerZone::initFromPoints(const vpImage &I, cons throw vpException(vpException::functionNotImplementedError, "Delaunay triangulation is not available!"); #endif } - } else { + } + else { Zone.clear(); for (unsigned int i = 0; i < vip.size(); i += 3) { vpTemplateTrackerTriangle triangle(vip[i], vip[i + 1], vip[i + 2]); @@ -577,3 +580,4 @@ double vpTemplateTrackerZone::getArea() const } return area; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/vpTemplateTracker.cpp b/modules/tracker/tt/src/vpTemplateTracker.cpp index 7dd4e4c17c..6191b831f5 100644 --- a/modules/tracker/tt/src/vpTemplateTracker.cpp +++ b/modules/tracker/tt/src/vpTemplateTracker.cpp @@ -40,16 +40,17 @@ #include #include +BEGIN_VISP_NAMESPACE vpTemplateTracker::vpTemplateTracker(vpTemplateTrackerWarp *_warp) : nbLvlPyr(1), l0Pyr(0), pyrInitialised(false), evolRMS(0), x_pos(), y_pos(), evolRMS_eps(1e-4), ptTemplate(nullptr), - ptTemplatePyr(nullptr), ptTemplateInit(false), templateSize(0), templateSizePyr(nullptr), ptTemplateSelect(nullptr), - ptTemplateSelectPyr(nullptr), ptTemplateSelectInit(false), templateSelectSize(0), ptTemplateSupp(nullptr), - ptTemplateSuppPyr(nullptr), ptTemplateCompo(nullptr), ptTemplateCompoPyr(nullptr), zoneTracked(nullptr), zoneTrackedPyr(nullptr), - pyr_IDes(nullptr), H(), Hdesire(), HdesirePyr(), HLM(), HLMdesire(), HLMdesirePyr(), HLMdesireInverse(), - HLMdesireInversePyr(), G(), gain(1.), thresholdGradient(40), costFunctionVerification(false), blur(true), - useBrent(false), nbIterBrent(3), taillef(7), fgG(nullptr), fgdG(nullptr), ratioPixelIn(0), mod_i(1), mod_j(1), nbParam(0), - lambdaDep(0.001), iterationMax(30), iterationGlobale(0), diverge(false), nbIteration(0), useCompositionnal(true), - useInverse(false), Warp(_warp), p(0), dp(), X1(), X2(), dW(), BI(), dIx(), dIy(), zoneRef_() + ptTemplatePyr(nullptr), ptTemplateInit(false), templateSize(0), templateSizePyr(nullptr), ptTemplateSelect(nullptr), + ptTemplateSelectPyr(nullptr), ptTemplateSelectInit(false), templateSelectSize(0), ptTemplateSupp(nullptr), + ptTemplateSuppPyr(nullptr), ptTemplateCompo(nullptr), ptTemplateCompoPyr(nullptr), zoneTracked(nullptr), zoneTrackedPyr(nullptr), + pyr_IDes(nullptr), H(), Hdesire(), HdesirePyr(), HLM(), HLMdesire(), HLMdesirePyr(), HLMdesireInverse(), + HLMdesireInversePyr(), G(), gain(1.), thresholdGradient(40), costFunctionVerification(false), blur(true), + useBrent(false), nbIterBrent(3), taillef(7), fgG(nullptr), fgdG(nullptr), ratioPixelIn(0), mod_i(1), mod_j(1), nbParam(0), + lambdaDep(0.001), iterationMax(30), iterationGlobale(0), diverge(false), nbIteration(0), useCompositionnal(true), + useInverse(false), Warp(_warp), p(0), dp(), X1(), X2(), dW(), BI(), dIx(), dIy(), zoneRef_() { nbParam = Warp->getNbParam(); p.resize(nbParam); @@ -125,7 +126,8 @@ void vpTemplateTracker::initTracking(const vpImage &I, vpTemplate if (pt.dx * pt.dx + pt.dy * pt.dy > thresholdGradient) { ptTemplateSelect[cpt_point] = true; templateSelectSize++; - } else { + } + else { ptTemplateSelect[cpt_point] = false; } pt.val = vpTemplateTrackerBSpline::getSubPixBspline4(GaussI, i, j); @@ -241,7 +243,8 @@ void vpTemplateTracker::resetTracker() delete[] pyr_IDes; pyr_IDes = nullptr; } - } else { + } + else { if (ptTemplateInit) { for (unsigned int point = 0; point < templateSize; point++) { delete[] ptTemplate[point].dW; @@ -382,7 +385,8 @@ void vpTemplateTracker::computeOptimalBrentGain(const vpImage &I, else dpt = direction; Warp->pRondp(tp, dpt, p1); - } else { + } + else { p1 = tp + direction; } @@ -394,7 +398,8 @@ void vpTemplateTracker::computeOptimalBrentGain(const vpImage &I, else dpt = adpt; Warp->pRondp(tp, dpt, p2); - } else { + } + else { p2 = tp + alpha * direction; } vpColVector p3(nbParam); @@ -431,7 +436,8 @@ void vpTemplateTracker::computeOptimalBrentGain(const vpImage &I, // If convexe if (parabol[0] > 0) { talpha[3] = -0.5 * parabol[1] / parabol[0]; - } else { // If concave + } + else { // If concave int tindic_x_min = 0; int tindic_x_max = 0; for (int i = 1; i < 3; i++) { @@ -443,7 +449,8 @@ void vpTemplateTracker::computeOptimalBrentGain(const vpImage &I, if (Cost[tindic_x_max] < Cost[tindic_x_min]) { talpha[3] = talpha[tindic_x_max] + 1.; - } else { + } + else { talpha[3] = talpha[tindic_x_min] - 1.; } } @@ -469,7 +476,8 @@ void vpTemplateTracker::computeOptimalBrentGain(const vpImage &I, else dpt = adpt; Warp->pRondp(tp, dpt, p3); - } else { + } + else { p3 = tp + talpha[3] * direction; } @@ -483,7 +491,8 @@ void vpTemplateTracker::computeOptimalBrentGain(const vpImage &I, *ptp[indice_f_max] = *ptp[3]; Cost[indice_f_max] = Cost[3]; talpha[indice_f_max] = talpha[3]; - } else + } + else break; } @@ -586,7 +595,8 @@ void vpTemplateTracker::initClick(const vpImage &I, bool delaunay initPyramidal(nbLvlPyr, l0Pyr); initTrackingPyr(I, zoneRef_); initHessienDesiredPyr(I); - } else { + } + else { initTracking(I, zoneRef_); initHessienDesired(I); } @@ -612,7 +622,8 @@ void vpTemplateTracker::initFromPoints(const vpImage &I, const st initPyramidal(nbLvlPyr, l0Pyr); initTrackingPyr(I, zoneRef_); initHessienDesiredPyr(I); - } else { + } + else { initTracking(I, zoneRef_); initHessienDesired(I); } @@ -632,7 +643,8 @@ void vpTemplateTracker::initFromZone(const vpImage &I, const vpTe initPyramidal(nbLvlPyr, l0Pyr); initTrackingPyr(I, zoneRef_); initHessienDesiredPyr(I); - } else { + } + else { initTracking(I, zoneRef_); initHessienDesired(I); } @@ -650,7 +662,8 @@ void vpTemplateTracker::initHessienDesiredPyr(const vpImage &I) HdesirePyr[0] = Hdesire; HLMdesirePyr[0] = HLMdesire; HLMdesireInversePyr[0] = HLMdesireInverse; - } catch (const vpException &e) { + } + catch (const vpException &e) { ptTemplateSuppPyr[0] = ptTemplateSupp; ptTemplateCompoPyr[0] = ptTemplateCompo; HdesirePyr[0] = Hdesire; @@ -675,7 +688,8 @@ void vpTemplateTracker::initHessienDesiredPyr(const vpImage &I) HdesirePyr[i] = Hdesire; HLMdesirePyr[i] = HLMdesire; HLMdesireInversePyr[i] = HLMdesireInverse; - } catch (const vpException &e) { + } + catch (const vpException &e) { ptTemplateSuppPyr[i] = ptTemplateSupp; ptTemplateCompoPyr[i] = ptTemplateCompo; HdesirePyr[i] = Hdesire; @@ -733,11 +747,13 @@ void vpTemplateTracker::trackPyr(const vpImage &I) zoneTracked = &zoneTrackedPyr[i - 1]; } } - } else { + } + else { trackRobust(I); } delete[] pyr_I; - } catch (const vpException &e) { + } + catch (const vpException &e) { delete[] pyr_I; throw(vpTrackingException(vpTrackingException::badValue, e.getMessage())); } @@ -757,7 +773,8 @@ void vpTemplateTracker::trackRobust(const vpImage &I) if (pre_fcost < post_fcost) { p = p_pre_estimation; } - } else { + } + else { trackNoPyr(I); } } @@ -823,3 +840,4 @@ void vpTemplateTracker::initPosEvalRMS(const vpColVector ¶m) } } } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/warp/vpTemplateTrackerWarp.cpp b/modules/tracker/tt/src/warp/vpTemplateTrackerWarp.cpp index e6788ec31f..adde6be834 100644 --- a/modules/tracker/tt/src/warp/vpTemplateTrackerWarp.cpp +++ b/modules/tracker/tt/src/warp/vpTemplateTrackerWarp.cpp @@ -38,13 +38,14 @@ *****************************************************************************/ #include +BEGIN_VISP_NAMESPACE void vpTemplateTrackerWarp::warpTriangle(const vpTemplateTrackerTriangle &in, const vpColVector &p, vpTemplateTrackerTriangle &out) { if (p.size() < 2) { vpCTRACE << "Bad template tracker warp parameters dimension. Should " - "never occur. " - << std::endl; + "never occur. " + << std::endl; throw(vpException(vpException::dimensionError, "Bad template tracker warp parameters dimension")); } vpColVector S1(2), S2(2), S3(2); @@ -149,8 +150,9 @@ void vpTemplateTrackerWarp::findWarp(const double *ut0, const double *vt0, const vpMatrix::computeHLM(H, lambda, HLM); try { p += (vpColVector)(HLM.inverseByLU() * G, 0u); - } catch (const vpException &e) { - // std::cout<<"Cannot inverse the matrix by LU " << std::endl; + } + catch (const vpException &e) { + // std::cout<<"Cannot inverse the matrix by LU " << std::endl; throw(e); } cpt++; @@ -158,3 +160,4 @@ void vpTemplateTrackerWarp::findWarp(const double *ut0, const double *vt0, const // std::cout<<"erreur apres transformation="< +BEGIN_VISP_NAMESPACE /*! * Construct a model with 6 affine parameters initialized to zero. */ @@ -221,7 +222,7 @@ void vpTemplateTrackerWarpAffine::getParamInverse(const vpColVector &p, vpColVec double det = r_00 * r_11 - r_01 * r_10; if (std::fabs(det) < std::numeric_limits::epsilon()) { throw(vpException(vpException::fatalError, "In vpTemplateTrackerWarpAffine::getParamInverse() " - "cannot inverse 2-by-2 matrix. Matrix determinant is 0.")); + "cannot inverse 2-by-2 matrix. Matrix determinant is 0.")); } double ri_11 = r_00 / det; @@ -263,3 +264,4 @@ void vpTemplateTrackerWarpAffine::pRondp(const vpColVector &p1, const vpColVecto p12[4] = r1_00 * u2 + r1_01 * v2 + u1; p12[5] = r1_10 * u2 + r1_11 * v2 + v1; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpHomography.cpp b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpHomography.cpp index 1fe19dced2..d51a296015 100644 --- a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpHomography.cpp +++ b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpHomography.cpp @@ -39,6 +39,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Construct an homography model with 8 parameters initialized to zero. */ @@ -151,7 +152,8 @@ void vpTemplateTrackerWarpHomography::computeDenom(vpColVector &X, const vpColVe if (std::fabs(value) > std::numeric_limits::epsilon()) { denom = (1. / value); - } else { + } + else { throw(vpTrackingException(vpTrackingException::fatalError, "Division by zero in vpTemplateTrackerWarpHomography::computeDenom()")); } @@ -259,10 +261,11 @@ void vpTemplateTrackerWarpHomography::warpXInv(const vpColVector &X1, vpColVecto if (std::fabs(value) > std::numeric_limits::epsilon()) { X2[0] = ((1 + p[0]) * X1[0] + p[3] * X1[1] + p[6]) / value; X2[1] = (p[1] * X1[0] + (1 + p[4]) * X1[1] + p[7]) / value; - } else { + } + else { throw(vpTrackingException(vpTrackingException::fatalError, "Division by zero in " - "vpTemplateTrackerWarpHomography::" - "warpXInv()")); + "vpTemplateTrackerWarpHomography::" + "warpXInv()")); } } @@ -400,3 +403,4 @@ void vpTemplateTrackerWarpHomography::pRondp(const vpColVector &p1, const vpColV p12[2] = (h1_20 * h2_00 + h1_21 * h2_10 + h2_20) / h12_22; p12[5] = (h1_20 * h2_01 + h1_21 * h2_11 + h2_21) / h12_22; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpHomographySL3.cpp b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpHomographySL3.cpp index 666ee5827b..8a7943ae9a 100644 --- a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpHomographySL3.cpp +++ b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpHomographySL3.cpp @@ -38,6 +38,7 @@ *****************************************************************************/ #include +BEGIN_VISP_NAMESPACE // findWarp special a SL3 car methode additionnelle ne marche pas (la derivee // n est calculable qu en p=0) // => resout le probleme de maniere compositionnelle @@ -526,3 +527,4 @@ void vpTemplateTrackerWarpHomographySL3::pRondp(const vpColVector &p1, const vpC // vrai que si commutatif ... p12 = p1 + p2; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpRT.cpp b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpRT.cpp index ab731939b8..2d4c8b7c74 100644 --- a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpRT.cpp +++ b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpRT.cpp @@ -38,6 +38,7 @@ *****************************************************************************/ #include +BEGIN_VISP_NAMESPACE /*! * Construct a model with 3 parameters for rotation and translation initialized to zero. */ @@ -242,3 +243,4 @@ void vpTemplateTrackerWarpRT::pRondp(const vpColVector &p1, const vpColVector &p p12[1] = c1 * u2 - s1 * v2 + u1; p12[2] = s1 * u2 + c1 * v2 + v1; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpSRT.cpp b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpSRT.cpp index 9969666e30..f651bf258e 100644 --- a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpSRT.cpp +++ b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpSRT.cpp @@ -38,6 +38,7 @@ *****************************************************************************/ #include +BEGIN_VISP_NAMESPACE /*! * Construct a model with 4 parameters for scale, rotation and translation initialized to zero. */ @@ -261,3 +262,4 @@ void vpTemplateTrackerWarpSRT::pRondp(const vpColVector &p1, const vpColVector & p12[2] = scale1 * (c1 * u2 - s1 * v2) + u1; p12[3] = scale1 * (s1 * u2 + c1 * v2) + v1; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpTranslation.cpp b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpTranslation.cpp index 6ae4e03eeb..e7bd2d22e0 100644 --- a/modules/tracker/tt/src/warp/vpTemplateTrackerWarpTranslation.cpp +++ b/modules/tracker/tt/src/warp/vpTemplateTrackerWarpTranslation.cpp @@ -38,6 +38,7 @@ *****************************************************************************/ #include +BEGIN_VISP_NAMESPACE /*! * Construct a model with 2 parameters for translation initialized to zero. */ @@ -194,3 +195,4 @@ void vpTemplateTrackerWarpTranslation::pRondp(const vpColVector &p1, const vpCol p12[0] = p1[0] + p2[0]; p12[1] = p1[1] + p2[1]; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/zncc/vpTemplateTrackerZNCC.cpp b/modules/tracker/tt/src/zncc/vpTemplateTrackerZNCC.cpp index 97e311baf6..f1eadb9b20 100644 --- a/modules/tracker/tt/src/zncc/vpTemplateTrackerZNCC.cpp +++ b/modules/tracker/tt/src/zncc/vpTemplateTrackerZNCC.cpp @@ -38,6 +38,7 @@ *****************************************************************************/ #include +BEGIN_VISP_NAMESPACE vpTemplateTrackerZNCC::vpTemplateTrackerZNCC(vpTemplateTrackerWarp *warp) : vpTemplateTracker(warp), DI(), temp() { dW.resize(2, nbParam); @@ -119,3 +120,4 @@ double vpTemplateTrackerZNCC::getCost(const vpImage &I, const vpC } return -nom / sqrt(var1 * var2); } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt/src/zncc/vpTemplateTrackerZNCCForwardAdditional.cpp b/modules/tracker/tt/src/zncc/vpTemplateTrackerZNCCForwardAdditional.cpp index b5c5961db6..4fe443f9b2 100644 --- a/modules/tracker/tt/src/zncc/vpTemplateTrackerZNCCForwardAdditional.cpp +++ b/modules/tracker/tt/src/zncc/vpTemplateTrackerZNCCForwardAdditional.cpp @@ -39,6 +39,7 @@ #include #include +BEGIN_VISP_NAMESPACE vpTemplateTrackerZNCCForwardAdditional::vpTemplateTrackerZNCCForwardAdditional(vpTemplateTrackerWarp *warp) : vpTemplateTrackerZNCC(warp) { @@ -252,7 +253,8 @@ void vpTemplateTrackerZNCCForwardAdditional::trackNoPyr(const vpImage #include +BEGIN_VISP_NAMESPACE vpTemplateTrackerZNCCInverseCompositional::vpTemplateTrackerZNCCInverseCompositional(vpTemplateTrackerWarp *warp) : vpTemplateTrackerZNCC(warp), compoInitialised(false), moydIrefdp() { @@ -194,7 +195,7 @@ void vpTemplateTrackerZNCCInverseCompositional::initHessienDesired(const vpImage sIcd2Iref[it][jt] += prodIc * (dW[0][it] * (dW[0][jt] * d_Ixx + dW[1][jt] * d_Ixy) + dW[1][it] * (dW[0][jt] * d_Ixy + dW[1][jt] * d_Iyy) - moyd2Iref[it][jt]); sdIrefdIref[it][jt] += - (ptTemplate[point].dW[it] - moydIrefdp[it]) * (ptTemplate[point].dW[jt] - moydIrefdp[jt]); + (ptTemplate[point].dW[it] - moydIrefdp[it]) * (ptTemplate[point].dW[jt] - moydIrefdp[jt]); } } @@ -323,7 +324,8 @@ void vpTemplateTrackerZNCCInverseCompositional::trackNoPyr(const vpImage::epsilon()) { diverge = true; - } else { + } + else { double NCC = sIcIref / denom; vpColVector dcovarIref(nbParam); dcovarIref = sIrefdIref / covarIref; @@ -331,7 +333,8 @@ void vpTemplateTrackerZNCCInverseCompositional::trackNoPyr(const vpImage #include +BEGIN_VISP_NAMESPACE /*! * \class vpTemplateTrackerMI * \ingroup group_tt_mi_tracker - */ +*/ class VISP_EXPORT vpTemplateTrackerMI : public vpTemplateTracker { public: @@ -165,5 +166,5 @@ class VISP_EXPORT vpTemplateTrackerMI : public vpTemplateTracker void setLambda(double _l) { lambda = _l; } void setNc(int newNc); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIBSpline.h b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIBSpline.h index 82201e4e0a..64ba0db0bb 100644 --- a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIBSpline.h +++ b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIBSpline.h @@ -54,7 +54,7 @@ #include #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE class VISP_EXPORT vpTemplateTrackerMIBSpline { public: @@ -118,6 +118,6 @@ class VISP_EXPORT vpTemplateTrackerMIBSpline unsigned int &NbParam, int &bspline, vpTemplateTrackerMI::vpHessienApproximationType &approx, bool use_hessien_des); }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIESM.h b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIESM.h index 4f92ef50a0..484b50ca7b 100644 --- a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIESM.h +++ b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIESM.h @@ -39,6 +39,7 @@ #ifndef vpTemplateTrackerMIESM_hh #define vpTemplateTrackerMIESM_hh +#include #include #include #include @@ -46,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerMIESM \ingroup group_tt_mi_tracker @@ -104,5 +106,5 @@ class VISP_EXPORT vpTemplateTrackerMIESM : public vpTemplateTrackerMI void setMinimizationMethod(vpMinimizationTypeMIESM method) { minimizationMethod = method; } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIForwardAdditional.h b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIForwardAdditional.h index 161c5d210b..80be91d081 100644 --- a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIForwardAdditional.h +++ b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIForwardAdditional.h @@ -48,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerMIForwardAdditional \ingroup group_tt_mi_tracker @@ -75,10 +76,9 @@ class VISP_EXPORT vpTemplateTrackerMIForwardAdditional : public vpTemplateTracke //! Default constructor. vpTemplateTrackerMIForwardAdditional() : vpTemplateTrackerMI(), minimizationMethod(USE_NEWTON), p_prec(), G_prec(), KQuasiNewton() - { - } + { } explicit vpTemplateTrackerMIForwardAdditional(vpTemplateTrackerWarp *_warp); void setMinimizationMethod(vpMinimizationTypeMIForwardAdditional method) { minimizationMethod = method; } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIForwardCompositional.h b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIForwardCompositional.h index ecb71dff50..831304c71e 100644 --- a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIForwardCompositional.h +++ b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIForwardCompositional.h @@ -48,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerMIForwardCompositional \ingroup group_tt_mi_tracker @@ -67,5 +68,5 @@ class VISP_EXPORT vpTemplateTrackerMIForwardCompositional : public vpTemplateTra public: explicit vpTemplateTrackerMIForwardCompositional(vpTemplateTrackerWarp *_warp); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIInverseCompositional.h b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIInverseCompositional.h index 876ed586d8..cf30bd2efe 100644 --- a/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIInverseCompositional.h +++ b/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMIInverseCompositional.h @@ -48,6 +48,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpTemplateTrackerMIInverseCompositional \ingroup group_tt_mi_tracker @@ -84,9 +85,8 @@ class VISP_EXPORT vpTemplateTrackerMIInverseCompositional : public vpTemplateTra //! Default constructor. vpTemplateTrackerMIInverseCompositional() : vpTemplateTrackerMI(), minimizationMethod(USE_LMA), CompoInitialised(false), useTemplateSelect(false), p_prec(), - G_prec(), KQuasiNewton() - { - } + G_prec(), KQuasiNewton() + { } explicit vpTemplateTrackerMIInverseCompositional(vpTemplateTrackerWarp *_warp); /*! Use only the strong gradient pixels to compute the Jabobian. By default @@ -94,4 +94,5 @@ class VISP_EXPORT vpTemplateTrackerMIInverseCompositional : public vpTemplateTra void setUseTemplateSelect(bool b) { useTemplateSelect = b; } void setMinimizationMethod(vpMinimizationTypeMIInverseCompositional method) { minimizationMethod = method; } }; +END_VISP_NAMESPACE #endif diff --git a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp index 634b7a300f..80b1cafd85 100644 --- a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp +++ b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp @@ -40,6 +40,7 @@ #include #include +BEGIN_VISP_NAMESPACE void vpTemplateTrackerMI::setBspline(const vpBsplineType &newbs) { bspline = (int)newbs; @@ -758,3 +759,4 @@ double vpTemplateTrackerMI::getMI256(const vpImage &I, const vpCo } return MI; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMIESM.cpp b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMIESM.cpp index 2238f304a0..b2db620907 100644 --- a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMIESM.cpp +++ b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMIESM.cpp @@ -43,9 +43,10 @@ #include #endif +BEGIN_VISP_NAMESPACE vpTemplateTrackerMIESM::vpTemplateTrackerMIESM(vpTemplateTrackerWarp *_warp) : vpTemplateTrackerMI(_warp), minimizationMethod(USE_NEWTON), CompoInitialised(false), HDirect(), HInverse(), - HdesireDirect(), HdesireInverse(), GDirect(), GInverse() + HdesireDirect(), HdesireInverse(), GDirect(), GInverse() { useCompositionnal = false; useInverse = false; @@ -293,7 +294,8 @@ void vpTemplateTrackerMIESM::trackNoPyr(const vpImage &I) diverge = true; MI = 0; throw(vpTrackingException(vpTrackingException::notEnoughPointError, "No points in the template")); - } else { + } + else { computeProba(Nbpoint); computeMI(MI); if (hessianComputation != vpTemplateTrackerMI::USE_HESSIEN_DESIRE) { @@ -377,7 +379,8 @@ void vpTemplateTrackerMIESM::trackNoPyr(const vpImage &I) case vpTemplateTrackerMI::USE_HESSIEN_BEST_COND: if (HLM.cond() > HLMdesire.cond()) { dp = gain * HLMdesireInverse * G; - } else { + } + else { dp = gain * 0.3 * HLM.inverseByLU() * G; } break; @@ -386,7 +389,8 @@ void vpTemplateTrackerMIESM::trackNoPyr(const vpImage &I) break; } } - } catch (const vpException &e) { + } + catch (const vpException &e) { throw(e); } @@ -411,3 +415,4 @@ void vpTemplateTrackerMIESM::trackNoPyr(const vpImage &I) nbIteration = iteration; } +END_VISP_NAMESPACE diff --git a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMIForwardAdditional.cpp b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMIForwardAdditional.cpp index 91ab3f8db9..298ff93232 100644 --- a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMIForwardAdditional.cpp +++ b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMIForwardAdditional.cpp @@ -43,6 +43,7 @@ #include #endif +BEGIN_VISP_NAMESPACE vpTemplateTrackerMIForwardAdditional::vpTemplateTrackerMIForwardAdditional(vpTemplateTrackerWarp *_warp) : vpTemplateTrackerMI(_warp), minimizationMethod(USE_NEWTON), p_prec(), G_prec(), KQuasiNewton() { @@ -122,7 +123,8 @@ void vpTemplateTrackerMIForwardAdditional::initHessienDesired(const vpImage MI) { p = p_test_LMA; lambda = (lambda / 10. < 1e-6) ? lambda / 10. : 1e-6; - } else { + } + else { lambda = (lambda * 10. < 1e6) ? 1e6 : lambda * 10.; } } break; @@ -325,3 +330,4 @@ void vpTemplateTrackerMIForwardAdditional::trackNoPyr(const vpImage +BEGIN_VISP_NAMESPACE vpTemplateTrackerMIForwardCompositional::vpTemplateTrackerMIForwardCompositional(vpTemplateTrackerWarp *_warp) : vpTemplateTrackerMI(_warp), CompoInitialised(false) -{ -} +{ } void vpTemplateTrackerMIForwardCompositional::initCompo() { @@ -228,7 +228,8 @@ void vpTemplateTrackerMIForwardCompositional::trackNoPyr(const vpImage +BEGIN_VISP_NAMESPACE vpTemplateTrackerMIInverseCompositional::vpTemplateTrackerMIInverseCompositional(vpTemplateTrackerWarp *_warp) : vpTemplateTrackerMI(_warp), minimizationMethod(USE_LMA), CompoInitialised(false), useTemplateSelect(false), - p_prec(), G_prec(), KQuasiNewton() + p_prec(), G_prec(), KQuasiNewton() { useInverse = true; } @@ -65,7 +66,8 @@ void vpTemplateTrackerMIInverseCompositional::initTemplateRefBspline(unsigned in ptBspFct = &vpTemplateTrackerMIBSpline::Bspline3; ptdBspFct = &vpTemplateTrackerMIBSpline::dBspline3; ptd2BspFct = &vpTemplateTrackerMIBSpline::d2Bspline3; - } else { + } + else { ptBspFct = &vpTemplateTrackerBSpline::Bspline4; ptdBspFct = &vpTemplateTrackerMIBSpline::dBspline4; ptd2BspFct = &vpTemplateTrackerMIBSpline::d2Bspline4; @@ -77,10 +79,10 @@ void vpTemplateTrackerMIInverseCompositional::initTemplateRefBspline(unsigned in for (unsigned int ip = 0; ip < nbParam; ++ip) { ptTemplateSupp[ptIndex].BtInit[index++] = - (*ptdBspFct)(static_cast(-it) + et) * ptTemplate[ptIndex].dW[ip] * (-1.0); + (*ptdBspFct)(static_cast(-it) + et) * ptTemplate[ptIndex].dW[ip] * (-1.0); for (unsigned int ip2 = 0; ip2 < nbParam; ++ip2) { ptTemplateSupp[ptIndex].BtInit[index++] = - (*ptd2BspFct)(static_cast(-it) + et) * ptTemplate[ptIndex].dW[ip] * ptTemplate[ptIndex].dW[ip2]; + (*ptd2BspFct)(static_cast(-it) + et) * ptTemplate[ptIndex].dW[ip] * ptTemplate[ptIndex].dW[ip2]; } } } @@ -166,14 +168,17 @@ void vpTemplateTrackerMIInverseCompositional::initHessienDesired(const vpImage(Ncb); @@ -323,7 +332,8 @@ void vpTemplateTrackerMIInverseCompositional::trackNoPyr(const vpImage MI) { dp = dp_test_LMA; lambda = (lambda / 10. < 1e-6) ? lambda / 10. : 1e-6; - } else { + } + else { dp = 0; lambda = (lambda * 10. < 1e6) ? 1e6 : lambda * 10.; } @@ -405,7 +416,8 @@ void vpTemplateTrackerMIInverseCompositional::trackNoPyr(const vpImagegetNbParam(), Warp->getNbParam()); covarianceMatrix = -1; MI_postEstimation = -1; @@ -429,3 +442,4 @@ void vpTemplateTrackerMIInverseCompositional::trackNoPyr(const vpImage #ifndef DOXYGEN_SHOULD_SKIP_THIS - +BEGIN_VISP_NAMESPACE void vpTemplateTrackerMIBSpline::PutPVBsplineD(double *Prt, int cr, double er, int ct, double et, int Nc, double val, const int °re) { @@ -72,7 +72,8 @@ void vpTemplateTrackerMIBSpline::PutPVBsplineD3(double *Prt, int cr, double er, *pt++ += Bspline3_diff_r_ * Bspline3(it - et) * val; } } - } else { + } + else { for (int ir = -1; ir <= 1; ir++) { double Bspline3_diff_r_ = Bspline3(ir - er); for (int it = -1; it <= 1; it++) { @@ -100,7 +101,8 @@ void vpTemplateTrackerMIBSpline::PutPVBsplineD4(double *Prt, int cr, double er, *pt++ += Br * (*ptBti++) * val; } } - } else { + } + else { for (int ir = -1; ir <= 2; ir++) { double Br = Bspline4i(ir - er, ir); ptBti = &Bti[0]; @@ -164,14 +166,18 @@ double vpTemplateTrackerMIBSpline::dBspline4(double diff) if ((diff > -2.) && (diff <= -1.)) { double diff_2_ = diff + 2.; return (diff_2_ * diff_2_ * 0.5); - } else if ((diff > -1.) && (diff <= 0.)) { + } + else if ((diff > -1.) && (diff <= 0.)) { return -1.5 * diff * diff - 2. * diff; - } else if ((diff > 0.) && (diff <= 1.)) { + } + else if ((diff > 0.) && (diff <= 1.)) { return 1.5 * diff * diff - 2. * diff; - } else if ((diff > 1.) && (diff <= 2.)) { + } + else if ((diff > 1.) && (diff <= 2.)) { double diff_2_ = diff - 2.; return (-0.5 * diff_2_ * diff_2_); - } else { + } + else { return 0; } } @@ -407,7 +413,7 @@ void vpTemplateTrackerMIBSpline::PutTotPVBspline4(double *Prt, double *dPrt, dou double Bti[4]; double dBti[4]; double d2Bti[4]; - + for (size_t i = 0; i < 4; ++i) { Bti[i] = 0.; dBti[i] = 0.; @@ -609,8 +615,8 @@ void vpTemplateTrackerMIBSpline::PutTotPVBspline3NoSecond(double *Prt, double *d void vpTemplateTrackerMIBSpline::PutTotPVBspline4NoSecond(double *Prt, int &cr, double &er, int &ct, double &et, int &Nc, double *val, unsigned int &NbParam) { - double Bti[4] = {0, 0, 0, 0}; - double dBti[4] = {0, 0, 0, 0}; + double Bti[4] = { 0, 0, 0, 0 }; + double dBti[4] = { 0, 0, 0, 0 }; for (char it = -1; it <= 2; it++) { Bti[it + 1] = vpTemplateTrackerBSpline::Bspline4(-it + et); @@ -638,8 +644,8 @@ void vpTemplateTrackerMIBSpline::PutTotPVBspline4NoSecond(double *Prt, int &cr, void vpTemplateTrackerMIBSpline::PutTotPVBspline4NoSecond(double *Prt, double *dPrt, int &cr, double &er, int &ct, double &et, int &Ncb, double *val, unsigned int &NbParam) { - double Bti[4] = {0, 0, 0, 0}; - double dBti[4] = {0, 0, 0, 0}; + double Bti[4] = { 0, 0, 0, 0 }; + double dBti[4] = { 0, 0, 0, 0 }; for (char it = -1; it <= 2; it++) { Bti[it + 1] = vpTemplateTrackerBSpline::Bspline4(-it + et); @@ -692,7 +698,7 @@ void vpTemplateTrackerMIBSpline::PutTotPVBspline3PrtTout(double *PrtTout, int &c et = et - 1; } - double Bti[3] = {0, 0, 0}; + double Bti[3] = { 0, 0, 0 }; for (char it = -1; it <= 1; it++) { Bti[it + 1] = Bspline3(-it + et); @@ -713,7 +719,7 @@ void vpTemplateTrackerMIBSpline::PutTotPVBspline3PrtTout(double *PrtTout, int &c void vpTemplateTrackerMIBSpline::PutTotPVBspline4PrtTout(double *PrtTout, int &cr, double &er, int &ct, double &et, int &Nc, unsigned int &NbParam) { - double Bti[4] = {0, 0, 0, 0}; + double Bti[4] = { 0, 0, 0, 0 }; for (char it = -1; it <= 2; it++) { Bti[it + 1] = vpTemplateTrackerBSpline::Bspline4(-it + et); @@ -757,7 +763,7 @@ void vpTemplateTrackerMIBSpline::PutTotPVBspline3Prt(double *Prt, int &cr, doubl et = et - 1; } - double Bti[3] = {0, 0, 0}; + double Bti[3] = { 0, 0, 0 }; for (char it = -1; it <= 1; it++) { Bti[it + 1] = Bspline3(-it + et); @@ -778,7 +784,7 @@ void vpTemplateTrackerMIBSpline::PutTotPVBspline3Prt(double *Prt, int &cr, doubl void vpTemplateTrackerMIBSpline::PutTotPVBspline4Prt(double *Prt, int &cr, double &er, int &ct, double &et, int &Ncb) { - double Bti[4] = {0, 0, 0, 0}; + double Bti[4] = { 0, 0, 0, 0 }; for (char it = -1; it <= 2; it++) { Bti[it + 1] = vpTemplateTrackerBSpline::Bspline4(-it + et); @@ -805,12 +811,13 @@ void vpTemplateTrackerMIBSpline::computeProbabilities(double *Prt, int &cr, doub PutTotPVBspline3NoSecond(Prt, cr, er, ct, et, Nc, dW, NbParam); else PutTotPVBspline4NoSecond(Prt, cr, er, ct, et, Nc, dW, NbParam); - } else { + } + else { if (bspline == 3) PutTotPVBspline3(Prt, cr, er, ct, et, Nc, dW, NbParam); else PutTotPVBspline4(Prt, cr, er, ct, et, Nc, dW, NbParam); } } - +END_VISP_NAMESPACE #endif diff --git a/modules/vision/include/visp3/vision/vpBasicKeyPoint.h b/modules/vision/include/visp3/vision/vpBasicKeyPoint.h index 612cd02db8..47c065d8b5 100644 --- a/modules/vision/include/visp3/vision/vpBasicKeyPoint.h +++ b/modules/vision/include/visp3/vision/vpBasicKeyPoint.h @@ -46,6 +46,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * \class vpBasicKeyPoint * \ingroup group_vision_keypoints @@ -53,7 +54,7 @@ * \brief class that defines what is a keypoint. This class provides * all the basic elements to implement classes which aims to match * points from an image to another. - */ +*/ class VISP_EXPORT vpBasicKeyPoint { public: @@ -279,5 +280,5 @@ class VISP_EXPORT vpBasicKeyPoint private: virtual void init() = 0; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vision/include/visp3/vision/vpCalibration.h b/modules/vision/include/visp3/vision/vpCalibration.h index fe032b46d3..3be07480ee 100644 --- a/modules/vision/include/visp3/vision/vpCalibration.h +++ b/modules/vision/include/visp3/vision/vpCalibration.h @@ -50,13 +50,14 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpCalibration * * \ingroup group_vision_calib * * \brief Tools for perspective camera calibration. - */ +*/ class VISP_EXPORT vpCalibration { public: @@ -339,5 +340,5 @@ class VISP_EXPORT vpCalibration static unsigned int m_nbIterMax; static double m_gain; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vision/include/visp3/vision/vpCalibrationException.h b/modules/vision/include/visp3/vision/vpCalibrationException.h index ab1af21145..7d574c5c76 100644 --- a/modules/vision/include/visp3/vision/vpCalibrationException.h +++ b/modules/vision/include/visp3/vision/vpCalibrationException.h @@ -40,10 +40,11 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpCalibrationException * \brief Error that can be emitted by the vpCalibration class. - */ +*/ class VISP_EXPORT vpCalibrationException : public vpException { public: @@ -90,5 +91,5 @@ class VISP_EXPORT vpCalibrationException : public vpException */ explicit vpCalibrationException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vision/include/visp3/vision/vpHandEyeCalibration.h b/modules/vision/include/visp3/vision/vpHandEyeCalibration.h index 7fadeff41f..bc30f1b6de 100644 --- a/modules/vision/include/visp3/vision/vpHandEyeCalibration.h +++ b/modules/vision/include/visp3/vision/vpHandEyeCalibration.h @@ -46,13 +46,14 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpHandEyeCalibration * * \ingroup group_vision_calib * * \brief Tool for hand-eye calibration. - */ +*/ class VISP_EXPORT vpHandEyeCalibration { public: @@ -94,5 +95,5 @@ class VISP_EXPORT vpHandEyeCalibration static int calibrationVVS(const std::vector &cMo, const std::vector &rMe, vpHomogeneousMatrix &eMc); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vision/include/visp3/vision/vpHomography.h b/modules/vision/include/visp3/vision/vpHomography.h index e05a08c887..7503232b6a 100644 --- a/modules/vision/include/visp3/vision/vpHomography.h +++ b/modules/vision/include/visp3/vision/vpHomography.h @@ -51,6 +51,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpHomography * \ingroup group_vision_homography @@ -163,7 +165,7 @@ } \endcode * - */ +*/ class VISP_EXPORT vpHomography : public vpArray2D { public: @@ -698,4 +700,6 @@ class VISP_EXPORT vpHomography : public vpArray2D static void initRansac(unsigned int n, double *xb, double *yb, double *xa, double *ya, vpColVector &x); }; +END_VISP_NAMESPACE + #endif diff --git a/modules/vision/include/visp3/vision/vpKeyPoint.h b/modules/vision/include/visp3/vision/vpKeyPoint.h index 26ffadf8c4..3fc8689679 100644 --- a/modules/vision/include/visp3/vision/vpKeyPoint.h +++ b/modules/vision/include/visp3/vision/vpKeyPoint.h @@ -73,6 +73,7 @@ #include #endif +BEGIN_VISP_NAMESPACE /*! * \class vpKeyPoint * \ingroup group_vision_keypoints group_detection_keypoint group_detection_mbt_object @@ -207,7 +208,7 @@ * \endcode * * This class is also described in \ref tutorial-matching. - */ +*/ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint { public: @@ -2252,6 +2253,6 @@ class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint #endif }; - +END_VISP_NAMESPACE #endif #endif diff --git a/modules/vision/include/visp3/vision/vpPlaneEstimation.h b/modules/vision/include/visp3/vision/vpPlaneEstimation.h index 8816bb3ce5..d3ee26e0b4 100644 --- a/modules/vision/include/visp3/vision/vpPlaneEstimation.h +++ b/modules/vision/include/visp3/vision/vpPlaneEstimation.h @@ -52,12 +52,14 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpPlaneEstimation * \ingroup group_vision_plane * * \note This class is only available with c++17 enabled. - */ +*/ class VISP_EXPORT vpPlaneEstimation { public: @@ -83,5 +85,5 @@ class VISP_EXPORT vpPlaneEstimation //! Maximal subsampling factor applied to the point cloud to estimate a plane static constexpr auto MaxSubSampFactorToEstimatePlane { 20u }; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vision/include/visp3/vision/vpPose.h b/modules/vision/include/visp3/vision/vpPose.h index 87dd3a3e38..faf3337222 100644 --- a/modules/vision/include/visp3/vision/vpPose.h +++ b/modules/vision/include/visp3/vision/vpPose.h @@ -62,6 +62,8 @@ #include +BEGIN_VISP_NAMESPACE + /*! * \class vpPose * \ingroup group_vision_pose @@ -73,7 +75,7 @@ * vpPoseFeatures class. * * To see how to use this class you can follow the \ref tutorial-pose-estimation. - */ +*/ class VISP_EXPORT vpPose { public: @@ -881,4 +883,6 @@ class VISP_EXPORT vpPose }; }; +END_VISP_NAMESPACE + #endif diff --git a/modules/vision/include/visp3/vision/vpPoseException.h b/modules/vision/include/visp3/vision/vpPoseException.h index ed749e1d82..00172ef0fd 100644 --- a/modules/vision/include/visp3/vision/vpPoseException.h +++ b/modules/vision/include/visp3/vision/vpPoseException.h @@ -39,11 +39,13 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! * \class vpPoseException * \ingroup group_vision_pose * \brief Error that can be emitted by the vpPose class and its derivatives. - */ +*/ class VISP_EXPORT vpPoseException : public vpException { public: @@ -89,4 +91,6 @@ class VISP_EXPORT vpPoseException : public vpException explicit vpPoseException(int id) : vpException(id) { } }; +END_VISP_NAMESPACE + #endif diff --git a/modules/vision/include/visp3/vision/vpPoseFeatures.h b/modules/vision/include/visp3/vision/vpPoseFeatures.h index 7428e422c5..4a79507bcd 100644 --- a/modules/vision/include/visp3/vision/vpPoseFeatures.h +++ b/modules/vision/include/visp3/vision/vpPoseFeatures.h @@ -62,6 +62,8 @@ #include #include +BEGIN_VISP_NAMESPACE + #ifndef DOXYGEN_SHOULD_SKIP_THIS //################################################# //## Call a function with a tuple as parameters @@ -806,6 +808,8 @@ void vpPoseFeatures::addSpecificFeature(ObjType *obj, RetType(ObjType:: *fct_ptr if (m_featureSpecific_list.size() > m_maxSize) m_maxSize = static_cast(m_featureSpecific_list.size()); } + +END_VISP_NAMESPACE #endif #endif diff --git a/modules/vision/include/visp3/vision/vpXmlConfigParserKeyPoint.h b/modules/vision/include/visp3/vision/vpXmlConfigParserKeyPoint.h index eaf7e67cfb..0658ead0ea 100644 --- a/modules/vision/include/visp3/vision/vpXmlConfigParserKeyPoint.h +++ b/modules/vision/include/visp3/vision/vpXmlConfigParserKeyPoint.h @@ -47,6 +47,7 @@ #if defined(VISP_HAVE_PUGIXML) #include +BEGIN_VISP_NAMESPACE /*! * \class vpXmlConfigParserKeyPoint * \ingroup group_vision_keypoints @@ -55,7 +56,7 @@ * XML file for vpKeyPoint class. * * \warning This class is only available if pugixml is successfully built. - */ +*/ class VISP_EXPORT vpXmlConfigParserKeyPoint { public: @@ -198,5 +199,6 @@ class VISP_EXPORT vpXmlConfigParserKeyPoint //! Pointer to implementation Impl *m_impl; }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/vision/src/calibration/vpCalibration.cpp b/modules/vision/src/calibration/vpCalibration.cpp index 0f2c53ec32..5c4cc80b52 100644 --- a/modules/vision/src/calibration/vpCalibration.cpp +++ b/modules/vision/src/calibration/vpCalibration.cpp @@ -41,6 +41,8 @@ #include #include +BEGIN_VISP_NAMESPACE + double vpCalibration::m_threshold = 1e-10f; unsigned int vpCalibration::m_nbIterMax = 4000; double vpCalibration::m_gain = 0.25; @@ -630,3 +632,4 @@ void vpCalibration::setAspectRatio(double aspect_ratio) m_aspect_ratio = aspect_ratio; } } +END_VISP_NAMESPACE diff --git a/modules/vision/src/calibration/vpCalibrationTools.cpp b/modules/vision/src/calibration/vpCalibrationTools.cpp index a4965614a3..35ce75a0e5 100644 --- a/modules/vision/src/calibration/vpCalibrationTools.cpp +++ b/modules/vision/src/calibration/vpCalibrationTools.cpp @@ -37,7 +37,6 @@ #include #include // std::fabs -#include // numeric_limits #define DEBUG_LEVEL1 0 #define DEBUG_LEVEL2 0 @@ -45,6 +44,7 @@ #undef MAX /* FC unused anywhere */ #undef MIN /* FC unused anywhere */ +BEGIN_VISP_NAMESPACE void vpCalibration::calibLagrange(vpCameraParameters &cam_est, vpHomogeneousMatrix &cMo_est) { @@ -1222,6 +1222,6 @@ void vpCalibration::calibVVSWithDistortionMulti(unsigned int nbPose, vpCalibrati table_cal[i] = v_table_cal[i]; } } - +END_VISP_NAMESPACE #undef DEBUG_LEVEL1 #undef DEBUG_LEVEL2 diff --git a/modules/vision/src/calibration/vpHandEyeCalibration.cpp b/modules/vision/src/calibration/vpHandEyeCalibration.cpp index 90d41e3f2b..6ba6492a0f 100644 --- a/modules/vision/src/calibration/vpHandEyeCalibration.cpp +++ b/modules/vision/src/calibration/vpHandEyeCalibration.cpp @@ -39,6 +39,8 @@ #define DEBUG_LEVEL1 0 #define DEBUG_LEVEL2 0 +BEGIN_VISP_NAMESPACE + /*! \brief Compute the distances of the data to the mean obtained. @@ -1023,6 +1025,8 @@ int vpHandEyeCalibration::calibrate(const std::vector &cMo, return err; } +END_VISP_NAMESPACE + #undef HE_I #undef HE_TSAI_OROT #undef HE_TSAI_ORNT diff --git a/modules/vision/src/homography-estimation/vpHomography.cpp b/modules/vision/src/homography-estimation/vpHomography.cpp index 9b9dd5d1ff..ccf7b944fc 100644 --- a/modules/vision/src/homography-estimation/vpHomography.cpp +++ b/modules/vision/src/homography-estimation/vpHomography.cpp @@ -48,6 +48,8 @@ #include #include +BEGIN_VISP_NAMESPACE + vpHomography::vpHomography() : vpArray2D(3, 3), m_aMb(), m_bP() { eye(); } vpHomography::vpHomography(const vpHomography &H) : vpArray2D(3, 3), m_aMb(), m_bP() { *this = H; } @@ -713,3 +715,5 @@ vpHomography vpHomography::homography2collineation(const vpCameraParameters &cam return H; } + +END_VISP_NAMESPACE diff --git a/modules/vision/src/homography-estimation/vpHomographyDLT.cpp b/modules/vision/src/homography-estimation/vpHomographyDLT.cpp index 7025c9f5c5..46aea9a2f5 100644 --- a/modules/vision/src/homography-estimation/vpHomographyDLT.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyDLT.cpp @@ -45,6 +45,8 @@ #include // std::fabs #include // numeric_limits +BEGIN_VISP_NAMESPACE + #ifndef DOXYGEN_SHOULD_SKIP_THIS void vpHomography::hartleyNormalization(const std::vector &x, const std::vector &y, @@ -308,3 +310,5 @@ void vpHomography::DLT(const std::vector &xb, const std::vector aHb = aHbn; } } + +END_VISP_NAMESPACE diff --git a/modules/vision/src/homography-estimation/vpHomographyExtract.cpp b/modules/vision/src/homography-estimation/vpHomographyExtract.cpp index 3af2843954..2ebec6a37c 100644 --- a/modules/vision/src/homography-estimation/vpHomographyExtract.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyExtract.cpp @@ -35,6 +35,8 @@ #include #include +BEGIN_VISP_NAMESPACE + //#define DEBUG_Homographie 0 /* ---------------------------------------------------------------------- */ @@ -137,28 +139,33 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, const vpColVecto vOrdre[0] = 0; vOrdre[1] = 1; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 0; vOrdre[1] = 2; vOrdre[2] = 1; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 0; vOrdre[2] = 1; } - } else { + } + else { if (svTemp[1] >= svTemp[2]) { if (svTemp[0] > svTemp[2]) { vOrdre[0] = 1; vOrdre[1] = 0; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 1; vOrdre[1] = 2; vOrdre[2] = 0; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 1; vOrdre[2] = 0; @@ -220,7 +227,8 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, const vpColVecto n[0] = normaleDesiree[0]; n[1] = normaleDesiree[1]; n[2] = normaleDesiree[2]; - } else { + } + else { #ifdef DEBUG_Homographie printf("\nCas general\n"); #endif @@ -318,7 +326,7 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, const vpColVecto de la solution retenue (cf. ci-dessous) *****/ sinusTheta = - (signeSinus * sqrt(((sv[0] * sv[0]) - (sv[1] * sv[1])) * ((sv[1] * sv[1]) - (sv[2] * sv[2])))) / ((sv[0] + sv[2]) * sv[1]); + (signeSinus * sqrt(((sv[0] * sv[0]) - (sv[1] * sv[1])) * ((sv[1] * sv[1]) - (sv[2] * sv[2])))) / ((sv[0] + sv[2]) * sv[1]); cosinusTheta = ((sv[1] * sv[1]) + (sv[0] * sv[2])) / ((sv[0] + sv[2]) * sv[1]); @@ -434,28 +442,33 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, vpRotationMatrix vOrdre[0] = 0; vOrdre[1] = 1; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 0; vOrdre[1] = 2; vOrdre[2] = 1; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 0; vOrdre[2] = 1; } - } else { + } + else { if (svTemp[1] >= svTemp[2]) { if (svTemp[0] > svTemp[2]) { vOrdre[0] = 1; vOrdre[1] = 0; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 1; vOrdre[1] = 2; vOrdre[2] = 0; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 1; vOrdre[2] = 0; @@ -517,7 +530,8 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, vpRotationMatrix n[0] = normaleDesiree[0]; n[1] = normaleDesiree[1]; n[2] = normaleDesiree[2]; - } else { + } + else { #ifdef DEBUG_Homographie printf("\nCas general\n"); #endif @@ -550,7 +564,7 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, vpRotationMatrix for (unsigned int i = 0; i < 3; ++i) { normaleEstimee[i] = 0.0; for (unsigned int j = 0; j < 3; ++j) { - normaleEstimee[i] += ((2.0 * k )- 1.0) * mV[i][j] * mX[j][w]; + normaleEstimee[i] += ((2.0 * k)- 1.0) * mV[i][j] * mX[j][w]; } } @@ -615,7 +629,7 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, vpRotationMatrix de la solution retenue (cf. ci-dessous) *****/ sinusTheta = - (signeSinus * sqrt(((sv[0] * sv[0]) - (sv[1] * sv[1])) * ((sv[1] * sv[1]) - (sv[2] * sv[2])))) / ((sv[0] + sv[2]) * sv[1]); + (signeSinus * sqrt(((sv[0] * sv[0]) - (sv[1] * sv[1])) * ((sv[1] * sv[1]) - (sv[2] * sv[2])))) / ((sv[0] + sv[2]) * sv[1]); cosinusTheta = ((sv[1] * sv[1]) + (sv[0] * sv[2])) / ((sv[0] + sv[2]) * sv[1]); @@ -713,28 +727,33 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y vOrdre[0] = 0; vOrdre[1] = 1; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 0; vOrdre[1] = 2; vOrdre[2] = 1; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 0; vOrdre[2] = 1; } - } else { + } + else { if (svTemp[1] >= svTemp[2]) { if (svTemp[0] > svTemp[2]) { vOrdre[0] = 1; vOrdre[1] = 0; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 1; vOrdre[1] = 2; vOrdre[2] = 0; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 1; vOrdre[2] = 0; @@ -764,10 +783,10 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // calcul du determinant de U et V determinantU = (U[0][0] * ((U[1][1] * U[2][2]) - (U[1][2] * U[2][1]))) + (U[0][1] * ((U[1][2] * U[2][0]) - (U[1][0] * U[2][2]))) + - (U[0][2] * ((U[1][0] * U[2][1]) - (U[1][1] * U[2][0]))); + (U[0][2] * ((U[1][0] * U[2][1]) - (U[1][1] * U[2][0]))); determinantV = (V[0][0] * ((V[1][1] * V[2][2]) - (V[1][2] * V[2][1]))) + (V[0][1] * ((V[1][2] * V[2][0]) - (V[1][0] * V[2][2]))) + - (V[0][2] * ((V[1][0] * V[2][1]) - (V[1][1] * V[2][0]))); + (V[0][2] * ((V[1][0] * V[2][1]) - (V[1][1] * V[2][0]))); s = determinantU * determinantV; @@ -807,7 +826,8 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y else { cas = cas2; } - } else { + } + else { if ((sv[1] - sv[2]) < m_sing_threshold) { cas = cas3; } @@ -930,7 +950,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim1[2][0] = (sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] + sv[2]) * sv[1]); + ((sv[0] + sv[2]) * sv[1]); Rprim1[0][2] = -Rprim1[2][0]; @@ -952,7 +972,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim2[2][0] = -(sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] + sv[2]) * sv[1]); + ((sv[0] + sv[2]) * sv[1]); Rprim2[0][2] = -Rprim2[2][0]; @@ -974,7 +994,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim3[2][0] = -(sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] + sv[2]) * sv[1]); + ((sv[0] + sv[2]) * sv[1]); Rprim3[0][2] = -Rprim3[2][0]; @@ -996,7 +1016,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim4[2][0] = (sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] + sv[2]) * sv[1]); + ((sv[0] + sv[2]) * sv[1]); Rprim4[0][2] = -Rprim4[2][0]; @@ -1061,7 +1081,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim1[2][0] = (sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] - sv[2]) * sv[1]); + ((sv[0] - sv[2]) * sv[1]); Rprim1[0][2] = Rprim1[2][0]; @@ -1083,7 +1103,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim2[2][0] = -(sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] - sv[2]) * sv[1]); + ((sv[0] - sv[2]) * sv[1]); Rprim2[0][2] = Rprim2[2][0]; @@ -1105,7 +1125,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim3[2][0] = -(sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] - sv[2]) * sv[1]); + ((sv[0] - sv[2]) * sv[1]); Rprim3[0][2] = Rprim3[2][0]; @@ -1126,7 +1146,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim4[2][0] = (sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] - sv[2]) * sv[1]); + ((sv[0] - sv[2]) * sv[1]); Rprim4[0][2] = Rprim4[2][0]; @@ -1232,14 +1252,15 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y vT.push_back(T4); vN.push_back(N4); } - } else { + } + else { std::cout << "On tombe dans le cas particulier ou le mouvement n'est pas " - "estimable!" - << std::endl; + "estimable!" + << std::endl; } - #ifdef DEBUG_Homographie - // on peut ensuite afficher les resultats... +#ifdef DEBUG_Homographie +// on peut ensuite afficher les resultats... std::cout << "Analyse des resultats : "<< std::endl; if (cas==cas1) { std::cout << "On est dans le cas 1" << std::endl; @@ -1260,10 +1281,12 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y else { std::cout << "d'>0" << std::endl; } - #endif +#endif #ifdef DEBUG_Homographie printf("fin : Homographie_EstimationDeplacementCamera\n"); #endif } #endif //#ifndef DOXYGEN_SHOULD_SKIP_THIS + +END_VISP_NAMESPACE diff --git a/modules/vision/src/homography-estimation/vpHomographyMalis.cpp b/modules/vision/src/homography-estimation/vpHomographyMalis.cpp index 69fb836691..863f0c0cb0 100644 --- a/modules/vision/src/homography-estimation/vpHomographyMalis.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyMalis.cpp @@ -47,8 +47,8 @@ #include #include // std::fabs -#include // numeric_limits +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS namespace @@ -623,7 +623,9 @@ void vpHomography::HLM(const std::vector &xb, const std::vector q_cible = 3; } - ::hlm(q_cible, xa, ya, xb, yb, H); + hlm(q_cible, xa, ya, xb, yb, H); aHb = H; } + +END_VISP_NAMESPACE diff --git a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp index bd0e5fae50..52c09b479b 100644 --- a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp @@ -39,6 +39,8 @@ #include #include +BEGIN_VISP_NAMESPACE + #define VPEPS 1e-6 /*! @@ -528,3 +530,5 @@ bool vpHomography::ransac(const std::vector &xb, const std::vector #include +BEGIN_VISP_NAMESPACE + const double vpHomography::m_threshold_rotation = 1e-7; const double vpHomography::m_threshold_displacement = 1e-18; @@ -696,3 +698,5 @@ double vpHomography::computeDisplacement(unsigned int nbpoint, vpPoint *c1P, vpP } #endif //#ifndef DOXYGEN_SHOULD_SKIP_THIS + +END_VISP_NAMESPACE diff --git a/modules/vision/src/key-point/vpKeyPoint.cpp b/modules/vision/src/key-point/vpKeyPoint.cpp index b0e6d5bf20..af463e54ef 100644 --- a/modules/vision/src/key-point/vpKeyPoint.cpp +++ b/modules/vision/src/key-point/vpKeyPoint.cpp @@ -43,6 +43,8 @@ #include #endif +BEGIN_VISP_NAMESPACE + namespace { // Specific Type transformation functions @@ -4216,6 +4218,8 @@ void vpKeyPoint::PyramidAdaptedFeatureDetector::detectImpl(const cv::Mat &image, #endif #endif +END_VISP_NAMESPACE + #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_vision.a(vpKeyPoint.cpp.o) has no symbols void dummy_vpKeyPoint() { }; diff --git a/modules/vision/src/key-point/vpXmlConfigParserKeyPoint.cpp b/modules/vision/src/key-point/vpXmlConfigParserKeyPoint.cpp index d6f3da952c..6c5966df62 100644 --- a/modules/vision/src/key-point/vpXmlConfigParserKeyPoint.cpp +++ b/modules/vision/src/key-point/vpXmlConfigParserKeyPoint.cpp @@ -48,6 +48,7 @@ #include +BEGIN_VISP_NAMESPACE #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpXmlConfigParserKeyPoint::Impl { @@ -546,7 +547,7 @@ bool vpXmlConfigParserKeyPoint::getUseRansacVVSPoseEstimation() const { return m_impl->getUseRansacVVSPoseEstimation(); } - +END_VISP_NAMESPACE #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpXmlConfigParserKeyPoint.cpp.o) has no symbols void dummy_vpXmlConfigParserKeyPoint() { }; diff --git a/modules/vision/src/plane-estimation/vpPlaneEstimation.cpp b/modules/vision/src/plane-estimation/vpPlaneEstimation.cpp index 1c9c13e78c..353b2200c6 100644 --- a/modules/vision/src/plane-estimation/vpPlaneEstimation.cpp +++ b/modules/vision/src/plane-estimation/vpPlaneEstimation.cpp @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE // Local helpers namespace { @@ -298,5 +299,5 @@ vpPlaneEstimation::estimatePlane(const vpImage &I_depth_raw, double de return estimatePlaneEquationSVD(pt_cloud); } } - +END_VISP_NAMESPACE #endif diff --git a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp index a6e091c56e..968e3cd60c 100644 --- a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp +++ b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp @@ -39,6 +39,8 @@ #include #include "vpLevenbergMarquartd.h" +BEGIN_VISP_NAMESPACE + #define SIGN(x) ((x) < 0 ? -1 : 1) #define SWAP(a, b, c) \ { \ @@ -1205,3 +1207,5 @@ int lmder1(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, #undef TRUE #undef FALSE + +END_VISP_NAMESPACE diff --git a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h index 768dcba371..b0daf95bf1 100644 --- a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h +++ b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h @@ -43,6 +43,8 @@ #include #include +BEGIN_VISP_NAMESPACE + /*! * ENTREE : * n Ordre de la matrice "r". @@ -459,4 +461,6 @@ int VISP_EXPORT lmder1(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, int m, int n, double *x, double *fvec, double *fjac, int ldfjac, double tol, int *info, int *ipvt, int lwa, double *wa); +END_VISP_NAMESPACE + #endif diff --git a/modules/vision/src/pose-estimation/vpPose.cpp b/modules/vision/src/pose-estimation/vpPose.cpp index e010fa5edd..bab5cc65fa 100644 --- a/modules/vision/src/pose-estimation/vpPose.cpp +++ b/modules/vision/src/pose-estimation/vpPose.cpp @@ -49,6 +49,8 @@ #include // std::fabs #include // numeric_limits +BEGIN_VISP_NAMESPACE + #define DEBUG_LEVEL1 0 vpPose::vpPose() @@ -663,3 +665,5 @@ double vpPose::poseFromRectangle(vpPoint &p1, vpPoint &p2, vpPoint &p3, vpPoint P.computePose(vpPose::DEMENTHON_LOWE, cMo); return lx / s; } + +END_VISP_NAMESPACE diff --git a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp index cfa8763aeb..d05074fb5c 100644 --- a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp +++ b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp @@ -34,6 +34,8 @@ #include #include +BEGIN_VISP_NAMESPACE + #define DEBUG_LEVEL1 0 #define DEBUG_LEVEL2 0 #define DEBUG_LEVEL3 0 @@ -477,7 +479,8 @@ void vpPose::poseDementhonPlan(vpHomogeneousMatrix &cMo) int nbMaxIter = static_cast(std::max(std::ceil(logNOfSvdThresholdLimit - logNofSvdThresh), 1.)); double svdThreshold = m_dementhonSvThresh; int irank = 0; - for (int i = 0; (i < nbMaxIter) && (!isRankEqualTo3); ++i) { + int i = 0; + while ((i < nbMaxIter) && (!isRankEqualTo3)) { irank = A.pseudoInverse(Ap, sv, svdThreshold, imA, imAt, kAt); if (irank == 3) { isRankEqualTo3 = true; @@ -486,6 +489,7 @@ void vpPose::poseDementhonPlan(vpHomogeneousMatrix &cMo) isRankEqualTo3 = false; svdThreshold *= svdFactorUsedWhenFailure; } + ++i; } if (!isRankEqualTo3) { @@ -612,3 +616,5 @@ double vpPose::computeResidualDementhon(const vpHomogeneousMatrix &cMo) #undef DEBUG_LEVEL1 #undef DEBUG_LEVEL2 #undef DEBUG_LEVEL3 + +END_VISP_NAMESPACE diff --git a/modules/vision/src/pose-estimation/vpPoseFeatures.cpp b/modules/vision/src/pose-estimation/vpPoseFeatures.cpp index 113fd30b2c..1033a7fd5b 100644 --- a/modules/vision/src/pose-estimation/vpPoseFeatures.cpp +++ b/modules/vision/src/pose-estimation/vpPoseFeatures.cpp @@ -34,6 +34,8 @@ #if defined(VISP_HAVE_MODULE_VISUAL_FEATURES) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +BEGIN_VISP_NAMESPACE + vpPoseFeatures::vpPoseFeatures() : m_maxSize(0), m_totalSize(0), m_vvsIterMax(200), m_lambda(1.0), m_verbose(false), m_computeCovariance(false), m_covarianceMatrix(), m_featurePoint_Point_list(), m_featurePoint3D_Point_list(), m_featureVanishingPoint_Point_list(), @@ -462,6 +464,9 @@ void vpPoseFeatures::computePoseRobustVVS(vpHomogeneousMatrix &cMo) throw; } } + +END_VISP_NAMESPACE + #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_vision.a(vpPoseFeatures.cpp.o) has no symbols void dummy_vpPoseFeatures() { }; diff --git a/modules/vision/src/pose-estimation/vpPoseLagrange.cpp b/modules/vision/src/pose-estimation/vpPoseLagrange.cpp index e0d778dbac..e497f4dcf2 100644 --- a/modules/vision/src/pose-estimation/vpPoseLagrange.cpp +++ b/modules/vision/src/pose-estimation/vpPoseLagrange.cpp @@ -33,6 +33,8 @@ #include +BEGIN_VISP_NAMESPACE + #define DEBUG_LEVEL1 0 #define DEBUG_LEVEL2 0 @@ -586,3 +588,5 @@ void vpPose::poseLagrangeNonPlan(vpHomogeneousMatrix &cMo) #undef DEBUG_LEVEL1 #undef DEBUG_LEVEL2 + +END_VISP_NAMESPACE diff --git a/modules/vision/src/pose-estimation/vpPoseLowe.cpp b/modules/vision/src/pose-estimation/vpPoseLowe.cpp index 1544b01bcc..16350f1714 100644 --- a/modules/vision/src/pose-estimation/vpPoseLowe.cpp +++ b/modules/vision/src/pose-estimation/vpPoseLowe.cpp @@ -41,6 +41,8 @@ #include "private/vpLevenbergMarquartd.h" #include +BEGIN_VISP_NAMESPACE + #define NBR_PAR 6 #define X3_SIZE 3 #define MINIMUM 0.000001 @@ -329,3 +331,5 @@ void vpPose::poseLowe(vpHomogeneousMatrix &cMo) #undef MINIMUM #undef DEBUG_LEVEL1 + +END_VISP_NAMESPACE diff --git a/modules/vision/src/pose-estimation/vpPoseRGBD.cpp b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp index bd519fccc4..93341e04ed 100644 --- a/modules/vision/src/pose-estimation/vpPoseRGBD.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp @@ -37,8 +37,8 @@ #include #include -namespace -{ +BEGIN_VISP_NAMESPACE + // See also vpPlaneEstimation.cpp that implements the same functionaly in c++17 void estimatePlaneEquationSVD(const std::vector &point_cloud_face, vpPlane &plane_equation_estimated, vpColVector ¢roid, double &normalized_weights) @@ -56,7 +56,8 @@ void estimatePlaneEquationSVD(const std::vector &point_cloud_face, vpPla vpColVector normal; double fabs_error_m_prev_error = std::fabs(error - prev_error); - for (unsigned int iter = 0; (iter < max_iter) && (fabs_error_m_prev_error > 1e-6); ++iter) { + unsigned int iter = 0; + while ((iter < max_iter) && (fabs_error_m_prev_error > 1e-6)) { if (iter != 0) { tukey.MEstimator(vpRobust::TUKEY, residues, weights); } @@ -116,6 +117,8 @@ void estimatePlaneEquationSVD(const std::vector &point_cloud_face, vpPla error /= total_w; // evaluate one of the end conditions of the for fabs_error_m_prev_error = std::fabs(error - prev_error); + + ++iter; } // Update final weights @@ -146,8 +149,6 @@ void estimatePlaneEquationSVD(const std::vector &point_cloud_face, vpPla normalized_weights = total_w / nPoints; } -} // namespace - bool vpPose::computePlanarObjectPoseFromRGBD(const vpImage &depthMap, const std::vector &corners, const vpCameraParameters &colorIntrinsics, const std::vector &point3d, vpHomogeneousMatrix &cMo, @@ -445,3 +446,5 @@ bool vpPose::computePlanarObjectPoseFromRGBD(const vpImage &depthMap, } return false; } + +END_VISP_NAMESPACE diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index 89ebc2ffb8..c461804263 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -53,6 +53,7 @@ #include #endif +BEGIN_VISP_NAMESPACE #define EPS 1e-6 namespace @@ -592,3 +593,5 @@ void vpPose::findMatch(std::vector &p2D, std::vector &p3D, listInliers = pose.getRansacInliers(); } } + +END_VISP_NAMESPACE diff --git a/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp b/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp index 5a47dd1103..0046accfd0 100644 --- a/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp +++ b/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp @@ -42,6 +42,8 @@ #include #include +BEGIN_VISP_NAMESPACE + void vpPose::poseVirtualVS(vpHomogeneousMatrix &cMo) { try { @@ -354,3 +356,5 @@ std::optional vpPose::poseVirtualVSWithDepth(const std::vec } #endif + +END_VISP_NAMESPACE diff --git a/modules/vision/test/homography/testDisplacement.cpp b/modules/vision/test/homography/testDisplacement.cpp index 0c57e3962f..f0284e9511 100644 --- a/modules/vision/test/homography/testDisplacement.cpp +++ b/modules/vision/test/homography/testDisplacement.cpp @@ -48,6 +48,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + bool test(const std::string &s, const vpHomography &H, const std::vector &bench) { static unsigned int cpt = 0; @@ -182,7 +186,8 @@ int main() } std::cout << "All tests succeed" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp index edcbab6cd3..025a6a2dec 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp @@ -52,6 +52,10 @@ // List of allowed command line options #define GETOPTARGS "cdph" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp index 1040f85c2f..37552fe411 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-3.cpp @@ -53,6 +53,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -244,12 +248,14 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis if (button == vpMouseButton::button3) { opt_click = false; } - } else { - // Use right click to enable/disable step by step tracking + } + else { + // Use right click to enable/disable step by step tracking if (vpDisplay::getClick(Imatch, button, false)) { if (button == vpMouseButton::button3) { opt_click = true; - } else if (button == vpMouseButton::button1) { + } + else if (button == vpMouseButton::button1) { break; } } @@ -282,8 +288,8 @@ int main(int argc, const char **argv) if (env_ipath.empty()) { std::cerr << "Please set the VISP_INPUT_IMAGE_PATH environment " - "variable value." - << std::endl; + "variable value." + << std::endl; return EXIT_FAILURE; } @@ -301,7 +307,8 @@ int main(int argc, const char **argv) run_test(env_ipath, opt_click_allowed, opt_display, Iref, Icur, Imatch); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp index 2dfd21d68f..e310246933 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-4.cpp @@ -54,6 +54,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp index 203f764ac9..cc874ebfd4 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-5.cpp @@ -48,13 +48,13 @@ #include #include - - - - // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp index d8fd45b188..0e5d86ace9 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-6.cpp @@ -50,6 +50,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -265,7 +269,8 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis ss << "No keypoints detected with " << detectorName << " and image:" << filename << "." << std::endl; throw(vpException(vpException::fatalError, ss.str())); } - } else if (*itd == "AKAZE") { + } + else if (*itd == "AKAZE") { detectorName = "AKAZE"; keyPoints.setDetector(detectorName); keyPoints.detect(I, kpts); @@ -275,13 +280,14 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis ss << "No keypoints detected with " << detectorName << " and image:" << filename << "." << std::endl; throw(vpException(vpException::fatalError, ss.str())); } - } else if (*itd == "BoostDesc") { + } + else if (*itd == "BoostDesc") { #if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(VISP_HAVE_OPENCV_XFEATURES2D) cv::Ptr boostDesc = keyPoints.getExtractor("BoostDesc"); // Init BIN BOOST descriptor for FAST keypoints boostDesc = cv::xfeatures2d::BoostDesc::create(cv::xfeatures2d::BoostDesc::BINBOOST_256, true, 5.0f); #endif - } + } double t = vpTime::measureTimeMs(); cv::Mat descriptor; @@ -289,8 +295,8 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis t = vpTime::measureTimeMs() - t; std::cout << "Descriptor: " << descriptor.rows << "x" << descriptor.cols - << " (rows x cols) ; type=" << getOpenCVType(descriptor.type()) << " for " << *itd << " method in " << t - << " ms." << std::endl; + << " (rows x cols) ; type=" << getOpenCVType(descriptor.type()) << " for " << *itd << " method in " << t + << " ms." << std::endl; if (descriptor.empty()) { std::stringstream ss; ss << "No descriptor extracted with " << *itd << " and image:" << filename << "." << std::endl; @@ -313,7 +319,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis vpDisplay::getClick(I); } } - } + } std::cout << "\n\n"; @@ -332,7 +338,8 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis ss << "No keypoints detected with " << detectorName << " and image:" << filename << "." << std::endl; throw(vpException(vpException::fatalError, ss.str())); } - } else if (mapOfDescriptorNames[(vpKeyPoint::vpFeatureDescriptorType)i] == "AKAZE") { + } + else if (mapOfDescriptorNames[(vpKeyPoint::vpFeatureDescriptorType)i] == "AKAZE") { detectorName = "AKAZE"; keyPoints.setDetector(detectorName); keyPoints.detect(I, kpts); @@ -342,7 +349,8 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis ss << "No keypoints detected with " << detectorName << " and image:" << filename << "." << std::endl; throw(vpException(vpException::fatalError, ss.str())); } - } else if (mapOfDescriptorNames[(vpKeyPoint::vpFeatureDescriptorType)i] == "BoostDesc") { + } + else if (mapOfDescriptorNames[(vpKeyPoint::vpFeatureDescriptorType)i] == "BoostDesc") { #if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(VISP_HAVE_OPENCV_XFEATURES2D) detectorName = "FAST"; keyPoints.setDetector(detectorName); @@ -358,7 +366,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis // Init BIN BOOST descriptor for FAST keypoints boostDesc = cv::xfeatures2d::BoostDesc::create(cv::xfeatures2d::BoostDesc::BINBOOST_256, true, 5.0f); #endif - } + } double t = vpTime::measureTimeMs(); cv::Mat descriptor; @@ -366,13 +374,13 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis t = vpTime::measureTimeMs() - t; std::cout << "Descriptor: " << descriptor.rows << "x" << descriptor.cols - << " (rows x cols) ; type=" << getOpenCVType(descriptor.type()) << " for " - << mapOfDescriptorNames[(vpKeyPoint::vpFeatureDescriptorType)i] << " method in " << t << " ms." - << std::endl; + << " (rows x cols) ; type=" << getOpenCVType(descriptor.type()) << " for " + << mapOfDescriptorNames[(vpKeyPoint::vpFeatureDescriptorType)i] << " method in " << t << " ms." + << std::endl; if (descriptor.empty()) { std::stringstream ss; ss << "No descriptor extracted with " << mapOfDescriptorNames[(vpKeyPoint::vpFeatureDescriptorType)i] - << " and image:" << filename << "." << std::endl; + << " and image:" << filename << "." << std::endl; throw(vpException(vpException::fatalError, ss.str())); } @@ -392,14 +400,14 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis vpDisplay::getClick(I); } } + } } -} -/*! - \example testKeyPoint-6.cpp + /*! + \example testKeyPoint-6.cpp - \brief Test descriptor extraction. -*/ + \brief Test descriptor extraction. + */ int main(int argc, const char **argv) { try { @@ -418,8 +426,8 @@ int main(int argc, const char **argv) if (env_ipath.empty()) { std::cerr << "Please set the VISP_INPUT_IMAGE_PATH environment " - "variable value." - << std::endl; + "variable value." + << std::endl; return EXIT_FAILURE; } @@ -437,7 +445,8 @@ int main(int argc, const char **argv) run_test(env_ipath, opt_click_allowed, opt_display, Iinput, I); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp index b66df93f4d..b526fe8090 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-7.cpp @@ -48,6 +48,10 @@ // List of allowed command line options #define GETOPTARGS "cdo:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + /*! Print the program options. diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp index 7240c1e375..2c833c7347 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint.cpp @@ -51,6 +51,10 @@ // List of allowed command line options #define GETOPTARGS "cdh" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam); bool getOptions(int argc, const char **argv, bool &click_allowed, bool &display); @@ -205,12 +209,14 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis if (button == vpMouseButton::button3) { opt_click = false; } - } else { - // Use right click to enable/disable step by step tracking + } + else { + // Use right click to enable/disable step by step tracking if (vpDisplay::getClick(Imatch, button, false)) { if (button == vpMouseButton::button3) { opt_click = true; - } else if (button == vpMouseButton::button1) { + } + else if (button == vpMouseButton::button1) { break; } } @@ -242,8 +248,8 @@ int main(int argc, const char **argv) if (env_ipath.empty()) { std::cerr << "Please set the VISP_INPUT_IMAGE_PATH environment " - "variable value." - << std::endl; + "variable value." + << std::endl; return EXIT_FAILURE; } @@ -261,7 +267,8 @@ int main(int argc, const char **argv) run_test(env_ipath, opt_click_allowed, opt_display, Iref, Icur, Imatch); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/vision/test/keypoint-with-dataset/testXmlConfigParserKeyPoint.cpp b/modules/vision/test/keypoint-with-dataset/testXmlConfigParserKeyPoint.cpp index 549f5a4c7a..04bd9ca326 100644 --- a/modules/vision/test/keypoint-with-dataset/testXmlConfigParserKeyPoint.cpp +++ b/modules/vision/test/keypoint-with-dataset/testXmlConfigParserKeyPoint.cpp @@ -42,6 +42,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + #if defined(VISP_HAVE_PUGIXML) std::string visp_images_dir = vpIoTools::getViSPImagesDataPath(); if (vpIoTools::checkDirectory(visp_images_dir + "/xml")) { diff --git a/modules/vision/test/pose-with-dataset/testPoseRansac2.cpp b/modules/vision/test/pose-with-dataset/testPoseRansac2.cpp index 19a6cb3ac0..a332b544ed 100644 --- a/modules/vision/test/pose-with-dataset/testPoseRansac2.cpp +++ b/modules/vision/test/pose-with-dataset/testPoseRansac2.cpp @@ -47,16 +47,20 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + namespace { #if (VISP_HAVE_DATASET_VERSION >= 0x030300) bool samePoints(const vpPoint &pt1, const vpPoint &pt2) { return vpMath::equal(pt1.get_oX(), pt2.get_oX(), std::numeric_limits::epsilon()) && - vpMath::equal(pt1.get_oY(), pt2.get_oY(), std::numeric_limits::epsilon()) && - vpMath::equal(pt1.get_oZ(), pt2.get_oZ(), std::numeric_limits::epsilon()) && - vpMath::equal(pt1.get_x(), pt2.get_x(), std::numeric_limits::epsilon()) && - vpMath::equal(pt1.get_y(), pt2.get_y(), std::numeric_limits::epsilon()); + vpMath::equal(pt1.get_oY(), pt2.get_oY(), std::numeric_limits::epsilon()) && + vpMath::equal(pt1.get_oZ(), pt2.get_oZ(), std::numeric_limits::epsilon()) && + vpMath::equal(pt1.get_x(), pt2.get_x(), std::numeric_limits::epsilon()) && + vpMath::equal(pt1.get_y(), pt2.get_y(), std::numeric_limits::epsilon()); } int checkInlierIndex(const std::vector &vectorOfFoundInlierIndex, @@ -81,16 +85,16 @@ bool checkInlierPoints(const std::vector &vectorOfFoundInlierPoints, for (size_t i = 0; i < vectorOfFoundInlierPoints.size(); i++) { if (!samePoints(vectorOfFoundInlierPoints[i], bunnyModelPoints_noisy[vectorOfFoundInlierIndex[i]])) { std::cerr << "Problem with the inlier index and the corresponding " - "inlier point!" - << std::endl; + "inlier point!" + << std::endl; std::cerr << "Returned inliers: oX=" << std::setprecision(std::numeric_limits::max_digits10) - << vectorOfFoundInlierPoints[i].get_oX() << ", oY=" << vectorOfFoundInlierPoints[i].get_oY() - << ", oZ=" << vectorOfFoundInlierPoints[i].get_oZ() << " ; x=" << vectorOfFoundInlierPoints[i].get_x() - << ", y=" << vectorOfFoundInlierPoints[i].get_y() << std::endl; + << vectorOfFoundInlierPoints[i].get_oX() << ", oY=" << vectorOfFoundInlierPoints[i].get_oY() + << ", oZ=" << vectorOfFoundInlierPoints[i].get_oZ() << " ; x=" << vectorOfFoundInlierPoints[i].get_x() + << ", y=" << vectorOfFoundInlierPoints[i].get_y() << std::endl; const vpPoint &pt = bunnyModelPoints_noisy[vectorOfFoundInlierIndex[i]]; std::cerr << "Object points: oX=" << std::setprecision(std::numeric_limits::max_digits10) << pt.get_oX() - << ", oY=" << pt.get_oY() << ", oZ=" << pt.get_oZ() << " ; x=" << pt.get_x() << ", y=" << pt.get_y() - << std::endl; + << ", oY=" << pt.get_oY() << ", oZ=" << pt.get_oZ() << " ; x=" << pt.get_x() << ", y=" << pt.get_y() + << std::endl; return false; } } @@ -256,8 +260,8 @@ bool testRansac(const std::vector &bunnyModelPoints_original, // Print the number of points in the final data vector std::cout << "\nNumber of model points in the noisy data vector: " << bunnyModelPoints_noisy.size() << " points." - << std::endl - << std::endl; + << std::endl + << std::endl; unsigned int nbInlierToReachConsensus = (unsigned int)(60.0 * (double)(bunnyModelPoints_noisy.size()) / 100.0); double threshold = 0.001; @@ -299,7 +303,7 @@ bool testRansac(const std::vector &bunnyModelPoints_original, chrono_RANSAC.stop(); std::cout << "\ncMo estimated with RANSAC (" << ransac_iterations << " iterations) on noisy data:\n" - << cMo_estimated_RANSAC_2 << std::endl; + << cMo_estimated_RANSAC_2 << std::endl; std::cout << "Computation time: " << chrono_RANSAC.getDurationMs() << " ms" << std::endl; double r_RANSAC_estimated_2 = ground_truth_pose.computeResidual(cMo_estimated_RANSAC_2); @@ -318,8 +322,8 @@ bool testRansac(const std::vector &bunnyModelPoints_original, chrono_RANSAC_parallel.stop(); std::cout << "\ncMo estimated with parallel RANSAC (1000 iterations) on " - "noisy data:\n" - << cMo_estimated_RANSAC_parallel << std::endl; + "noisy data:\n" + << cMo_estimated_RANSAC_parallel << std::endl; std::cout << "Computation time: " << chrono_RANSAC_parallel.getDurationMs() << " ms" << std::endl; double r_RANSAC_estimated_parallel = ground_truth_pose.computeResidual(cMo_estimated_RANSAC_parallel); @@ -332,28 +336,28 @@ bool testRansac(const std::vector &bunnyModelPoints_original, chrono_RANSAC_parallel2.stop(); std::cout << "\ncMo estimated with parallel RANSAC (" << ransac_iterations << " iterations) on noisy data:\n" - << cMo_estimated_RANSAC_parallel2 << std::endl; + << cMo_estimated_RANSAC_parallel2 << std::endl; std::cout << "Computation time: " << chrono_RANSAC_parallel2.getDurationMs() << " ms" << std::endl; double r_RANSAC_estimated_parallel2 = ground_truth_pose.computeResidual(cMo_estimated_RANSAC_parallel2); std::cout << "Corresponding residual (" << ransac_iterations << " iterations): " << r_RANSAC_estimated_parallel2 - << std::endl; + << std::endl; - // Check inlier index +// Check inlier index std::vector vectorOfFoundInlierIndex = pose_ransac.getRansacInlierIndex(); int nbInlierIndexOk = checkInlierIndex(vectorOfFoundInlierIndex, vectorOfOutlierFlags); int nbTrueInlierIndex = (int)std::count(vectorOfOutlierFlags.begin(), vectorOfOutlierFlags.end(), false); std::cout << "\nThere are " << nbInlierIndexOk << " true inliers found, " << vectorOfFoundInlierIndex.size() - << " inliers returned and " << nbTrueInlierIndex << " true inliers." << std::endl; + << " inliers returned and " << nbTrueInlierIndex << " true inliers." << std::endl; - // Check inlier points returned +// Check inlier points returned std::vector vectorOfFoundInlierPoints = pose_ransac.getRansacInliers(); if (vectorOfFoundInlierPoints.size() != vectorOfFoundInlierIndex.size()) { std::cerr << "The number of inlier index is different from the number of " - "inlier points!" - << std::endl; + "inlier points!" + << std::endl; return false; } if (!checkInlierPoints(vectorOfFoundInlierPoints, vectorOfFoundInlierIndex, bunnyModelPoints_noisy)) { @@ -367,14 +371,14 @@ bool testRansac(const std::vector &bunnyModelPoints_original, nbInlierIndexOk = checkInlierIndex(vectorOfFoundInlierIndex_2, vectorOfOutlierFlags); std::cout << "There are " << nbInlierIndexOk << " true inliers found, " << vectorOfFoundInlierIndex_2.size() - << " inliers returned and " << nbTrueInlierIndex << " true inliers." << std::endl; + << " inliers returned and " << nbTrueInlierIndex << " true inliers." << std::endl; - // Check inlier points returned +// Check inlier points returned std::vector vectorOfFoundInlierPoints_2 = pose_ransac2.getRansacInliers(); if (vectorOfFoundInlierPoints_2.size() != vectorOfFoundInlierIndex_2.size()) { std::cerr << "The number of inlier index is different from the number of " - "inlier points!" - << std::endl; + "inlier points!" + << std::endl; return false; } if (!checkInlierPoints(vectorOfFoundInlierPoints_2, vectorOfFoundInlierIndex_2, bunnyModelPoints_noisy)) { @@ -388,14 +392,14 @@ bool testRansac(const std::vector &bunnyModelPoints_original, nbInlierIndexOk = checkInlierIndex(vectorOfFoundInlierIndex_parallel, vectorOfOutlierFlags); std::cout << "There are " << nbInlierIndexOk << " true inliers found, " << vectorOfFoundInlierIndex_parallel.size() - << " inliers returned and " << nbTrueInlierIndex << " true inliers." << std::endl; + << " inliers returned and " << nbTrueInlierIndex << " true inliers." << std::endl; - // Check inlier points returned +// Check inlier points returned std::vector vectorOfFoundInlierPoints_parallel = pose_ransac_parallel.getRansacInliers(); if (vectorOfFoundInlierPoints_parallel.size() != vectorOfFoundInlierIndex_parallel.size()) { std::cerr << "The number of inlier index is different from the number " - "of inlier points!" - << std::endl; + "of inlier points!" + << std::endl; return false; } if (!checkInlierPoints(vectorOfFoundInlierPoints_parallel, vectorOfFoundInlierIndex_parallel, @@ -410,14 +414,14 @@ bool testRansac(const std::vector &bunnyModelPoints_original, nbInlierIndexOk = checkInlierIndex(vectorOfFoundInlierIndex_parallel2, vectorOfOutlierFlags); std::cout << "There are " << nbInlierIndexOk << " true inliers found, " << vectorOfFoundInlierIndex_parallel2.size() - << " inliers returned and " << nbTrueInlierIndex << " true inliers." << std::endl; + << " inliers returned and " << nbTrueInlierIndex << " true inliers." << std::endl; - // Check inlier points returned +// Check inlier points returned std::vector vectorOfFoundInlierPoints_parallel2 = pose_ransac_parallel2.getRansacInliers(); if (vectorOfFoundInlierPoints_parallel2.size() != vectorOfFoundInlierIndex_parallel2.size()) { std::cerr << "The number of inlier index is different from the number " - "of inlier points!" - << std::endl; + "of inlier points!" + << std::endl; return false; } if (!checkInlierPoints(vectorOfFoundInlierPoints_parallel2, vectorOfFoundInlierIndex_parallel2, @@ -430,11 +434,12 @@ bool testRansac(const std::vector &bunnyModelPoints_original, std::cerr << "r_RANSAC_estimated=" << r_RANSAC_estimated << std::endl; std::cerr << "threshold=" << threshold << std::endl; return false; - } else { + } + else { if (r_RANSAC_estimated_parallel > threshold) { std::cerr << "The pose estimated with the parallel RANSAC method is " - "badly estimated!" - << std::endl; + "badly estimated!" + << std::endl; std::cerr << "r_RANSAC_estimated_parallel=" << r_RANSAC_estimated_parallel << std::endl; std::cerr << "threshold=" << threshold << std::endl; return false; @@ -449,14 +454,14 @@ bool testRansac(const std::vector &bunnyModelPoints_original, TEST_CASE("Print RANSAC number of iterations", "[ransac_pose]") { - const int sample_sizes[] = {2, 3, 4, 5, 6, 7, 8}; - const double epsilon[] = {0.05, 0.1, 0.2, 0.25, 0.3, 0.4, 0.5}; + const int sample_sizes[] = { 2, 3, 4, 5, 6, 7, 8 }; + const double epsilon[] = { 0.05, 0.1, 0.2, 0.25, 0.3, 0.4, 0.5 }; // Format output const std::string spacing = " "; std::cout << spacing << " outliers percentage\n" - << "nb pts\\"; + << "nb pts\\"; for (int cpt2 = 0; cpt2 < 7; cpt2++) { std::cout << std::setfill(' ') << std::setw(5) << epsilon[cpt2] << " "; } @@ -483,9 +488,9 @@ TEST_CASE("Print RANSAC number of iterations", "[ransac_pose]") #if (VISP_HAVE_DATASET_VERSION >= 0x030300) TEST_CASE("RANSAC pose estimation tests", "[ransac_pose]") { - const std::vector model_sizes = {10, 20, 50, 100, 200, 500, 1000, 0, 0}; - const std::vector duplicates = {false, false, false, false, false, false, false, false, true}; - const std::vector degenerates = {false, false, false, false, false, false, true, true, true}; + const std::vector model_sizes = { 10, 20, 50, 100, 200, 500, 1000, 0, 0 }; + const std::vector duplicates = { false, false, false, false, false, false, false, false, true }; + const std::vector degenerates = { false, false, false, false, false, false, true, true, true }; std::string visp_input_images = vpIoTools::getViSPImagesDataPath(); std::string model_filename = vpIoTools::createFilePath(visp_input_images, "3dmodel/bunny/bunny.xyz"); @@ -499,7 +504,8 @@ TEST_CASE("RANSAC pose estimation tests", "[ransac_pose]") std::cout << "\n\n===============================================================================" << std::endl; if (model_sizes[i] == 0) { std::cout << "Test on " << bunnyModelPoints_noisy_original.size() << " model points." << std::endl; - } else { + } + else { std::cout << "Test on " << model_sizes[i] << " model points." << std::endl; } std::cout << "Test duplicate: " << duplicates[i] << " ; Test degenerate: " << degenerates[i] << std::endl; diff --git a/modules/vision/test/pose/testFindMatch.cpp b/modules/vision/test/pose/testFindMatch.cpp index 60bd02e72f..7431f3dca0 100644 --- a/modules/vision/test/pose/testFindMatch.cpp +++ b/modules/vision/test/pose/testFindMatch.cpp @@ -52,6 +52,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + #if (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) try { std::cout << "Find Matches using Ransac" << std::endl; @@ -106,7 +110,8 @@ int main() std::cout << "Matching is " << (test_fail ? "badly" : "well") << " performed" << std::endl; return (test_fail ? EXIT_FAILURE : 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/vision/test/pose/testPose.cpp b/modules/vision/test/pose/testPose.cpp index c09a94c99b..0d9f034acb 100644 --- a/modules/vision/test/pose/testPose.cpp +++ b/modules/vision/test/pose/testPose.cpp @@ -59,6 +59,10 @@ */ +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void print_pose(const vpHomogeneousMatrix &cMo, const std::string &legend); int compare_pose(const vpPose &pose, const vpHomogeneousMatrix &cMo_ref, const vpHomogeneousMatrix &cMo_est, const vpCameraParameters &cam, const std::string &legend, const double &translation3DThresh, const double &rotationRadian3DThresh, const double &pose2DThresh, const double &posePixThresh); diff --git a/modules/vision/test/pose/testPoseFeatures.cpp b/modules/vision/test/pose/testPoseFeatures.cpp index 811697078c..8dbe26bc50 100644 --- a/modules/vision/test/pose/testPoseFeatures.cpp +++ b/modules/vision/test/pose/testPoseFeatures.cpp @@ -32,7 +32,6 @@ */ #include -#include #include #include @@ -50,6 +49,10 @@ */ +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #if defined(VISP_HAVE_MODULE_VISUAL_FEATURES) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #ifndef DOXYGEN_SHOULD_SKIP_THIS class vp_createPointClass diff --git a/modules/vision/test/pose/testPoseRansac.cpp b/modules/vision/test/pose/testPoseRansac.cpp index 9dd4cc8330..fd01d591a2 100644 --- a/modules/vision/test/pose/testPoseRansac.cpp +++ b/modules/vision/test/pose/testPoseRansac.cpp @@ -52,6 +52,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #if (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) try { std::cout << "Pose computation with matched points" << std::endl; @@ -117,7 +120,8 @@ int main() std::cout << "Pose is " << (test_fail ? "badly" : "well") << " estimated" << std::endl; return (test_fail ? EXIT_FAILURE : EXIT_SUCCESS); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -125,4 +129,4 @@ int main() std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif -} + } diff --git a/modules/visual_features/include/visp3/visual_features/vpBasicFeature.h b/modules/visual_features/include/visp3/visual_features/vpBasicFeature.h index 4be273154e..fc61436e88 100644 --- a/modules/visual_features/include/visp3/visual_features/vpBasicFeature.h +++ b/modules/visual_features/include/visp3/visual_features/vpBasicFeature.h @@ -36,14 +36,15 @@ * *****************************************************************************/ -#ifndef vpBasicFeature_H -#define vpBasicFeature_H - /*! \file vpBasicFeature.h \brief class that defines what is a visual feature */ +#ifndef vpBasicFeature_H +#define vpBasicFeature_H + +#include #include #include @@ -68,11 +69,12 @@ // #define FEATURE_LINE7 0x40 // #define FEATURE_LINE8 0x80 +BEGIN_VISP_NAMESPACE /*! * \class vpBasicFeature * \ingroup group_visual_features * \brief class that defines what is a visual feature - */ +*/ class VISP_EXPORT vpBasicFeature { public: @@ -145,5 +147,5 @@ class VISP_EXPORT vpBasicFeature protected: vpBasicFeatureDeallocatorType deallocate; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureBuilder.h b/modules/visual_features/include/visp3/visual_features/vpFeatureBuilder.h index 4469fe64af..ec19d9101b 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureBuilder.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureBuilder.h @@ -33,13 +33,15 @@ * *****************************************************************************/ -#ifndef vpFeatureBuilder_H -#define vpFeatureBuilder_H - /*! \file vpFeatureBuilder.h \brief class that defines conversion between tracker and visual feature */ + +#ifndef vpFeatureBuilder_H +#define vpFeatureBuilder_H + + #include // tracker @@ -79,6 +81,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! \class vpFeatureBuilder @@ -152,4 +155,5 @@ class VISP_EXPORT vpFeatureBuilder const vpImagePoint &line1_ip2, const vpImagePoint &line2_ip1, const vpImagePoint &line2_ip2, unsigned int select); }; +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h b/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h index f93422418d..30728379cc 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h @@ -31,14 +31,14 @@ * 2D point visual feature. */ -#ifndef vpFeatureDepth_H -#define vpFeatureDepth_H - /*! * \file vpFeatureDepth.h * \brief Class that defines 3D point visual feature */ +#ifndef vpFeatureDepth_H +#define vpFeatureDepth_H + #include #include #include @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeatureDepth * \ingroup group_visual_features @@ -151,7 +152,7 @@ * s.error(s_star); * } * \endcode - */ +*/ class VISP_EXPORT vpFeatureDepth : public vpBasicFeature { @@ -207,5 +208,5 @@ class VISP_EXPORT vpFeatureDepth : public vpBasicFeature void set_xyZLogZoverZstar(double x, double y, double Z, double logZZs); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h b/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h index bfe879edc0..f40d2bb05b 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h @@ -31,14 +31,14 @@ * 2D ellipse visual feature. */ -#ifndef vpFeatureEllipse_H -#define vpFeatureEllipse_H - /*! * \file vpFeatureEllipse.h * \brief Class that defines 2D ellipse visual feature */ +#ifndef vpFeatureEllipse_H +#define vpFeatureEllipse_H + #include #include #include @@ -46,11 +46,12 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeatureEllipse * \ingroup group_visual_features * \brief Class that defines 2D ellipse visual feature. - */ +*/ class VISP_EXPORT vpFeatureEllipse : public vpBasicFeature { /* @@ -173,5 +174,5 @@ class VISP_EXPORT vpFeatureEllipse : public vpBasicFeature //@} #endif }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureException.h b/modules/visual_features/include/visp3/visual_features/vpFeatureException.h index cd76aa0eca..fdc1ca71e6 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureException.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureException.h @@ -31,25 +31,26 @@ * Exception that can be emitted by the vpFeature class and its derivatives. */ -#ifndef _vpFeatureException_h_ -#define _vpFeatureException_h_ - /*! * \file vpFeatureException.h * \brief error that can be emitted by the vpFeature class and its derivatives */ +#ifndef _vpFeatureException_h_ +#define _vpFeatureException_h_ + #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeatureException * \ingroup group_visual_features * \brief Error that can be emitted by the vpBasicFeature class and its * derivates. - */ +*/ class VISP_EXPORT vpFeatureException : public vpException { public: @@ -92,5 +93,5 @@ class VISP_EXPORT vpFeatureException : public vpException */ explicit vpFeatureException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h b/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h index 76ffe94cb9..ae98b4d48c 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h @@ -31,14 +31,14 @@ * 2D line visual feature. */ -#ifndef _vpFeatureLine_h_ -#define _vpFeatureLine_h_ - /*! * \file vpFeatureLine.h * \brief Class that defines 2D line visual feature */ +#ifndef _vpFeatureLine_h_ +#define _vpFeatureLine_h_ + #include #include #include @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeatureLine * \ingroup group_visual_features @@ -186,7 +187,7 @@ * s.error(s_star); * } * \endcode - */ +*/ class VISP_EXPORT vpFeatureLine : public vpBasicFeature { /*! @@ -236,5 +237,5 @@ class VISP_EXPORT vpFeatureLine : public vpBasicFeature static unsigned int selectRho(); static unsigned int selectTheta(); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h index 2806a8e3ea..b857262786 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h @@ -31,6 +31,13 @@ * Luminance based feature. */ +/*! + * \file vpFeatureLuminance.h + * \brief Class that defines the image luminance visual feature + * + * For more details see \cite Collewet08c. + */ + #ifndef vpFeatureLuminance_h #define vpFeatureLuminance_h @@ -39,21 +46,15 @@ #include #include -/*! - * \file vpFeatureLuminance.h - * \brief Class that defines the image luminance visual feature - * - * For more details see \cite Collewet08c. - */ - #ifndef DOXYGEN_SHOULD_SKIP_THIS +BEGIN_VISP_NAMESPACE /*! * \class vpLuminance * \brief Class that defines the luminance and gradient of a point. * * \sa vpFeatureLuminance - */ +*/ class VISP_EXPORT vpLuminance { public: @@ -129,5 +130,5 @@ class VISP_EXPORT vpFeatureLuminance : public vpBasicFeature public: vpCameraParameters cam; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h index b387404617..cab170def7 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE class vpMomentObject; class vpMomentDatabase; class vpFeatureMomentDatabase; @@ -152,7 +153,7 @@ class vpMoment; * std::cout << fmb.interaction(1,1) << std::endl; * } * \endcode - */ +*/ class VISP_EXPORT vpFeatureMoment : public vpBasicFeature { protected: @@ -277,5 +278,5 @@ class VISP_EXPORT vpMomentGenericFeature : public vpFeatureMoment */ virtual const std::string name() const { return std::string(); } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h index ed7de38ddc..f787a2b5c0 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAlpha.h @@ -40,9 +40,11 @@ #ifndef _vpFeatureMomentAlpha_h_ #define _vpFeatureMomentAlpha_h_ +#include #include #include +BEGIN_VISP_NAMESPACE class vpMomentDatabase; /*! * \class vpFeatureMomentAlpha @@ -95,7 +97,7 @@ class vpMomentDatabase; * This feature depends on: * - vpMomentCentered * - vpMomentGravityCenter - */ +*/ class VISP_EXPORT vpFeatureMomentAlpha : public vpFeatureMoment { public: @@ -133,4 +135,5 @@ class VISP_EXPORT vpFeatureMomentAlpha : public vpFeatureMoment vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL) vp_override; }; +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h index 7281bbf156..d57bcb2e70 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentArea.h @@ -39,8 +39,10 @@ #ifndef _vpFeatureMomentArea_h_ #define _vpFeatureMomentArea_h_ +#include #include +BEGIN_VISP_NAMESPACE class vpMomentDatabase; /*! @@ -50,7 +52,7 @@ class vpMomentDatabase; * * \brief Surface moment feature. Computes the interaction matrix associated * with vpMomentArea. - */ +*/ class VISP_EXPORT vpFeatureMomentArea : public vpFeatureMoment { public: @@ -87,4 +89,5 @@ class VISP_EXPORT vpFeatureMomentArea : public vpFeatureMoment return "vpFeatureMomentArea"; } }; +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h index 1e7401a609..6a6c2787df 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentAreaNormalized.h @@ -39,8 +39,10 @@ #ifndef _vpFeatureMomentAreaNormalized_h_ #define _vpFeatureMomentAreaNormalized_h_ +#include #include +BEGIN_VISP_NAMESPACE #ifdef VISP_MOMENTS_COMBINE_MATRICES class vpMomentDatabase; @@ -216,4 +218,5 @@ class VISP_EXPORT vpFeatureMomentAreaNormalized : public vpFeatureMoment } }; #endif +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h index 9c8c2dff92..d05fe6b506 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentBasic.h @@ -44,6 +44,7 @@ #include #include +BEGIN_VISP_NAMESPACE class vpMomentDatabase; /*! * \class vpFeatureMomentBasic @@ -72,7 +73,7 @@ class vpMomentDatabase; * * This feature depends on: * - vpMomentBasic - */ +*/ class VISP_EXPORT vpFeatureMomentBasic : public vpFeatureMoment { protected: @@ -110,4 +111,5 @@ class VISP_EXPORT vpFeatureMomentBasic : public vpFeatureMoment return "vpFeatureMomentBasic"; } }; +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h index 96a9c299d5..2d649839a9 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h @@ -38,9 +38,12 @@ #ifndef _vpFeatureMomentCInvariant_h_ #define _vpFeatureMomentCInvariant_h_ +#include #include #ifdef VISP_MOMENTS_COMBINE_MATRICES +BEGIN_VISP_NAMESPACE + /*! * \class vpFeatureMomentCInvariant * @@ -85,7 +88,7 @@ * * An example of how to use vpFeatureMomentCInvariant in a complete visual * servoing example is given in vpFeatureMomentCommon. - */ +*/ class VISP_EXPORT vpFeatureMomentCInvariant : public vpFeatureMoment { public: @@ -179,8 +182,9 @@ class VISP_EXPORT vpFeatureMomentCInvariant : public vpFeatureMoment */ static unsigned int selectPy() { return 1 << 13; } }; - +END_VISP_NAMESPACE #else +BEGIN_VISP_NAMESPACE class vpMomentDatabase; /*! @@ -329,5 +333,6 @@ class VISP_EXPORT vpFeatureMomentCInvariant : public vpFeatureMoment friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpFeatureMomentCInvariant &featcinv); }; +END_VISP_NAMESPACE #endif #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h index dd035e8005..302c7d8d22 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h @@ -38,10 +38,13 @@ #ifndef _vpFeatureMomentCentered_h_ #define _vpFeatureMomentCentered_h_ +#include #include #include +BEGIN_VISP_NAMESPACE class vpMomentDatabase; + /*! * \class vpFeatureMomentCentered * @@ -70,7 +73,7 @@ class vpMomentDatabase; * - vpFeatureMomentBasic * - vpFeatureMomentGravityCenter * - vpMomentGravityCenter - */ +*/ class VISP_EXPORT vpFeatureMomentCentered : public vpFeatureMoment { protected: @@ -116,5 +119,5 @@ class VISP_EXPORT vpFeatureMomentCentered : public vpFeatureMoment friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpFeatureMomentCentered &v); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCommon.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCommon.h index 39a26f163f..6e683b8c8b 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCommon.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCommon.h @@ -40,6 +40,7 @@ #ifndef _vpFeatureMomentCommon_h_ #define _vpFeatureMomentCommon_h_ +#include #include #include #include @@ -51,6 +52,7 @@ #include #include +BEGIN_VISP_NAMESPACE class vpMomentDatabase; class vpServo; /*! @@ -212,7 +214,7 @@ class vpServo; * Gain : Zero= 1 Inf= 1 Deriv= 0 * * \endcode - */ +*/ class VISP_EXPORT vpFeatureMomentCommon : public vpFeatureMomentDatabase { private: @@ -266,5 +268,5 @@ class VISP_EXPORT vpFeatureMomentCommon : public vpFeatureMomentDatabase */ vpFeatureMomentGravityCenter &getFeatureGravityCenter() { return featureGravity; } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentDatabase.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentDatabase.h index d6530fac82..0b86967fbd 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentDatabase.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentDatabase.h @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE class vpFeatureMoment; class vpMomentObject; /*! @@ -149,7 +150,7 @@ class vpMomentObject; * return 0; * } * \endcode - */ +*/ class VISP_EXPORT vpFeatureMomentDatabase { private: @@ -180,5 +181,5 @@ class VISP_EXPORT vpFeatureMomentDatabase // vpFeatureMomentDatabase& m); friend class vpFeatureMoment; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h index 71351a164a..c994621f46 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenter.h @@ -39,8 +39,10 @@ #ifndef _vpFeatureMomentGravityCenter_h_ #define _vpFeatureMomentGravityCenter_h_ +#include #include +BEGIN_VISP_NAMESPACE #ifdef VISP_MOMENTS_COMBINE_MATRICES class vpMomentDatabase; /*! @@ -142,7 +144,7 @@ class vpMomentDatabase; * - vpFeatureMomentBasic * * Minimum vpMomentObject order needed to compute this feature: 2. - */ +*/ class VISP_EXPORT vpFeatureMomentGravityCenter : public vpFeatureMoment { public: @@ -255,6 +257,6 @@ class VISP_EXPORT vpFeatureMomentGravityCenter : public vpFeatureMoment */ static unsigned int selectYg() { return 1 << 1; } }; - #endif +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h index a2cef02fd9..5792e708d5 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h @@ -39,8 +39,10 @@ #ifndef _vpFeatureMomentGravityCenterNormalized_h_ #define _vpFeatureMomentGravityCenterNormalized_h_ +#include #include +BEGIN_VISP_NAMESPACE #ifdef VISP_MOMENTS_COMBINE_MATRICES class vpMomentDatabase; /*! @@ -83,7 +85,7 @@ class vpMomentDatabase; * - vpMomentGravityCenter * - vpMomentAreaNormalized * - vpFeatureMomentAreaNormalized - */ +*/ class VISP_EXPORT vpFeatureMomentGravityCenterNormalized : public vpFeatureMoment { public: @@ -279,4 +281,5 @@ class VISP_EXPORT vpFeatureMomentGravityCenterNormalized : public vpFeatureMomen static unsigned int selectYn() { return 1 << 1; } }; #endif +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h index 9f10acb371..528b3f5dfe 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h @@ -31,14 +31,14 @@ * 2D point visual feature. */ -#ifndef vpFeaturePoint_H -#define vpFeaturePoint_H - /*! * \file vpFeaturePoint.h * \brief Class that defines 2D point visual feature */ +#ifndef vpFeaturePoint_H +#define vpFeaturePoint_H + #include #include #include @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeaturePoint * \ingroup group_visual_features @@ -171,7 +172,7 @@ * \endcode * * An other fully explained example is given in the \ref tutorial-ibvs. - */ +*/ class VISP_EXPORT vpFeaturePoint : public vpBasicFeature { private: @@ -227,5 +228,5 @@ class VISP_EXPORT vpFeaturePoint : public vpBasicFeature Y = 2 // y coordinates } vpFeaturePointType; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h index 2422eb41ba..6b685c9a24 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h @@ -31,14 +31,14 @@ * 3D point visual feature. */ -#ifndef vpFeaturePoint3d_H -#define vpFeaturePoint3d_H - /*! * \file vpFeaturePoint3D.h * \brief class that defines the 3D point visual feature. */ +#ifndef vpFeaturePoint3d_H +#define vpFeaturePoint3d_H + #include #include #include @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeaturePoint3D * \ingroup group_visual_features @@ -198,7 +199,7 @@ * std::cout << "e: " << e << std::endl; * } * \endcode - */ +*/ class VISP_EXPORT vpFeaturePoint3D : public vpBasicFeature { public: @@ -260,5 +261,6 @@ class VISP_EXPORT vpFeaturePoint3D : public vpBasicFeature static unsigned int selectY(); static unsigned int selectZ(); }; +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h index e34faaae83..9f34bdfe55 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h @@ -31,14 +31,14 @@ * 2D point with polar coordinates visual feature. */ -#ifndef vpFeaturePointPolar_H -#define vpFeaturePointPolar_H - /*! * \file vpFeaturePointPolar.h * \brief Class that defines a 2D point visual feature with polar coordinates. */ +#ifndef vpFeaturePointPolar_H +#define vpFeaturePointPolar_H + #include #include #include @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeaturePointPolar * \ingroup group_visual_features @@ -248,7 +249,7 @@ * return 0; * } * \endcode - */ +*/ class VISP_EXPORT vpFeaturePointPolar : public vpBasicFeature { private: @@ -309,5 +310,5 @@ class VISP_EXPORT vpFeaturePointPolar : public vpBasicFeature static unsigned int selectTheta(); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h b/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h index 284596a155..c54e442d82 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h @@ -31,14 +31,14 @@ * Segment visual feature. */ -#ifndef vpFeatureSegment_H -#define vpFeatureSegment_H - /*! * \file vpFeatureSegment.h * \brief class that defines the Segment visual feature */ +#ifndef vpFeatureSegment_H +#define vpFeatureSegment_H + #include #include #include @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeatureSegment * \ingroup group_visual_features @@ -61,7 +62,7 @@ * * The selection of the feature set is done either during construction using * vpFeatureSegment(bool), or by setNormalized(bool). - */ +*/ class VISP_EXPORT vpFeatureSegment : public vpBasicFeature { public: @@ -291,5 +292,5 @@ class VISP_EXPORT vpFeatureSegment : public vpBasicFeature double sin_a_; bool normalized_; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h b/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h index 05ba663316..a7ff99d246 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h @@ -33,14 +33,14 @@ * *****************************************************************************/ -#ifndef vpFeatureThetaU_H -#define vpFeatureThetaU_H - /*! \file vpFeatureThetaU.h \brief class that defines the ThetaU visual feature */ +#ifndef vpFeatureThetaU_H +#define vpFeatureThetaU_H + #include #include #include @@ -49,6 +49,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeatureThetaU * \ingroup group_visual_features @@ -215,7 +216,7 @@ * s.error(s_star); * } * \endcode - */ +*/ class VISP_EXPORT vpFeatureThetaU : public vpBasicFeature { public: @@ -306,5 +307,5 @@ class VISP_EXPORT vpFeatureThetaU : public vpBasicFeature private: vpFeatureThetaURotationRepresentationType rotation; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h b/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h index 7a0f9d2143..839ae0e714 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h @@ -31,14 +31,14 @@ * 3D translation visual feature. */ -#ifndef vpFeatureTranslation_H -#define vpFeatureTranslation_H - /*! \file vpFeatureTranslation.h \brief class that defines the translation visual feature. */ +#ifndef vpFeatureTranslation_H +#define vpFeatureTranslation_H + #include #include #include @@ -46,6 +46,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeatureTranslation * \ingroup group_visual_features @@ -264,7 +265,7 @@ * } * } * \endcode - */ +*/ class VISP_EXPORT vpFeatureTranslation : public vpBasicFeature { public: @@ -347,5 +348,5 @@ class VISP_EXPORT vpFeatureTranslation : public vpBasicFeature vpHomogeneousMatrix f2Mf1; vpFeatureTranslationRepresentationType translation; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h b/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h index 5463eb0945..f3ab9c3dc7 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h @@ -31,14 +31,14 @@ * 2D vanishing point visual feature (Z coordinate in 3D space is infinity) */ -#ifndef vpFeatureVanishingPoint_H -#define vpFeatureVanishingPoint_H - /*! * \file vpFeatureVanishingPoint.h \brief Class that defines 2D vanishing * point visual feature (Z coordinate in 3D space is infinity) */ +#ifndef vpFeatureVanishingPoint_H +#define vpFeatureVanishingPoint_H + #include #include #include @@ -47,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpFeatureVanishingPoint * \ingroup group_visual_features @@ -67,7 +68,7 @@ * 0 \end{array} \right] \f] \f[ L_{\frac{1}{\rho}} = \left[ \begin{array}{cccccc} 0 & 0 & 0 & -(1 + \frac{1}{\rho^2}) * \sin \alpha & (1 + \frac{1}{\rho^2}) \cos \alpha & 0 \end{array} \right] \f] \f[ L_{\alpha} = \left[ * \begin{array}{cccccc} 0 & 0 & 0 & \frac{\cos \alpha}{\rho} & \frac{\sin \alpha}{\rho} & -1 \end{array} \right] \f] - */ +*/ class VISP_EXPORT vpFeatureVanishingPoint : public vpBasicFeature { public: @@ -112,5 +113,5 @@ class VISP_EXPORT vpFeatureVanishingPoint : public vpBasicFeature protected: unsigned int m_select; // Memory to know which features are used for display; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h b/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h index b21adc2191..69c825055a 100644 --- a/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h +++ b/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h @@ -31,21 +31,23 @@ * Generic feature (used to create new feature not implemented in ViSP). */ -#ifndef vpGenericFeature_hh -#define vpGenericFeature_hh - /*! * \file vpGenericFeature.h * \brief class that defines what is a generic feature (used to create new * feature not implemented in ViSP2 */ +#ifndef vpGenericFeature_hh +#define vpGenericFeature_hh + +#include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpGenericFeature * \ingroup group_visual_features @@ -171,7 +173,7 @@ * * If the feature needs to be use with other features, the example * servoSimuPoint2DhalfCamVelocity2.cpp shows how to do it. - */ +*/ class VISP_EXPORT vpGenericFeature : public vpBasicFeature { private: @@ -212,5 +214,5 @@ class VISP_EXPORT vpGenericFeature : public vpBasicFeature vpColVector err; vpGenericFeatureErrorType errorStatus; }; - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderEllipse.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderEllipse.cpp index 6c0bebbab9..e700601649 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderEllipse.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderEllipse.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Initialize an ellipse feature thanks to a vpCircle. The vpFeatureEllipse is initialized thanks to the parameters of the circle @@ -196,3 +197,4 @@ void vpFeatureBuilder::create(vpFeatureEllipse &s, const vpCameraParameters &cam } #endif //#ifdef VISP_HAVE_MODULE_ME +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderLine.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderLine.cpp index 4b2cc411f4..129d8743fe 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderLine.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderLine.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Initialize a line feature thanks to a vpLine. A vpFeatureLine contains the parameters \f$(\rho,\theta)\f$ which are @@ -66,7 +67,8 @@ void vpFeatureBuilder::create(vpFeatureLine &s, const vpLine &t) B = t.cP[1]; C = t.cP[2]; D = t.cP[3]; - } else { + } + else { A = t.cP[4]; B = t.cP[5]; C = t.cP[6]; @@ -75,7 +77,8 @@ void vpFeatureBuilder::create(vpFeatureLine &s, const vpLine &t) s.setABCD(A, B, C, D); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -110,7 +113,7 @@ void vpFeatureBuilder::create(vpFeatureLine &s, const vpCylinder &t, int line) double R = t.getR(); double D = - vpMath::sqr(x0) + vpMath::sqr(y0) + vpMath::sqr(z0) - vpMath::sqr(R) - vpMath::sqr(a * x0 + b * y0 + c * z0); + vpMath::sqr(x0) + vpMath::sqr(y0) + vpMath::sqr(z0) - vpMath::sqr(R) - vpMath::sqr(a * x0 + b * y0 + c * z0); double alpha1 = (1 - a * a) * x0 - a * b * y0 - a * c * z0; double beta1 = -a * b * x0 + (1 - b * b) * y0 - b * c * z0; @@ -131,11 +134,13 @@ void vpFeatureBuilder::create(vpFeatureLine &s, const vpCylinder &t, int line) s.setRhoTheta(t.getRho1(), t.getTheta1()); - } else { + } + else { s.setRhoTheta(t.getRho2(), t.getTheta2()); } - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -223,9 +228,11 @@ void vpFeatureBuilder::create(vpFeatureLine &s, const vpCameraParameters &cam, c } s.build(rho, theta); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } } #endif //#ifdef VISP_HAVE_MODULE_ME +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderPoint.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderPoint.cpp index 56f4866cf1..b6dde258ae 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderPoint.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderPoint.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE #ifdef VISP_HAVE_MODULE_BLOB /*! Create a vpFeaturePoint thanks to a vpDot and the parameters of the camera. @@ -99,7 +100,8 @@ void vpFeatureBuilder::create(vpFeaturePoint &s, const vpCameraParameters &cam, s.set_x(x); s.set_y(y); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -159,7 +161,8 @@ void vpFeatureBuilder::create(vpFeaturePoint &s, const vpCameraParameters &cam, s.set_x(x); s.set_y(y); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -217,7 +220,8 @@ void vpFeatureBuilder::create(vpFeaturePoint &s, const vpCameraParameters &cam, s.set_x(x); s.set_y(y); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -259,7 +263,8 @@ void vpFeatureBuilder::create(vpFeaturePoint &s, const vpPoint &p) throw(vpFeatureException(vpFeatureException::badInitializationError, "Point Z coordinates is null")); } - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -311,8 +316,10 @@ void vpFeatureBuilder::create(vpFeaturePoint &s, const vpCameraParameters &goodC s.set_x(x); s.set_y(y); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderPoint3D.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderPoint3D.cpp index 26572f006e..ea62ffce75 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderPoint3D.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderPoint3D.cpp @@ -42,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Initialize a 3D point feature using the coordinates of the point @@ -64,12 +65,13 @@ void vpFeatureBuilder::create(vpFeaturePoint3D &s, const vpPoint &t) s.set_Y(t.cP[1] / t.cP[3]); s.set_Z(t.cP[2] / t.cP[3]); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } } - +END_VISP_NAMESPACE /* * Local variables: * c-basic-offset: 2 diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderPointPolar.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderPointPolar.cpp index 8aaa92d95d..990858e0fe 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderPointPolar.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderPointPolar.cpp @@ -44,6 +44,7 @@ #include #include +BEGIN_VISP_NAMESPACE #ifdef VISP_HAVE_MODULE_BLOB /*! @@ -111,7 +112,8 @@ void vpFeatureBuilder::create(vpFeaturePointPolar &s, const vpCameraParameters & s.set_rho(rho); s.set_theta(theta); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -183,7 +185,8 @@ void vpFeatureBuilder::create(vpFeaturePointPolar &s, const vpCameraParameters & s.set_rho(rho); s.set_theta(theta); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -251,7 +254,8 @@ void vpFeatureBuilder::create(vpFeaturePointPolar &s, const vpCameraParameters & s.set_rho(rho); s.set_theta(theta); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -304,7 +308,8 @@ void vpFeatureBuilder::create(vpFeaturePointPolar &s, const vpPoint &p) throw(vpFeatureException(vpFeatureException::badInitializationError, "Point Z coordinates is null")); } - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -361,12 +366,13 @@ void vpFeatureBuilder::create(vpFeaturePointPolar &s, const vpCameraParameters & s.set_rho(rho); s.set_theta(theta); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } } - +END_VISP_NAMESPACE /* * Local variables: * c-basic-offset: 2 diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderSegment.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderSegment.cpp index 22a1938feb..c86272bef3 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderSegment.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderSegment.cpp @@ -39,6 +39,7 @@ #include #include +BEGIN_VISP_NAMESPACE #ifdef VISP_HAVE_MODULE_BLOB /*! @@ -162,3 +163,4 @@ void vpFeatureBuilder::create(vpFeatureSegment &s, vpPoint &P1, vpPoint &P2) s.build(x1, y1, Z1, x2, y2, Z2); } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderVanishingPoint.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderVanishingPoint.cpp index 1cd2d9a4ea..40cca32c69 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderVanishingPoint.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderVanishingPoint.cpp @@ -45,6 +45,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Initialize a vpFeatureVanishingPoint thanks to a vpPoint. The vpFeatureVanishingPoint is initialized thanks to the parameters of the @@ -66,8 +67,9 @@ void vpFeatureBuilder::create(vpFeatureVanishingPoint &s, const vpPoint &p, unsi if ((vpFeatureVanishingPoint::selectX() & select) || (vpFeatureVanishingPoint::selectY() & select)) { s.set_x(p.get_x()); s.set_y(p.get_y()); - } else if ((vpFeatureVanishingPoint::selectOneOverRho() & select) || - (vpFeatureVanishingPoint::selectAlpha() & select)) { + } + else if ((vpFeatureVanishingPoint::selectOneOverRho() & select) || + (vpFeatureVanishingPoint::selectAlpha() & select)) { double x = p.get_x(); double y = p.get_y(); @@ -113,8 +115,8 @@ void vpFeatureBuilder::create(vpFeatureVanishingPoint &s, const vpFeatureLine &L if (fabs(theta_r - theta_l) < min || fabs(fabs(theta_r - theta_l) - M_PI) < min || fabs(fabs(theta_r - theta_l) - 2 * M_PI) < min) { vpCERROR << "There is no vanishing point : the lines are parallel in the " - "image plane" - << std::endl; + "image plane" + << std::endl; throw(vpFeatureException(vpFeatureException::badInitializationError, "There is no vanishing point : the lines are " "parallel in the image plane")); @@ -125,8 +127,9 @@ void vpFeatureBuilder::create(vpFeatureVanishingPoint &s, const vpFeatureLine &L s.set_x(x); s.set_y(y); - } else if ((vpFeatureVanishingPoint::selectOneOverRho() & select) || - (vpFeatureVanishingPoint::selectAlpha() & select)) { + } + else if ((vpFeatureVanishingPoint::selectOneOverRho() & select) || + (vpFeatureVanishingPoint::selectAlpha() & select)) { double rho_1 = L1.getRho(); double theta_1 = L1.getTheta(); double rho_2 = L2.getRho(); @@ -225,7 +228,8 @@ void vpFeatureBuilder::create(vpFeatureVanishingPoint &s, const vpCameraParamete s.set_x(x); s.set_y(y); - } else if ((vpFeatureVanishingPoint::selectOneOverRho() & select)) { + } + else if ((vpFeatureVanishingPoint::selectOneOverRho() & select)) { double theta_diff = theta_1 - theta_2; double denom = sqrt(rho_1 * rho_1 + rho_2 * rho_2 - 2 * rho_1 * rho_2 * cos(theta_diff)); double one_over_rho = sin(theta_diff) / denom; @@ -236,7 +240,8 @@ void vpFeatureBuilder::create(vpFeatureVanishingPoint &s, const vpCameraParamete s.setOneOverRho(one_over_rho); s.setAlpha(alpha); - } else if ((vpFeatureVanishingPoint::selectAtanOneOverRho() & select)) { + } + else if ((vpFeatureVanishingPoint::selectAtanOneOverRho() & select)) { double theta_diff = theta_1 - theta_2; double denom = sqrt(rho_1 * rho_1 + rho_2 * rho_2 - 2 * rho_1 * rho_2 * cos(theta_diff)); double alpha = atan2(rho_1 * cos(theta_2) - rho_2 * cos(theta_1), rho_2 * sin(theta_1) - rho_1 * sin(theta_2)); @@ -252,3 +257,4 @@ void vpFeatureBuilder::create(vpFeatureVanishingPoint &s, const vpCameraParamete s.setAlpha(alpha); } } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpBasicFeature.cpp b/modules/visual_features/src/visual-feature/vpBasicFeature.cpp index 1f219c43b9..69b68ed5e2 100644 --- a/modules/visual_features/src/visual-feature/vpBasicFeature.cpp +++ b/modules/visual_features/src/visual-feature/vpBasicFeature.cpp @@ -36,8 +36,14 @@ * *****************************************************************************/ +/*! + \file vpBasicFeature.cpp + \brief Class that defines what is a visual feature. +*/ + #include +BEGIN_VISP_NAMESPACE const unsigned int vpBasicFeature::FEATURE_LINE[32] = { (unsigned int)(1 << 0), (unsigned int)(1 << 1), (unsigned int)(1 << 2), (unsigned int)(1 << 3), (unsigned int)(1 << 4), (unsigned int)(1 << 5), (unsigned int)(1 << 6), (unsigned int)(1 << 7), @@ -46,16 +52,13 @@ const unsigned int vpBasicFeature::FEATURE_LINE[32] = { (unsigned int)(1 << 16), (unsigned int)(1 << 17), (unsigned int)(1 << 18), (unsigned int)(1 << 19), (unsigned int)(1 << 20), (unsigned int)(1 << 21), (unsigned int)(1 << 22), (unsigned int)(1 << 23), (unsigned int)(1 << 24), (unsigned int)(1 << 25), (unsigned int)(1 << 26), (unsigned int)(1 << 27), - (unsigned int)(1 << 28), (unsigned int)(1 << 29), (unsigned int)(1 << 30), (unsigned int)(1 << 31)}; + (unsigned int)(1 << 28), (unsigned int)(1 << 29), (unsigned int)(1 << 30), (unsigned int)(1 << 31) }; + -/*! - \file vpBasicFeature.cpp - \brief Class that defines what is a visual feature. -*/ /*! Default constructor. */ -vpBasicFeature::vpBasicFeature() : s(), dim_s(0), flags(nullptr), nbParameters(0), deallocate(vpBasicFeature::user) {} +vpBasicFeature::vpBasicFeature() : s(), dim_s(0), flags(nullptr), nbParameters(0), deallocate(vpBasicFeature::user) { } /*! Destructor that free allocated memory. @@ -157,7 +160,8 @@ vpColVector vpBasicFeature::error(const vpBasicFeature &s_star, unsigned int sel // std::cout << "dim_s <= 31"< /* - - - attributes and members directly related to the vpBasicFeature needs other functionalities ar useful but not mandatory - - - - - */ +BEGIN_VISP_NAMESPACE /*! Initialize the memory space requested for 3D depth visual feature. */ @@ -463,7 +456,7 @@ void vpFeatureDepth::display(const vpCameraParameters & /* cam */, const vpImage // to produce a failure } } - +END_VISP_NAMESPACE /* * Local variables: * c-basic-offset: 2 diff --git a/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp b/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp index 5919bd3672..9d7a19f5b4 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp @@ -60,6 +60,8 @@ other functionalities ar useful but not mandatory */ +BEGIN_VISP_NAMESPACE + void vpFeatureEllipse::init() { // feature dimension @@ -481,3 +483,4 @@ vp_deprecated unsigned int vpFeatureEllipse::selectMu11() { return FEATURE_LINE[ */ vp_deprecated unsigned int vpFeatureEllipse::selectMu02() { return FEATURE_LINE[4]; } #endif +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureLine.cpp b/modules/visual_features/src/visual-feature/vpFeatureLine.cpp index b273a1d7c0..a86788be39 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureLine.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureLine.cpp @@ -67,6 +67,7 @@ attributes and members directly related to the vpBasicFeature needs other functionalities ar useful but not mandatory */ +BEGIN_VISP_NAMESPACE /*! Initialize the memory space requested for 2D line visual feature. */ @@ -600,3 +601,4 @@ unsigned int vpFeatureLine::selectRho() { return FEATURE_LINE[0]; } \endcode */ unsigned int vpFeatureLine::selectTheta() { return FEATURE_LINE[1]; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp b/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp index 41d04e195a..e2560d33d9 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp @@ -33,6 +33,13 @@ * *****************************************************************************/ +/*! + \file vpFeatureLuminance.cpp + \brief Class that defines the image luminance visual feature + + For more details see \cite Collewet08c. +*/ + #include #include #include @@ -43,12 +50,7 @@ #include -/*! - \file vpFeatureLuminance.cpp - \brief Class that defines the image luminance visual feature - - For more details see \cite Collewet08c. -*/ +BEGIN_VISP_NAMESPACE /*! Initialize the memory space requested for vpFeatureLuminance visual feature. @@ -367,6 +369,7 @@ vpFeatureLuminance *vpFeatureLuminance::duplicate() const return feature; } +END_VISP_NAMESPACE /* * Local variables: * c-basic-offset: 2 diff --git a/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp b/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp index bf8222a83b..8606bbe78d 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp @@ -43,6 +43,7 @@ #include #include +BEGIN_VISP_NAMESPACE class vpBasicFeature; /*! @@ -247,20 +248,6 @@ void vpFeatureMoment::linkTo(vpFeatureMomentDatabase &featureMoments) void vpFeatureMoment::compute_interaction() { } -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpFeatureMoment &featM) -{ - /* - * - A static_cast is forced here since interaction() defined in vpBasicFeature() - * is not const. But introducing const in vpBasicFeature() can break a lot of - * client code. - * - 6 corresponds to 6 velocities in standard interaction matrix - */ - vpMatrix Lcomplete(static_cast(featM.getDimension()), 6); - Lcomplete = const_cast(featM).interaction(vpBasicFeature::FEATURE_ALL); - Lcomplete.matlabPrint(os); - return os; -} - /*! * Interface function to display the moments and other interaction matrices * on which a particular vpFeatureMoment is dependent upon @@ -275,3 +262,19 @@ void vpFeatureMoment::printDependencies(std::ostream &os) const "to be implemented in the derived classes!" << std::endl; } + +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpFeatureMoment &featM) +{ + /* + * - A static_cast is forced here since interaction() defined in vpBasicFeature() + * is not const. But introducing const in vpBasicFeature() can break a lot of + * client code. + * - 6 corresponds to 6 velocities in standard interaction matrix + */ + vpMatrix Lcomplete(static_cast(featM.getDimension()), 6); + Lcomplete = const_cast(featM).interaction(vpBasicFeature::FEATURE_ALL); + Lcomplete.matlabPrint(os); + return os; +} + +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentAlpha.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentAlpha.cpp index 22a418b852..8960635465 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentAlpha.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentAlpha.cpp @@ -38,9 +38,9 @@ #include #include -#include #include +BEGIN_VISP_NAMESPACE #ifdef VISP_MOMENTS_COMBINE_MATRICES /*! @@ -50,7 +50,7 @@ * - vpMomentCentered * - vpFeatureMomentCentered */ -void vpFeatureMomentAlpha::compute_interaction() + void vpFeatureMomentAlpha::compute_interaction() { bool found_moment_centered; bool found_FeatureMoment_centered; @@ -83,7 +83,7 @@ void vpFeatureMomentAlpha::compute_interaction() * - vpMomentCentered * - vpMomentGravityCenter */ -void vpFeatureMomentAlpha::compute_interaction() + void vpFeatureMomentAlpha::compute_interaction() { bool found_moment_centered; bool found_moment_gravity; @@ -166,3 +166,4 @@ vpColVector vpFeatureMomentAlpha::error(const vpBasicFeature &s_star, const unsi return e; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentArea.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentArea.cpp index ed31e18f21..05b264be75 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentArea.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentArea.cpp @@ -36,7 +36,6 @@ * *****************************************************************************/ #include -#include #include // numeric_limits #include #include @@ -48,6 +47,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! Computes interaction matrix for the normalized surface moment. Called internally. The moment primitives must be computed before calling this. This @@ -74,11 +74,12 @@ void vpFeatureMomentArea::compute_interaction() if (!found_centered) throw vpException(vpException::notInitialized, "vpFeatureMomentCentered not found"); interaction_matrices[0] = momentCentered.interaction(2, 0) + momentCentered.interaction(0, 2); - } else { - // Get Xg and Yg + } + else { + // Get Xg and Yg bool found_xgyg; const vpMomentGravityCenter &momentGravity = - static_cast(moments.get("vpMomentGravityCenter", found_xgyg)); + static_cast(moments.get("vpMomentGravityCenter", found_xgyg)); if (!found_xgyg) throw vpException(vpException::notInitialized, "vpMomentGravityCenter not found"); @@ -102,3 +103,4 @@ void vpFeatureMomentArea::compute_interaction() interaction_matrices[0][0][5] = 0.; } } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentAreaNormalized.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentAreaNormalized.cpp index 61c845c788..7cc3c73222 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentAreaNormalized.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentAreaNormalized.cpp @@ -33,7 +33,6 @@ #include #ifdef VISP_MOMENTS_COMBINE_MATRICES -#include #include #include @@ -44,6 +43,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Computes interaction matrix for the normalized surface moment. Called * internally. The moment primitives must be computed before calling this. This @@ -53,7 +53,7 @@ * - vpMomentAreaNormalized * - vpFeatureMomentBasic */ -void vpFeatureMomentAreaNormalized::compute_interaction() + void vpFeatureMomentAreaNormalized::compute_interaction() { bool found_moment_centered; bool found_moment_surface_normalized; @@ -97,10 +97,9 @@ void vpFeatureMomentAreaNormalized::compute_interaction() (-momentSurfaceNormalized.getDesiredDepth() / (2 * a)) * sqrt(momentSurfaceNormalized.getDesiredArea() / a); interaction_matrices[0] = normalized_multiplier * La; } - +END_VISP_NAMESPACE #else -#include #include #include @@ -110,6 +109,7 @@ void vpFeatureMomentAreaNormalized::compute_interaction() #include #include +BEGIN_VISP_NAMESPACE /*! * Computes interaction matrix for the normalized surface moment. Called * internally. The moment primitives must be computed before calling this. This @@ -118,7 +118,7 @@ void vpFeatureMomentAreaNormalized::compute_interaction() * - vpMomentAreaNormalized * - vpMomentGravityCenter */ -void vpFeatureMomentAreaNormalized::compute_interaction() + void vpFeatureMomentAreaNormalized::compute_interaction() { bool found_moment_centered; bool found_moment_surface_normalized; @@ -199,5 +199,5 @@ void vpFeatureMomentAreaNormalized::compute_interaction() interaction_matrices[0][0][WY] = Anwy; interaction_matrices[0][0][WZ] = 0.; } - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentBasic.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentBasic.cpp index ff1bd231e8..ed5f0dd650 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentBasic.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentBasic.cpp @@ -31,11 +31,12 @@ * Implementation for all supported moment features. */ -#include #include #include #include #include + +BEGIN_VISP_NAMESPACE /*! * Default constructor. * \param data_base : Database of moment primitives. @@ -44,8 +45,8 @@ * \param C_ : Third plane coefficient for a plane equation of the following type Ax+By+C=1/Z. * \param featureMoments : Database of features. */ -vpFeatureMomentBasic::vpFeatureMomentBasic(vpMomentDatabase &data_base, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments) + vpFeatureMomentBasic::vpFeatureMomentBasic(vpMomentDatabase &data_base, double A_, double B_, double C_, + vpFeatureMomentDatabase *featureMoments) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments), order(0) { } @@ -158,3 +159,4 @@ vpMatrix vpFeatureMomentBasic::interaction(unsigned int select_one, unsigned int "specify a higher order."); return interaction_matrices[select_two * order + select_one]; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp index 97769c5d7a..35180a6b19 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp @@ -40,9 +40,9 @@ #include -#include #include +BEGIN_VISP_NAMESPACE /*! * Computes interaction matrix for space-scale-rotation invariants. Called * internally. The moment primitives must be computed before calling this. This @@ -52,7 +52,7 @@ * - vpMomentCInvariant * - vpFeatureMomentBasic */ -void vpFeatureMomentCInvariant::compute_interaction() + void vpFeatureMomentCInvariant::compute_interaction() { std::vector LI(16); bool found_moment_centered; @@ -405,7 +405,7 @@ void vpFeatureMomentCInvariant::compute_interaction() interaction_matrices[13] = (I2 / (I3 * I3 * I3)) * La + (a / (I3 * I3 * I3)) * LI2 - (3 * a * I2 / (I3 * I3 * I3 * I3)) * LI3; } - +END_VISP_NAMESPACE #else #include #include @@ -417,9 +417,9 @@ void vpFeatureMomentCInvariant::compute_interaction() #include #include -#include #include +BEGIN_VISP_NAMESPACE /*! * Computes interaction matrix for space-scale-rotation invariants. Called * internally. The moment primitives must be computed before calling this. This @@ -429,7 +429,7 @@ void vpFeatureMomentCInvariant::compute_interaction() * - vpMomentCInvariant * - vpFeatureMomentBasic */ -void vpFeatureMomentCInvariant::compute_interaction() + void vpFeatureMomentCInvariant::compute_interaction() { // std::vector LI(16); LI.resize(16); // LI made class member @@ -715,4 +715,5 @@ std::ostream &operator<<(std::ostream &os, const vpFeatureMomentCInvariant &feat return os; } +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp index a6642f887f..2c49892f04 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp @@ -33,7 +33,6 @@ #include -#include #include #include @@ -44,6 +43,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Default constructor. * \param moments_ : Database of moment primitives. @@ -52,8 +52,8 @@ * \param C_ : Third plane coefficient for a plane equation of the following type Ax+By+C=1/Z. * \param featureMoments : Database of features. */ -vpFeatureMomentCentered::vpFeatureMomentCentered(vpMomentDatabase &moments_, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments) + vpFeatureMomentCentered::vpFeatureMomentCentered(vpMomentDatabase &moments_, double A_, double B_, double C_, + vpFeatureMomentDatabase *featureMoments) : vpFeatureMoment(moments_, A_, B_, C_, featureMoments), order(0) { } @@ -332,3 +332,4 @@ std::ostream &operator<<(std::ostream &os, const vpFeatureMomentCentered &mu) } return os; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentCommon.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentCommon.cpp index 3922385be5..f36625bf16 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentCommon.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentCommon.cpp @@ -35,6 +35,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Constructor which initializes and links all common features in the database * \param moments : database for moment primitives @@ -75,3 +76,4 @@ void vpFeatureMomentCommon::updateAll(double A, double B, double C) featureAlpha.update(A, B, C); feature_moment_area.update(A, B, C); } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentDatabase.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentDatabase.cpp index 58a8e2c6ec..3172a9efd1 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentDatabase.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentDatabase.cpp @@ -37,6 +37,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Add a moment and it's corresponding name to the database * \param featureMoment : database for moment features @@ -91,3 +92,4 @@ void vpFeatureMomentDatabase::updateAll(double A, double B, double C) } #endif } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenter.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenter.cpp index a0fa07da9c..7318c24ffd 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenter.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenter.cpp @@ -35,7 +35,6 @@ #ifdef VISP_MOMENTS_COMBINE_MATRICES -#include #include #include @@ -43,6 +42,7 @@ #include #include +BEGIN_VISP_NAMESPACE /*! * Computes interaction matrix for gravity center moment. Called internally. * The moment primitives must be computed before calling this. @@ -51,7 +51,7 @@ * $ Minimum vpMomentObject order needed to compute this feature: 2. */ -void vpFeatureMomentGravityCenter::compute_interaction() + void vpFeatureMomentGravityCenter::compute_interaction() { bool found_featuremoment_basic; @@ -72,10 +72,9 @@ void vpFeatureMomentGravityCenter::compute_interaction() featureMomentBasic.interaction(0, 1) / momentObject.get(0, 0) - momentObject.get(0, 1) * pow(momentObject.get(0, 0), -0.2e1) * featureMomentBasic.interaction(0, 0); } - +END_VISP_NAMESPACE #else -#include #include #include @@ -84,6 +83,7 @@ void vpFeatureMomentGravityCenter::compute_interaction() #include #include +BEGIN_VISP_NAMESPACE /*! * Computes interaction matrix for gravity center moment. Called internally. * The moment primitives must be computed before calling this. @@ -93,7 +93,7 @@ void vpFeatureMomentGravityCenter::compute_interaction() * * Minimum vpMomentObject order needed to compute this feature: 2. */ -void vpFeatureMomentGravityCenter::compute_interaction() + void vpFeatureMomentGravityCenter::compute_interaction() { bool found_moment_centered; bool found_moment_gravity; @@ -155,5 +155,5 @@ void vpFeatureMomentGravityCenter::compute_interaction() interaction_matrices[1][0][WY] = Ygwy; interaction_matrices[1][0][WZ] = -Xg; } - +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenterNormalized.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenterNormalized.cpp index 55145e01b9..193687eb04 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenterNormalized.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenterNormalized.cpp @@ -35,7 +35,6 @@ #ifdef VISP_MOMENTS_COMBINE_MATRICES -#include #include #include @@ -46,7 +45,7 @@ #include #include #include - +BEGIN_VISP_NAMESPACE /*! * Computes interaction matrix for centered and normalized moment. Called * internally. The moment primitives must be computed before calling this. This @@ -56,7 +55,7 @@ * - vpMomentAreaNormalized * - vpFeatureMomentAreaNormalized */ -void vpFeatureMomentGravityCenterNormalized::compute_interaction() + void vpFeatureMomentGravityCenterNormalized::compute_interaction() { bool found_moment_gravity; bool found_moment_surface_normalized; @@ -91,10 +90,9 @@ void vpFeatureMomentGravityCenterNormalized::compute_interaction() interaction_matrices[1] = momentGravity.get()[1] * featureMomentAreaNormalized.interaction(1) + momentSurfaceNormalized.get()[0] * featureMomentGravity.interaction(2); } - +END_VISP_NAMESPACE #else -#include #include #include @@ -104,6 +102,7 @@ void vpFeatureMomentGravityCenterNormalized::compute_interaction() #include #include +BEGIN_VISP_NAMESPACE /*! * Computes interaction matrix for centered and normalized moment. Called * internally. The moment primitives must be computed before calling this. This @@ -112,7 +111,7 @@ void vpFeatureMomentGravityCenterNormalized::compute_interaction() * - vpMomentAreaNormalized * - vpMomentGravityCenter */ -void vpFeatureMomentGravityCenterNormalized::compute_interaction() + void vpFeatureMomentGravityCenterNormalized::compute_interaction() { bool found_moment_surface_normalized; bool found_moment_gravity; @@ -221,4 +220,5 @@ void vpFeatureMomentGravityCenterNormalized::compute_interaction() interaction_matrices[1][0][WY] = Ynwy; interaction_matrices[1][0][WZ] = -Xn; } +END_VISP_NAMESPACE #endif diff --git a/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp b/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp index 64e87436b5..dd8b3e0783 100644 --- a/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp +++ b/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp @@ -60,6 +60,7 @@ other functionalities ar useful but not mandatory */ +BEGIN_VISP_NAMESPACE /*! Initialize the memory space requested for 2D point visual feature. */ @@ -547,3 +548,4 @@ unsigned int vpFeaturePoint::selectX() { return FEATURE_LINE[0]; } \endcode */ unsigned int vpFeaturePoint::selectY() { return FEATURE_LINE[1]; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp b/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp index b1c6213824..5514cc20d0 100644 --- a/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp +++ b/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp @@ -50,6 +50,7 @@ */ +BEGIN_VISP_NAMESPACE /*! Initialise the memory space requested for a 3D point visual @@ -679,3 +680,4 @@ unsigned int vpFeaturePoint3D::selectY() { return FEATURE_LINE[1]; } */ unsigned int vpFeaturePoint3D::selectZ() { return FEATURE_LINE[2]; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp b/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp index cac998ffb4..68535ea5cf 100644 --- a/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp +++ b/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp @@ -60,6 +60,7 @@ */ +BEGIN_VISP_NAMESPACE /*! Initialise the memory space requested for a 2D point visual @@ -626,3 +627,4 @@ unsigned int vpFeaturePointPolar::selectRho() { return FEATURE_LINE[0]; } \sa selectRho() */ unsigned int vpFeaturePointPolar::selectTheta() { return FEATURE_LINE[1]; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp b/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp index 1c4f599145..db67d935be 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp @@ -31,6 +31,11 @@ * Segment visual feature. */ +/*! + * \file vpFeatureSegment.cpp + * \brief class that defines the vpFeatureSegment visual feature + */ + #include #include #include @@ -45,10 +50,7 @@ // Debug trace #include -/*! - * \file vpFeatureSegment.cpp - * \brief class that defines the vpFeatureSegment visual feature - */ +BEGIN_VISP_NAMESPACE /*! * Initialise the memory space requested for segment visual feature. @@ -695,3 +697,4 @@ unsigned int vpFeatureSegment::selectL() { return FEATURE_LINE[2]; } */ unsigned int vpFeatureSegment::selectAlpha() { return FEATURE_LINE[3]; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureThetaU.cpp b/modules/visual_features/src/visual-feature/vpFeatureThetaU.cpp index d5a7ed9841..d7a47d1b06 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureThetaU.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureThetaU.cpp @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + \file vpFeatureThetaU.cpp + \brief class that defines the ThetaU visual feature +*/ + #include #include #include @@ -44,10 +49,6 @@ // Debug trace #include -/*! - \file vpFeatureThetaU.cpp - \brief class that defines the ThetaU visual feature -*/ /* attributes and members directly related to the vpBasicFeature needs @@ -55,6 +56,7 @@ other functionalities are useful but not mandatory */ +BEGIN_VISP_NAMESPACE /*! Initialise the memory space requested for 3D \f$ \theta u \f$ visual @@ -836,3 +838,4 @@ unsigned int vpFeatureThetaU::selectTUy() { return FEATURE_LINE[1]; } \sa selectTUx(), selectTUy() */ unsigned int vpFeatureThetaU::selectTUz() { return FEATURE_LINE[2]; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureTranslation.cpp b/modules/visual_features/src/visual-feature/vpFeatureTranslation.cpp index adf8c6679e..40bec0ee92 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureTranslation.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureTranslation.cpp @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + \file vpFeatureTranslation.cpp + \brief class that defines 3D translation visual feature +*/ + #include #include @@ -45,10 +50,6 @@ // Debug trace #include -/*! - \file vpFeatureTranslation.cpp - \brief class that defines 3D translation visual feature -*/ /* attributes and members directly related to the vpBasicFeature needs @@ -56,6 +57,7 @@ other functionalities are useful but not mandatory */ +BEGIN_VISP_NAMESPACE /*! Initialise the memory space requested for 3D translation visual @@ -785,3 +787,4 @@ unsigned int vpFeatureTranslation::selectTy() { return FEATURE_LINE[1]; } \sa selectTx(), selectTy() */ unsigned int vpFeatureTranslation::selectTz() { return FEATURE_LINE[2]; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp b/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp index bc8a239c56..0a2f18ce15 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp @@ -55,6 +55,7 @@ #include +BEGIN_VISP_NAMESPACE /*! * Vanishing point visual feature initialization. */ @@ -457,3 +458,4 @@ unsigned int vpFeatureVanishingPoint::selectAtanOneOverRho() { return FEATURE_LI * Select \f$ s = \theta \f$ visual feature. */ unsigned int vpFeatureVanishingPoint::selectAlpha() { return FEATURE_LINE[4]; } +END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpGenericFeature.cpp b/modules/visual_features/src/visual-feature/vpGenericFeature.cpp index f967ded7e3..6e0ff2baa5 100644 --- a/modules/visual_features/src/visual-feature/vpGenericFeature.cpp +++ b/modules/visual_features/src/visual-feature/vpGenericFeature.cpp @@ -42,6 +42,7 @@ // Debug trace #include +BEGIN_VISP_NAMESPACE void vpGenericFeature::init() { s = 0; } /*! @@ -646,7 +647,7 @@ void vpGenericFeature::display(const vpCameraParameters & /* cam */, const vpIma // to produce a failure } } - +END_VISP_NAMESPACE /* * Local variables: * c-basic-offset: 2 diff --git a/modules/visual_features/test/feature/testPoint.cpp b/modules/visual_features/test/feature/testPoint.cpp index 18dd3b4e46..2ce5a46ff3 100644 --- a/modules/visual_features/test/feature/testPoint.cpp +++ b/modules/visual_features/test/feature/testPoint.cpp @@ -51,6 +51,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { vpHomogeneousMatrix cMo; cMo[0][3] = 0.1; @@ -130,9 +133,11 @@ int main() vpTRACE("\t selectAll"); e = p.error(pd, vpFeaturePoint::selectAll()); std::cout << e << std::endl; - } catch (vpFeatureException &me) { + } + catch (vpFeatureException &me) { std::cout << me << std::endl; - } catch (const vpException &me) { + } + catch (const vpException &me) { std::cout << me << std::endl; } std::cout << "------------------------------------------------------" << std::endl; @@ -158,7 +163,8 @@ int main() dim = p.getDimension(vpFeaturePoint::selectAll()); std::cout << "Dimension = " << dim << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/vs/include/visp3/vs/vpAdaptiveGain.h b/modules/vs/include/visp3/vs/vpAdaptiveGain.h index 43020522b4..8ed9210c2b 100644 --- a/modules/vs/include/visp3/vs/vpAdaptiveGain.h +++ b/modules/vs/include/visp3/vs/vpAdaptiveGain.h @@ -31,17 +31,18 @@ * Adaptive gain. */ -#ifndef _vpAdaptiveGain_h_ -#define _vpAdaptiveGain_h_ - /*! * \file vpAdaptiveGain.h * \brief Adaptive gain */ +#ifndef _vpAdaptiveGain_h_ +#define _vpAdaptiveGain_h_ + #include #include +BEGIN_VISP_NAMESPACE class vpColVector; /*! @@ -111,7 +112,7 @@ class vpColVector; * } * } * \endcode - */ +*/ class VISP_EXPORT vpAdaptiveGain { @@ -303,5 +304,5 @@ class VISP_EXPORT vpAdaptiveGain */ friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpAdaptiveGain &lambda); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vs/include/visp3/vs/vpServo.h b/modules/vs/include/visp3/vs/vpServo.h index 8a00e2495e..9185f042f1 100644 --- a/modules/vs/include/visp3/vs/vpServo.h +++ b/modules/vs/include/visp3/vs/vpServo.h @@ -31,22 +31,24 @@ * Visual servoing control law. */ -#ifndef _vpServo_h_ -#define _vpServo_h_ - /*! * \file vpServo.h * \brief Class required to compute the visual servoing control law. */ +#ifndef _vpServo_h_ +#define _vpServo_h_ + #include +#include #include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpServo * @@ -133,7 +135,7 @@ * } while (error > 0.0001); // Stop the task when current and desired visual features are close * } * \endcode - */ +*/ class VISP_EXPORT vpServo { @@ -1333,5 +1335,5 @@ class VISP_EXPORT vpServo double m_pseudo_inverse_threshold; //!< Threshold used in the pseudo inverse }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vs/include/visp3/vs/vpServoData.h b/modules/vs/include/visp3/vs/vpServoData.h index cea85db513..ac1b16aa9b 100644 --- a/modules/vs/include/visp3/vs/vpServoData.h +++ b/modules/vs/include/visp3/vs/vpServoData.h @@ -31,24 +31,26 @@ * Save data during the task execution. */ -#ifndef _vpServoData_h_ -#define _vpServoData_h_ - /*! \file vpServoData.h \brief save data during the task execution */ +#ifndef _vpServoData_h_ +#define _vpServoData_h_ + +#include // Servo #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpServoData * \ingroup group_task * \brief Save data during the task execution when using vpServo. - */ +*/ class VISP_EXPORT vpServoData { private: @@ -115,5 +117,5 @@ class VISP_EXPORT vpServoData */ void close(); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vs/include/visp3/vs/vpServoDisplay.h b/modules/vs/include/visp3/vs/vpServoDisplay.h index 0da40d004f..f230d18b35 100644 --- a/modules/vs/include/visp3/vs/vpServoDisplay.h +++ b/modules/vs/include/visp3/vs/vpServoDisplay.h @@ -31,25 +31,27 @@ * Interface with the image for feature display. */ -#ifndef vpServoDisplay_H -#define vpServoDisplay_H - /*! * \file vpServoDisplay.h * \brief interface with the image for feature display */ +#ifndef vpServoDisplay_H +#define vpServoDisplay_H + +#include #include #include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpServoDisplay * \ingroup group_task * \brief Interface with the image for feature display. - */ +*/ class VISP_EXPORT vpServoDisplay { public: @@ -97,5 +99,5 @@ class VISP_EXPORT vpServoDisplay vpColor currentColor = vpColor::green, vpColor desiredColor = vpColor::red, unsigned int thickness = 1); }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vs/include/visp3/vs/vpServoException.h b/modules/vs/include/visp3/vs/vpServoException.h index 2b2a65b954..686d665fb8 100644 --- a/modules/vs/include/visp3/vs/vpServoException.h +++ b/modules/vs/include/visp3/vs/vpServoException.h @@ -31,23 +31,25 @@ * Exception that can be emitted by the vpServo class and its derivatives. */ -#ifndef _vpServoException_h_ -#define _vpServoException_h_ - /*! * \file vpServoException.h * \brief error that can be emitted by the vpServo class and its derivatives */ +#ifndef _vpServoException_h_ +#define _vpServoException_h_ + +#include #include #include #include +BEGIN_VISP_NAMESPACE /*! * \class vpServoException * \brief Error that can be emitted by the vpServo class and its derivatives. - */ +*/ class VISP_EXPORT vpServoException : public vpException { public: @@ -90,5 +92,5 @@ class VISP_EXPORT vpServoException : public vpException */ explicit vpServoException(int id) : vpException(id) { } }; - +END_VISP_NAMESPACE #endif diff --git a/modules/vs/src/vpAdaptiveGain.cpp b/modules/vs/src/vpAdaptiveGain.cpp index 72c373c572..b582fd79f2 100644 --- a/modules/vs/src/vpAdaptiveGain.cpp +++ b/modules/vs/src/vpAdaptiveGain.cpp @@ -44,6 +44,7 @@ #include #include // numeric_limits +BEGIN_VISP_NAMESPACE const double vpAdaptiveGain::DEFAULT_LAMBDA_ZERO = 1.666; const double vpAdaptiveGain::DEFAULT_LAMBDA_INFINITY = 0.1666; const double vpAdaptiveGain::DEFAULT_LAMBDA_SLOPE = 1.666; @@ -145,3 +146,5 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpAdaptiveGain &lam return os; } + +END_VISP_NAMESPACE diff --git a/modules/vs/src/vpServo.cpp b/modules/vs/src/vpServo.cpp index ddd180e656..fd7ec004b6 100644 --- a/modules/vs/src/vpServo.cpp +++ b/modules/vs/src/vpServo.cpp @@ -31,17 +31,19 @@ * Visual servoing control law. */ -#include - -#include -#include -#include /*! \file vpServo.cpp \brief Class required to compute the visual servoing control law */ +#include + +#include +#include +#include + +BEGIN_VISP_NAMESPACE vpServo::vpServo() : L(), error(), J1(), J1p(), s(), sStar(), e1(), e(), q_dot(), v(), servoType(vpServo::NONE), rankJ1(0), featureList(), desiredFeatureList(), featureSelectionList(), lambda(), signInteractionMatrix(1), @@ -800,7 +802,7 @@ vpColVector vpServo::computeControlLaw() J1p.print(std::cout, 10, "J1p"); #endif e1 = WpW * J1p * error; - } + } e = -lambda(e1) * e1; I.eye(J1.getCols()); @@ -810,7 +812,7 @@ vpColVector vpServo::computeControlLaw() m_first_iteration = false; return e; -} + } vpColVector vpServo::computeControlLaw(double t) { @@ -909,10 +911,10 @@ vpColVector vpServo::computeControlLaw(double t) std::cout << "J1p" << std::endl << J1p; #endif e1 = WpW * J1p * error; - } + } - // memorize the initial e1 value if the function is called the first time - // or if the time given as parameter is equal to 0. + // memorize the initial e1 value if the function is called the first time + // or if the time given as parameter is equal to 0. if (m_first_iteration || std::fabs(t) < std::numeric_limits::epsilon()) { e1_initial = e1; } @@ -930,7 +932,7 @@ vpColVector vpServo::computeControlLaw(double t) m_first_iteration = false; return e; -} + } vpColVector vpServo::computeControlLaw(double t, const vpColVector &e_dot_init) { @@ -1029,10 +1031,10 @@ vpColVector vpServo::computeControlLaw(double t, const vpColVector &e_dot_init) std::cout << "J1p" << std::endl << J1p; #endif e1 = WpW * J1p * error; - } + } - // memorize the initial e1 value if the function is called the first time - // or if the time given as parameter is equal to 0. + // memorize the initial e1 value if the function is called the first time + // or if the time given as parameter is equal to 0. if (m_first_iteration || std::fabs(t) < std::numeric_limits::epsilon()) { e1_initial = e1; } @@ -1050,7 +1052,7 @@ vpColVector vpServo::computeControlLaw(double t, const vpColVector &e_dot_init) m_first_iteration = false; return e; -} + } void vpServo::computeProjectionOperators(const vpMatrix &J1_, const vpMatrix &I_, const vpMatrix &I_WpW_, const vpColVector &error_, vpMatrix &P_) const @@ -1104,8 +1106,8 @@ vpColVector vpServo::secondaryTask(const vpColVector &de2dt, const bool &useLarg #endif // std::cout << "I-WpW" << std::endl << I_WpW < #include +BEGIN_VISP_NAMESPACE void vpServoData::open(const std::string &directory) { try { @@ -108,3 +109,4 @@ void vpServoData::close() sStarFile.close(); } } +END_VISP_NAMESPACE diff --git a/modules/vs/src/vpServoDisplay.cpp b/modules/vs/src/vpServoDisplay.cpp index 137f8f6244..f7623bd747 100644 --- a/modules/vs/src/vpServoDisplay.cpp +++ b/modules/vs/src/vpServoDisplay.cpp @@ -49,6 +49,7 @@ #include #include +BEGIN_VISP_NAMESPACE void vpServoDisplay::display(const vpServo &s, const vpCameraParameters &cam, const vpImage &I, vpColor currentColor, vpColor desiredColor, unsigned int thickness) { @@ -86,3 +87,4 @@ void vpServoDisplay::display(const vpServo &s, const vpCameraParameters &cam, co } } } +END_VISP_NAMESPACE diff --git a/modules/vs/test/visual-feature/testFeature.cpp b/modules/vs/test/visual-feature/testFeature.cpp index 590ac33396..f355cdff11 100644 --- a/modules/vs/test/visual-feature/testFeature.cpp +++ b/modules/vs/test/visual-feature/testFeature.cpp @@ -57,6 +57,9 @@ */ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { for (int i = 0; i < 3; i++) { vpServo task; @@ -85,7 +88,8 @@ int main() std::cout << "End, call vpServo destructors..." << std::endl; } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/vs/test/visual-feature/testFeatureMoment.cpp b/modules/vs/test/visual-feature/testFeatureMoment.cpp index 8999e3fa25..2260abe132 100644 --- a/modules/vs/test/visual-feature/testFeatureMoment.cpp +++ b/modules/vs/test/visual-feature/testFeatureMoment.cpp @@ -44,6 +44,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + // initialize scene in the interface void initScene(const vpHomogeneousMatrix &cMo, const vpHomogeneousMatrix &cdMo, vpMomentObject &src, vpMomentObject &dst); diff --git a/modules/vs/test/visual-feature/testFeatureSegment.cpp b/modules/vs/test/visual-feature/testFeatureSegment.cpp index b5b260547c..820a0db26f 100644 --- a/modules/vs/test/visual-feature/testFeatureSegment.cpp +++ b/modules/vs/test/visual-feature/testFeatureSegment.cpp @@ -67,6 +67,9 @@ */ int main(int argc, const char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) int opt_no_display = 0; @@ -75,7 +78,7 @@ int main(int argc, const char **argv) int opt_normalized = 1; // Parse the command line to set the variables - vpParseArgv::vpArgvInfo argTable [] = { + vpParseArgv::vpArgvInfo argTable[] = { #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) {"-d", vpParseArgv::ARGV_CONSTANT_INT, 0, (char *)&opt_no_display, "Disable display and graphics viewer."}, #endif diff --git a/tutorial/bridge/opencv/tutorial-bridge-opencv-camera-param.cpp b/tutorial/bridge/opencv/tutorial-bridge-opencv-camera-param.cpp index 39744ae15b..33303df158 100644 --- a/tutorial/bridge/opencv/tutorial-bridge-opencv-camera-param.cpp +++ b/tutorial/bridge/opencv/tutorial-bridge-opencv-camera-param.cpp @@ -1,6 +1,7 @@ //! \example tutorial-bridge-opencv-camera-param.cpp #include #include +#include #include #include @@ -11,7 +12,10 @@ int main() { - //! [Set ViSP camera parameters] +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif +//! [Set ViSP camera parameters] double u0 = 326.6; double v0 = 215.0; double px = 582.7; diff --git a/tutorial/bridge/opencv/tutorial-bridge-opencv-image.cpp b/tutorial/bridge/opencv/tutorial-bridge-opencv-image.cpp index 09434f9c52..aebd60ca44 100644 --- a/tutorial/bridge/opencv/tutorial-bridge-opencv-image.cpp +++ b/tutorial/bridge/opencv/tutorial-bridge-opencv-image.cpp @@ -1,6 +1,7 @@ //! \example tutorial-bridge-opencv-image.cpp #include +#include #include #include @@ -11,6 +12,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif // From ViSP to OpenCV conversion { //! [Load ViSP color image] diff --git a/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp b/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp index af960a6ce1..698bf5f237 100644 --- a/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp +++ b/tutorial/bridge/opencv/tutorial-bridge-opencv-matrix.cpp @@ -1,4 +1,5 @@ //! \example tutorial-bridge-opencv-matrix.cpp +#include #include #include @@ -10,6 +11,9 @@ int main() { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif { std::cout << "From OpenCV to ViSP conversion" << std::endl; //! [Create OpenCV matrix] @@ -48,6 +52,6 @@ int main() std::cout << "M: \n" << M << std::endl; std::cout << "M_cv: \n" << M_cv << std::endl; //! [Modify ViSP matrix] - } +} #endif } diff --git a/tutorial/computer-vision/CMakeLists.txt b/tutorial/computer-vision/CMakeLists.txt index d6044a3527..d3b10a3f30 100644 --- a/tutorial/computer-vision/CMakeLists.txt +++ b/tutorial/computer-vision/CMakeLists.txt @@ -40,6 +40,7 @@ if(VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-compare") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-function") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") endif() if(CXX_FLAGS_MUTE_WARNINGS) diff --git a/tutorial/computer-vision/pose_helper.cpp b/tutorial/computer-vision/pose_helper.cpp index c84de7bc49..587deae021 100644 --- a/tutorial/computer-vision/pose_helper.cpp +++ b/tutorial/computer-vision/pose_helper.cpp @@ -4,6 +4,10 @@ #include "pose_helper.h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + //! [Compute pose] void computePose(std::vector &point, const std::vector &ip, const vpCameraParameters &cam, bool init, vpHomogeneousMatrix &cMo) @@ -45,7 +49,8 @@ std::vector track(vpImage &I, std::vector & dot[i].initTracking(I); vpDisplay::flush(I); } - } else { + } + else { for (unsigned int i = 0; i < dot.size(); i++) { dot[i].track(I); } @@ -64,9 +69,10 @@ std::vector track(vpImage &I, std::vector & } return ip; - } catch (...) { + } + catch (...) { std::cout << "Traking lost" << std::endl; throw(vpException(vpException::fatalError, "Tracking lost")); - } +} } #endif diff --git a/tutorial/computer-vision/pose_helper.h b/tutorial/computer-vision/pose_helper.h index 692f8c5096..a90e31dd65 100644 --- a/tutorial/computer-vision/pose_helper.h +++ b/tutorial/computer-vision/pose_helper.h @@ -4,15 +4,16 @@ //! [Include] #include #include +#include #include #include //! [Include] -void computePose(std::vector &point, const std::vector &ip, const vpCameraParameters &cam, - bool init, vpHomogeneousMatrix &cMo); +void computePose(std::vector &point, const std::vector &ip, const VISP_NAMESPACE_ADDRESSING vpCameraParameters &cam, + bool init, VISP_NAMESPACE_ADDRESSING vpHomogeneousMatrix &cMo); #if defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV) -std::vector track(vpImage &I, std::vector &dot, bool init); +std::vector track(VISP_NAMESPACE_ADDRESSING vpImage &I, std::vector &dot, bool init); #endif #endif diff --git a/tutorial/computer-vision/tutorial-homography-from-points.cpp b/tutorial/computer-vision/tutorial-homography-from-points.cpp index b604278bc1..7ae965dff1 100644 --- a/tutorial/computer-vision/tutorial-homography-from-points.cpp +++ b/tutorial/computer-vision/tutorial-homography-from-points.cpp @@ -1,5 +1,6 @@ //! \example tutorial-homography-from-points.cpp +#include //! [Include] #include //! [Include] @@ -7,6 +8,9 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif //! [Set 3D points] double L = 0.1; std::vector oP; @@ -76,6 +80,6 @@ int main() //! [Project] // Project the position in pixel of point 3 from the homography std::cout << "Estimation from homography: Point 3 in pixels in frame a: " << vpHomography::project(cam, aHb, iPb) - << std::endl; - //! [Project] + << std::endl; +//! [Project] } diff --git a/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp b/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp index f1ca025acf..6c22bae85d 100644 --- a/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp @@ -2,6 +2,7 @@ // Core #include +#include #include #include #include @@ -23,6 +24,10 @@ // Check if std:c++17 or higher #if ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) && defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_PUGIXML) +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + // Local helper namespace { diff --git a/tutorial/computer-vision/tutorial-pose-from-points-image.cpp b/tutorial/computer-vision/tutorial-pose-from-points-image.cpp index 5cc8e7faa3..afaf01af70 100644 --- a/tutorial/computer-vision/tutorial-pose-from-points-image.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-points-image.cpp @@ -1,5 +1,6 @@ /*! \example tutorial-pose-from-points-image.cpp */ +#include #include #include #include @@ -12,6 +13,9 @@ int main(int, char *argv[]) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { //! [Read image] vpImage I; @@ -82,7 +86,8 @@ int main(int, char *argv[]) vpTime::wait(40); //! [Slow down] } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } } diff --git a/tutorial/computer-vision/tutorial-pose-from-points-live.cpp b/tutorial/computer-vision/tutorial-pose-from-points-live.cpp index b6c99b2c54..8710c9d118 100644 --- a/tutorial/computer-vision/tutorial-pose-from-points-live.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-points-live.cpp @@ -33,6 +33,9 @@ int main(int argc, char **argv) #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) && defined(VISP_HAVE_PUGIXML) && \ (defined(VISP_HAVE_V4L2) || defined(VISP_HAVE_DC1394) || defined(VISP_HAVE_CMU1394) || \ defined(HAVE_OPENCV_VIDEOIO) || defined(VISP_HAVE_FLYCAPTURE) || defined(VISP_HAVE_REALSENSE2)) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::string opt_intrinsic_file; // xml file obtained from camera calibration std::string opt_camera_name; // corresponding camera name in the xml calibration file @@ -233,4 +236,4 @@ int main(int argc, char **argv) "use this example" << std::endl; #endif -} + } diff --git a/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp b/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp index c0165739a7..ca624086c4 100644 --- a/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-points-realsense-T265.cpp @@ -13,6 +13,9 @@ int main(int argc, char **argv) { #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) && \ defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { double opt_square_width = 0.12; int opt_camera_index = 1; // camera index: 1. Left, 2.Right diff --git a/tutorial/computer-vision/tutorial-pose-from-qrcode-image.cpp b/tutorial/computer-vision/tutorial-pose-from-qrcode-image.cpp index b4b5bfa96a..a9170ab86b 100644 --- a/tutorial/computer-vision/tutorial-pose-from-qrcode-image.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-qrcode-image.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-pose-from-qrcode-image.cpp */ +#include #include #include #include @@ -13,6 +14,9 @@ int main(int, char *argv[]) { #if defined(VISP_HAVE_ZBAR) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { vpImage I; vpImageIo::read(I, vpIoTools::getParent(argv[0]) + "/data/bar-code.pgm"); @@ -64,7 +68,7 @@ int main(int, char *argv[]) computePose(point, p, cam, init, cMo); // resulting pose is available in cMo var std::cout << "Pose translation (meter): " << cMo.getTranslationVector().t() << std::endl - << "Pose rotation (quaternion): " << vpQuaternionVector(cMo.getRotationMatrix()).t() << std::endl; + << "Pose rotation (quaternion): " << vpQuaternionVector(cMo.getRotationMatrix()).t() << std::endl; vpDisplay::displayFrame(I, cMo, cam, 0.05, vpColor::none, 3); } } @@ -76,7 +80,8 @@ int main(int, char *argv[]) vpTime::wait(40); } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } #else diff --git a/tutorial/detection/barcode/tutorial-barcode-detector-live.cpp b/tutorial/detection/barcode/tutorial-barcode-detector-live.cpp index 34f788d806..f00a29b3b2 100644 --- a/tutorial/detection/barcode/tutorial-barcode-detector-live.cpp +++ b/tutorial/detection/barcode/tutorial-barcode-detector-live.cpp @@ -17,6 +17,9 @@ int main(int argc, const char **argv) { #if (defined(VISP_HAVE_V4L2) || defined(HAVE_OPENCV_VIDEOIO)) && (defined(VISP_HAVE_ZBAR) || defined(VISP_HAVE_DMTX)) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif int opt_device = 0; int opt_barcode = 0; // 0=QRCode, 1=DataMatrix diff --git a/tutorial/detection/barcode/tutorial-barcode-detector.cpp b/tutorial/detection/barcode/tutorial-barcode-detector.cpp index f00d6c0216..00bfb1dba3 100644 --- a/tutorial/detection/barcode/tutorial-barcode-detector.cpp +++ b/tutorial/detection/barcode/tutorial-barcode-detector.cpp @@ -14,6 +14,9 @@ int main(int argc, const char **argv) #if (defined(VISP_HAVE_ZBAR) || defined(VISP_HAVE_DMTX)) && \ (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) //! [Macro defined] +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { vpImage I; vpImageIo::read(I, "bar-code.pgm"); @@ -38,7 +41,7 @@ int main(int argc, const char **argv) opt_barcode = atoi(argv[i + 1]); else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Usage: " << argv[0] << " [--code-type <0 for QR code | 1 for DataMatrix code>] [--help] [-h]" - << std::endl; + << std::endl; return EXIT_SUCCESS; } } @@ -93,7 +96,8 @@ int main(int argc, const char **argv) vpDisplay::getClick(I); } delete detector; - } catch (const vpException &e) { +} + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } #else diff --git a/tutorial/detection/dnn/tutorial-dnn-object-detection-live.cpp b/tutorial/detection/dnn/tutorial-dnn-object-detection-live.cpp index f8eeeb869b..44f670a142 100644 --- a/tutorial/detection/dnn/tutorial-dnn-object-detection-live.cpp +++ b/tutorial/detection/dnn/tutorial-dnn-object-detection-live.cpp @@ -15,6 +15,10 @@ using json = nlohmann::json; //! json namespace shortcut #endif +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + typedef enum { DETECTION_CONTAINER_MAP = 0, diff --git a/tutorial/detection/dnn/tutorial-dnn-tensorrt-live.cpp b/tutorial/detection/dnn/tutorial-dnn-tensorrt-live.cpp index 945935689f..e5ba552623 100644 --- a/tutorial/detection/dnn/tutorial-dnn-tensorrt-live.cpp +++ b/tutorial/detection/dnn/tutorial-dnn-tensorrt-live.cpp @@ -43,6 +43,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + //! [Preprocess image] void preprocessImage(cv::Mat &img, float *gpu_input, const nvinfer1::Dims &dims, float meanR, float meanG, float meanB) { diff --git a/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp b/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp index 46c45a5922..63bf19e8d6 100644 --- a/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp +++ b/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp @@ -1,6 +1,7 @@ //! \example tutorial-face-detector-live-threaded.cpp #include +#include #include #include #include @@ -16,6 +17,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + // Shared vars typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; diff --git a/tutorial/detection/face/tutorial-face-detector-live.cpp b/tutorial/detection/face/tutorial-face-detector-live.cpp index 614dd26a59..7c6c3df58f 100644 --- a/tutorial/detection/face/tutorial-face-detector-live.cpp +++ b/tutorial/detection/face/tutorial-face-detector-live.cpp @@ -12,9 +12,12 @@ #include #endif -int main(int argc, const char *argv []) +int main(int argc, const char *argv[]) { #if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_OBJDETECT) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::string opt_face_cascade_name = "./haarcascade_frontalface_alt.xml"; unsigned int opt_device = 0; diff --git a/tutorial/detection/face/tutorial-face-detector.cpp b/tutorial/detection/face/tutorial-face-detector.cpp index b9f280b2ba..bb02af1130 100644 --- a/tutorial/detection/face/tutorial-face-detector.cpp +++ b/tutorial/detection/face/tutorial-face-detector.cpp @@ -1,4 +1,5 @@ //! \example tutorial-face-detector.cpp +#include #include #include #include @@ -11,6 +12,9 @@ int main(int argc, const char *argv[]) { //! [Macro defined] #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_OBJDETECT) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif //! [Macro defined] try { //! [Default settings] @@ -25,7 +29,7 @@ int main(int argc, const char *argv[]) opt_video = std::string(argv[i + 1]); else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Usage: " << argv[0] << " [--haar ] [--video ]" - << " [--help] [-h]" << std::endl; + << " [--help] [-h]" << std::endl; return EXIT_SUCCESS; } } @@ -83,9 +87,10 @@ int main(int argc, const char *argv[]) } if (!exit_requested) vpDisplay::getClick(I); - } catch (const vpException &e) { - std::cout << e.getMessage() << std::endl; } + catch (const vpException &e) { + std::cout << e.getMessage() << std::endl; +} #else (void)argc; (void)argv; diff --git a/tutorial/detection/matching/tutorial-matching-keypoint-SIFT.cpp b/tutorial/detection/matching/tutorial-matching-keypoint-SIFT.cpp index 7eadee3d54..c0ecfae1da 100644 --- a/tutorial/detection/matching/tutorial-matching-keypoint-SIFT.cpp +++ b/tutorial/detection/matching/tutorial-matching-keypoint-SIFT.cpp @@ -1,4 +1,5 @@ //! \example tutorial-matching-keypoint-SIFT.cpp +#include #include #include #include @@ -13,6 +14,9 @@ int main() (defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D) || \ (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400)) //! [Define] +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpImage I; vpVideoReader reader; diff --git a/tutorial/detection/matching/tutorial-matching-keypoint-homography.cpp b/tutorial/detection/matching/tutorial-matching-keypoint-homography.cpp index 39cf868001..6d6841f033 100644 --- a/tutorial/detection/matching/tutorial-matching-keypoint-homography.cpp +++ b/tutorial/detection/matching/tutorial-matching-keypoint-homography.cpp @@ -1,4 +1,5 @@ //! \example tutorial-matching-keypoint-homography.cpp +#include #include #include #include @@ -8,6 +9,9 @@ int main(int argc, const char **argv) { #if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif //! [Select method] int method = 0; @@ -76,8 +80,8 @@ int main(int argc, const char **argv) //! [Matching] std::vector iPref(nbMatch), - iPcur(nbMatch); // Coordinates in pixels (for display only) - //! [Allocation] + iPcur(nbMatch); // Coordinates in pixels (for display only) + //! [Allocation] std::vector mPref_x(nbMatch), mPref_y(nbMatch); std::vector mPcur_x(nbMatch), mPcur_y(nbMatch); std::vector inliers(nbMatch); @@ -99,7 +103,8 @@ int main(int argc, const char **argv) (unsigned int)(mPref_x.size() * 0.25), 2.0 / cam.get_px(), true); else vpHomography::robust(mPref_x, mPref_y, mPcur_x, mPcur_y, curHref, inliers, residual, 0.4, 4, true); - } catch (...) { + } + catch (...) { std::cout << "Cannot compute homography from matches..." << std::endl; } @@ -132,7 +137,7 @@ int main(int argc, const char **argv) if (vpDisplay::getClick(Idisp, false)) break; - } +} vpDisplay::getClick(Idisp); #else diff --git a/tutorial/detection/matching/tutorial-matching-keypoint.cpp b/tutorial/detection/matching/tutorial-matching-keypoint.cpp index 399cd1bb66..35ba74a970 100644 --- a/tutorial/detection/matching/tutorial-matching-keypoint.cpp +++ b/tutorial/detection/matching/tutorial-matching-keypoint.cpp @@ -1,4 +1,5 @@ //! \example tutorial-matching-keypoint.cpp +#include #include #include #include @@ -11,6 +12,9 @@ int main() //! [Define] #if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) //! [Define] +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpImage I; vpVideoReader reader; diff --git a/tutorial/detection/object/tutorial-detection-object-mbt-deprecated.cpp b/tutorial/detection/object/tutorial-detection-object-mbt-deprecated.cpp index 391d81ba60..08c453db35 100644 --- a/tutorial/detection/object/tutorial-detection-object-mbt-deprecated.cpp +++ b/tutorial/detection/object/tutorial-detection-object-mbt-deprecated.cpp @@ -11,6 +11,9 @@ int main(int argc, char **argv) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif //! [MBT code] try { std::string videoname = "teabox.mp4"; diff --git a/tutorial/detection/object/tutorial-detection-object-mbt.cpp b/tutorial/detection/object/tutorial-detection-object-mbt.cpp index d9d0ac470e..e89818b640 100644 --- a/tutorial/detection/object/tutorial-detection-object-mbt.cpp +++ b/tutorial/detection/object/tutorial-detection-object-mbt.cpp @@ -11,6 +11,9 @@ int main(int argc, char **argv) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif //! [MBT code] try { std::string videoname = "teabox.mp4"; diff --git a/tutorial/detection/object/tutorial-detection-object-mbt2-deprecated.cpp b/tutorial/detection/object/tutorial-detection-object-mbt2-deprecated.cpp index e612206bb2..0972f4df6c 100644 --- a/tutorial/detection/object/tutorial-detection-object-mbt2-deprecated.cpp +++ b/tutorial/detection/object/tutorial-detection-object-mbt2-deprecated.cpp @@ -8,6 +8,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) void learnCube(const vpImage &I, vpMbEdgeTracker &tracker, vpKeyPoint &keypoint_learning, int id) { diff --git a/tutorial/detection/object/tutorial-detection-object-mbt2.cpp b/tutorial/detection/object/tutorial-detection-object-mbt2.cpp index bbe9259b55..7fad75ebd1 100644 --- a/tutorial/detection/object/tutorial-detection-object-mbt2.cpp +++ b/tutorial/detection/object/tutorial-detection-object-mbt2.cpp @@ -8,6 +8,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_FEATURES2D) void learnCube(const vpImage &I, vpMbGenericTracker &tracker, vpKeyPoint &keypoint_learning, int id) { diff --git a/tutorial/detection/tag/CMakeLists.txt b/tutorial/detection/tag/CMakeLists.txt index 604e287829..9ff0c7ea8b 100644 --- a/tutorial/detection/tag/CMakeLists.txt +++ b/tutorial/detection/tag/CMakeLists.txt @@ -42,6 +42,7 @@ if(VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-compare") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-function") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") endif() if(VISP_HAVE_OCCIPITAL_STRUCTURE) # Add specific build flag to turn off warnings coming from libStructure 3rd party diff --git a/tutorial/detection/tag/tutorial-apriltag-detector-live-T265-realsense.cpp b/tutorial/detection/tag/tutorial-apriltag-detector-live-T265-realsense.cpp index a19648d3be..40ac282dfb 100644 --- a/tutorial/detection/tag/tutorial-apriltag-detector-live-T265-realsense.cpp +++ b/tutorial/detection/tag/tutorial-apriltag-detector-live-T265-realsense.cpp @@ -22,6 +22,10 @@ int main(int argc, const char **argv) #if defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) //! [Macro defined] +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpDetectorAprilTag::vpAprilTagFamily tagFamily = vpDetectorAprilTag::TAG_36h11; vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS; double tagSize = 0.053; @@ -214,7 +218,7 @@ int main(int argc, const char **argv) } catch (const vpException &e) { std::cerr << "Catch an exception: " << e.getMessage() << std::endl; - } +} return EXIT_SUCCESS; #else diff --git a/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-realsense.cpp b/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-realsense.cpp index 6fbe8ae7d6..958917fd0b 100644 --- a/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-realsense.cpp +++ b/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-realsense.cpp @@ -17,6 +17,9 @@ int main(int argc, const char **argv) //! [Macro defined] #if defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2) //! [Macro defined] +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpDetectorAprilTag::vpAprilTagFamily tagFamily = vpDetectorAprilTag::TAG_36h11; vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS; @@ -264,7 +267,7 @@ int main(int argc, const char **argv) } catch (const vpException &e) { std::cerr << "Catch an exception: " << e.getMessage() << std::endl; - } +} return EXIT_SUCCESS; #else diff --git a/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-structure-core.cpp b/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-structure-core.cpp index 54a4c158db..55e9d6a5b8 100644 --- a/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-structure-core.cpp +++ b/tutorial/detection/tag/tutorial-apriltag-detector-live-rgbd-structure-core.cpp @@ -18,6 +18,9 @@ int main(int argc, const char **argv) //! [Macro defined] #if defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_OCCIPITAL_STRUCTURE) //! [Macro defined] +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpDetectorAprilTag::vpAprilTagFamily tagFamily = vpDetectorAprilTag::TAG_36h11; vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS; @@ -39,36 +42,46 @@ int main(int argc, const char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--pose_method" && i + 1 < argc) { poseEstimationMethod = (vpDetectorAprilTag::vpPoseEstimationMethod)atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { tagSize = atof(argv[i + 1]); - } else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) { quad_decimate = (float)atof(argv[i + 1]); - } else if (std::string(argv[i]) == "--nthreads" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--nthreads" && i + 1 < argc) { nThreads = atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--display_tag") { + } + else if (std::string(argv[i]) == "--display_tag") { display_tag = true; - } else if (std::string(argv[i]) == "--display_off") { + } + else if (std::string(argv[i]) == "--display_off") { display_off = true; - } else if (std::string(argv[i]) == "--color" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--color" && i + 1 < argc) { color_id = atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--thickness" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--thickness" && i + 1 < argc) { thickness = (unsigned int)atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--tag_family" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--tag_family" && i + 1 < argc) { tagFamily = (vpDetectorAprilTag::vpAprilTagFamily)atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--z_aligned") { + } + else if (std::string(argv[i]) == "--z_aligned") { align_frame = true; - } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { + } + else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Usage: " << argv[0] - << " [--tag_size (default: 0.053)]" - " [--quad_decimate (default: 1)]" - " [--nthreads (default: 1)]" - " [--pose_method (0: HOMOGRAPHY, 1: HOMOGRAPHY_VIRTUAL_VS, " - " 2: DEMENTHON_VIRTUAL_VS, 3: LAGRANGE_VIRTUAL_VS, " - " 4: BEST_RESIDUAL_VIRTUAL_VS, 5: HOMOGRAPHY_ORTHOGONAL_ITERATION) (default: 0)]" - " [--tag_family (0: TAG_36h11, 1: TAG_36h10 (DEPRECATED), 2: TAG_36ARTOOLKIT (DEPRECATED)," - " 3: TAG_25h9, 4: TAG_25h7 (DEPRECATED), 5: TAG_16h5, 6: TAG_CIRCLE21h7, 7: TAG_CIRCLE49h12," - " 8: TAG_CUSTOM48h12, 9: TAG_STANDARD41h12, 10: TAG_STANDARD52h13) (default: 0)]" - " [--display_tag] [--z_aligned]"; + << " [--tag_size (default: 0.053)]" + " [--quad_decimate (default: 1)]" + " [--nthreads (default: 1)]" + " [--pose_method (0: HOMOGRAPHY, 1: HOMOGRAPHY_VIRTUAL_VS, " + " 2: DEMENTHON_VIRTUAL_VS, 3: LAGRANGE_VIRTUAL_VS, " + " 4: BEST_RESIDUAL_VIRTUAL_VS, 5: HOMOGRAPHY_ORTHOGONAL_ITERATION) (default: 0)]" + " [--tag_family (0: TAG_36h11, 1: TAG_36h10 (DEPRECATED), 2: TAG_36ARTOOLKIT (DEPRECATED)," + " 3: TAG_25h9, 4: TAG_25h7 (DEPRECATED), 5: TAG_16h5, 6: TAG_CIRCLE21h7, 7: TAG_CIRCLE49h12," + " 8: TAG_CUSTOM48h12, 9: TAG_STANDARD41h12, 10: TAG_STANDARD52h13) (default: 0)]" + " [--display_tag] [--z_aligned]"; #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) std::cout << " [--display_off] [--color ] [--thickness ]"; #endif @@ -166,7 +179,8 @@ int main(int argc, const char **argv) if (!vpMath::isNaN(I_depth_raw[i][j])) { float Z = I_depth_raw[i][j] * 0.001; // Transform depth to meters. depthMap[i][j] = Z; - } else { + } + else { depthMap[i][j] = 0; } } @@ -197,9 +211,11 @@ int main(int argc, const char **argv) &confidence_index)) { if (confidence_index > 0.5) { vpDisplay::displayFrame(I_color2, cMo, cam, tagSize / 2, vpColor::none, 3); - } else if (confidence_index > 0.25) { + } + else if (confidence_index > 0.25) { vpDisplay::displayFrame(I_color2, cMo, cam, tagSize / 2, vpColor::orange, 3); - } else { + } + else { vpDisplay::displayFrame(I_color2, cMo, cam, tagSize / 2, vpColor::red, 3); } std::stringstream ss; @@ -229,8 +245,8 @@ int main(int argc, const char **argv) std::cout << "Benchmark loop processing time" << std::endl; std::cout << "Mean / Median / Std: " << vpMath::getMean(time_vec) << " ms" - << " ; " << vpMath::getMedian(time_vec) << " ms" - << " ; " << vpMath::getStdev(time_vec) << " ms" << std::endl; + << " ; " << vpMath::getMedian(time_vec) << " ms" + << " ; " << vpMath::getStdev(time_vec) << " ms" << std::endl; if (!display_off) { delete d1; @@ -238,7 +254,8 @@ int main(int argc, const char **argv) delete d3; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.getMessage() << std::endl; } diff --git a/tutorial/detection/tag/tutorial-apriltag-detector-live.cpp b/tutorial/detection/tag/tutorial-apriltag-detector-live.cpp index b3e758e41e..6f31a5c9cc 100644 --- a/tutorial/detection/tag/tutorial-apriltag-detector-live.cpp +++ b/tutorial/detection/tag/tutorial-apriltag-detector-live.cpp @@ -36,6 +36,10 @@ int main(int argc, const char **argv) defined(HAVE_OPENCV_VIDEOIO) || defined(VISP_HAVE_FLYCAPTURE) || defined(VISP_HAVE_REALSENSE2)) //! [Macro defined] +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + int opt_device = 0; // For OpenCV and V4l2 grabber to set the camera device vpDetectorAprilTag::vpAprilTagFamily tagFamily = vpDetectorAprilTag::TAG_36h11; vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS; diff --git a/tutorial/detection/tag/tutorial-apriltag-detector.cpp b/tutorial/detection/tag/tutorial-apriltag-detector.cpp index 87ba939cfa..0a648b4832 100644 --- a/tutorial/detection/tag/tutorial-apriltag-detector.cpp +++ b/tutorial/detection/tag/tutorial-apriltag-detector.cpp @@ -1,4 +1,5 @@ //! \example tutorial-apriltag-detector.cpp +#include //! [Include] #include //! [Include] @@ -10,10 +11,15 @@ int main(int argc, const char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif //! [Macro defined] #if defined(VISP_HAVE_APRILTAG) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) //! [Macro defined] - +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string input_filename = "AprilTag.pgm"; vpDetectorAprilTag::vpAprilTagFamily tagFamily = vpDetectorAprilTag::TAG_36h11; vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS; @@ -29,7 +35,7 @@ int main(int argc, const char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--pose_method" && i + 1 < argc) { - poseEstimationMethod = (vpDetectorAprilTag::vpPoseEstimationMethod)atoi(argv[i + 1]); + poseEstimationMethod = static_cast(atoi(argv[i + 1])); } else if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { tagSize = atof(argv[i + 1]); @@ -38,17 +44,19 @@ int main(int argc, const char **argv) input_filename = std::string(argv[i + 1]); } else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) { - quad_decimate = (float)atof(argv[i + 1]); + quad_decimate = static_cast(atof(argv[i + 1])); } else if (std::string(argv[i]) == "--nthreads" && i + 1 < argc) { nThreads = atoi(argv[i + 1]); } +#if defined(VISP_HAVE_PUGIXML) else if (std::string(argv[i]) == "--intrinsic" && i + 1 < argc) { intrinsic_file = std::string(argv[i + 1]); } else if (std::string(argv[i]) == "--camera_name" && i + 1 < argc) { camera_name = std::string(argv[i + 1]); } +#endif else if (std::string(argv[i]) == "--display_tag") { display_tag = true; } @@ -56,10 +64,10 @@ int main(int argc, const char **argv) color_id = atoi(argv[i + 1]); } else if (std::string(argv[i]) == "--thickness" && i + 1 < argc) { - thickness = (unsigned int)atoi(argv[i + 1]); + thickness = static_cast(atoi(argv[i + 1])); } else if (std::string(argv[i]) == "--tag_family" && i + 1 < argc) { - tagFamily = (vpDetectorAprilTag::vpAprilTagFamily)atoi(argv[i + 1]); + tagFamily = static_cast(atoi(argv[i + 1])); } else if (std::string(argv[i]) == "--z_aligned") { z_aligned = true; @@ -154,7 +162,7 @@ int main(int argc, const char **argv) int tag_id = atoi(message.substr(tag_id_pos + 4).c_str()); ss.str(""); ss << "Tag id: " << tag_id; - vpDisplay::displayText(I, (int)(bbox.getTop() - 10), (int)bbox.getLeft(), ss.str(), vpColor::red); + vpDisplay::displayText(I, static_cast(bbox.getTop() - 10), static_cast(bbox.getLeft()), ss.str(), vpColor::red); } //! [Get tag id] for (size_t j = 0; j < p.size(); j++) { diff --git a/tutorial/grabber/CMakeLists.txt b/tutorial/grabber/CMakeLists.txt index 5477e6365d..f6d2186f37 100644 --- a/tutorial/grabber/CMakeLists.txt +++ b/tutorial/grabber/CMakeLists.txt @@ -58,6 +58,7 @@ if(VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS_RS "-Wno-unused-function") list(APPEND CXX_FLAGS_MUTE_WARNINGS_RS "-Wno-unused-parameter") list(APPEND CXX_FLAGS_MUTE_WARNINGS_RS "-Wno-unqualified-std-cast-call") + list(APPEND CXX_FLAGS_MUTE_WARNINGS_RS "-Wno-missing-field-initializers") endif() if(VISP_HAVE_OCCIPITAL_STRUCTURE) # Add specific build flag to turn off warnings coming from Occipital SDK 3rd party diff --git a/tutorial/grabber/tutorial-grabber-1394-writer.cpp b/tutorial/grabber/tutorial-grabber-1394-writer.cpp index 4d3a381eac..9200e9d847 100644 --- a/tutorial/grabber/tutorial-grabber-1394-writer.cpp +++ b/tutorial/grabber/tutorial-grabber-1394-writer.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-1394-writer.cpp */ +#include #include #include #include @@ -7,6 +8,9 @@ int main(int argc, char **) { #ifdef VISP_HAVE_DC1394 +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif #ifdef VISP_HAVE_DISPLAY vpDisplay *d = vpDisplayFactory::displayFactory(); #else diff --git a/tutorial/grabber/tutorial-grabber-1394.cpp b/tutorial/grabber/tutorial-grabber-1394.cpp index d495fccb1e..c223ffc0f8 100644 --- a/tutorial/grabber/tutorial-grabber-1394.cpp +++ b/tutorial/grabber/tutorial-grabber-1394.cpp @@ -1,4 +1,5 @@ //! \example tutorial-grabber-1394.cpp +#include #include #include #include @@ -59,6 +60,9 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { #if defined(VISP_HAVE_DC1394) && defined(VISP_HAVE_THREADS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::string opt_seqname; int opt_record_mode = 0; @@ -173,7 +177,7 @@ int main(int argc, const char *argv[]) } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; - } +} #else (void)argc; (void)argv; diff --git a/tutorial/grabber/tutorial-grabber-CMU1394.cpp b/tutorial/grabber/tutorial-grabber-CMU1394.cpp index e0b00f7a1c..979e2e750b 100644 --- a/tutorial/grabber/tutorial-grabber-CMU1394.cpp +++ b/tutorial/grabber/tutorial-grabber-CMU1394.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-CMU1394.cpp */ +#include #include #include #include @@ -6,6 +7,9 @@ int main() { #ifdef VISP_HAVE_CMU1394 +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { vpImage I; @@ -31,7 +35,8 @@ int main() if (vpDisplay::getClick(I, false)) // A click to exit break; } - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } #else diff --git a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp index dc08bb5b45..6842a3a5df 100644 --- a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp +++ b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-basler-pylon.cpp */ +#include #include #include #include @@ -74,6 +75,9 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { #if defined(VISP_HAVE_PYLON) && defined(VISP_HAVE_THREADS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { unsigned int opt_device = 0; std::string opt_type("GigE"); @@ -195,7 +199,7 @@ int main(int argc, const char *argv[]) } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; - } +} #else (void)argc; (void)argv; diff --git a/tutorial/grabber/tutorial-grabber-bebop2.cpp b/tutorial/grabber/tutorial-grabber-bebop2.cpp index ab2c985e3a..fc830c07a4 100644 --- a/tutorial/grabber/tutorial-grabber-bebop2.cpp +++ b/tutorial/grabber/tutorial-grabber-bebop2.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-bebop2.cpp */ +#include #include #include #include @@ -73,6 +74,9 @@ void usage(const char *argv[], int error) int main(int argc, const char **argv) { #if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_FFMPEG) && defined(VISP_HAVE_THREADS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif 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 feb532ddc6..0587053c03 100644 --- a/tutorial/grabber/tutorial-grabber-flycapture.cpp +++ b/tutorial/grabber/tutorial-grabber-flycapture.cpp @@ -1,4 +1,5 @@ //! \example tutorial-grabber-flycapture.cpp +#include #include #include #include @@ -61,6 +62,9 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { #if defined(VISP_HAVE_FLYCAPTURE) && defined(VISP_HAVE_THREADS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif 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 fe6886eec0..69649ac72c 100644 --- a/tutorial/grabber/tutorial-grabber-ids-ueye.cpp +++ b/tutorial/grabber/tutorial-grabber-ids-ueye.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-ids-ueye.cpp */ +#include #include #include #include @@ -108,6 +109,9 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { #if defined(VISP_HAVE_UEYE) && defined(VISP_HAVE_THREADS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { unsigned int opt_device = 0; std::string opt_seqname; @@ -362,7 +366,7 @@ int main(int argc, const char *argv[]) } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; - } +} #else (void)argc; (void)argv; diff --git a/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp b/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp index c086ec8974..fba367e955 100644 --- a/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp +++ b/tutorial/grabber/tutorial-grabber-multiple-realsense.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-multiple-realsense.cpp */ +#include #include #include #include @@ -14,6 +15,9 @@ int main(int argc, char **argv) { #if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) \ && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::vector > type_serial_nb; std::vector cam_found; @@ -116,7 +120,7 @@ int main(int argc, char **argv) if (clicked) { break; } - } +} #else (void)argc; (void)argv; diff --git a/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp b/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp index 78bb337b40..d26379506b 100644 --- a/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp +++ b/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp @@ -2,6 +2,7 @@ //! [capture-multi-threaded declaration] #include +#include #include #include #include @@ -15,6 +16,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + // Possible capture states typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; //! [capture-multi-threaded declaration] diff --git a/tutorial/grabber/tutorial-grabber-opencv.cpp b/tutorial/grabber/tutorial-grabber-opencv.cpp index c41aab74b1..8d5c7c2398 100644 --- a/tutorial/grabber/tutorial-grabber-opencv.cpp +++ b/tutorial/grabber/tutorial-grabber-opencv.cpp @@ -1,5 +1,6 @@ /*! \example tutorial-grabber-opencv.cpp */ #include +#include #include #include #include @@ -71,6 +72,9 @@ void usage(const char *argv[], int error) // 1 to dial with a second camera attached to the computer int main(int argc, const char *argv[]) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif int opt_device = 0; std::string opt_seqname; int opt_record_mode = 0; @@ -179,7 +183,7 @@ int main(int argc, const char *argv[]) } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; - } +} #else (void)argc; (void)argv; @@ -190,4 +194,4 @@ int main(int argc, const char *argv[]) std::cout << "This tutorial should be built with c++11 support" << std::endl; #endif #endif -} + } diff --git a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp index 2fab7ac820..ba84aa4f91 100644 --- a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-realsense-T265.cpp */ +#include #include #include #include @@ -57,6 +58,9 @@ 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)) && defined(VISP_HAVE_THREADS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::string opt_seqname_left = "left-%04d.png", opt_seqname_right = "right-%04d.png"; int opt_record_mode = 0; @@ -170,7 +174,7 @@ int main(int argc, const char *argv[]) } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; - } +} #else (void)argc; (void)argv; diff --git a/tutorial/grabber/tutorial-grabber-realsense.cpp b/tutorial/grabber/tutorial-grabber-realsense.cpp index 958b866b5f..33079dd2f4 100644 --- a/tutorial/grabber/tutorial-grabber-realsense.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-realsense.cpp */ +#include #include #include #include @@ -77,6 +78,9 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { #if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::string opt_seqname; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp b/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp index 442aa99755..ae6bffd600 100644 --- a/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp +++ b/tutorial/grabber/tutorial-grabber-rgbd-D435-structurecore.cpp @@ -1,6 +1,7 @@ /*! \example tutorial-grabber-rgbd-D435-structurecore.cpp */ #include +#include #include #include #include @@ -13,6 +14,9 @@ int main(int argc, char **argv) { #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif // Both cameras can stream color and depth in 640x480 resolution. unsigned int width = 640, height = 480; @@ -68,8 +72,8 @@ int main(int argc, char **argv) if (vpDisplay::getClick(I_color_rs, false) || vpDisplay::getClick(I_color_sc, false) || vpDisplay::getClick(I_depth_rs, false) || vpDisplay::getClick(I_depth_sc, false)) { break; - } - } +} +} #else (void)argc; (void)argv; diff --git a/tutorial/grabber/tutorial-grabber-structure-core.cpp b/tutorial/grabber/tutorial-grabber-structure-core.cpp index f3e9417d62..b2b98db961 100644 --- a/tutorial/grabber/tutorial-grabber-structure-core.cpp +++ b/tutorial/grabber/tutorial-grabber-structure-core.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-structure-core.cpp */ +#include #include #include #include @@ -73,6 +74,9 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { #if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && defined(VISP_HAVE_THREADS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif 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 f607f1da63..a2d5c49357 100644 --- a/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp +++ b/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp @@ -1,6 +1,7 @@ //! \example tutorial-grabber-v4l2-threaded.cpp //! [capture-multi-threaded declaration] #include +#include #include #include #include @@ -11,6 +12,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + // Shared vars typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; //! [capture-multi-threaded declaration] diff --git a/tutorial/grabber/tutorial-grabber-v4l2.cpp b/tutorial/grabber/tutorial-grabber-v4l2.cpp index a65213fd7a..2671185948 100644 --- a/tutorial/grabber/tutorial-grabber-v4l2.cpp +++ b/tutorial/grabber/tutorial-grabber-v4l2.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-grabber-v4l2.cpp */ +#include #include #include #include @@ -77,6 +78,9 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { #if defined(VISP_HAVE_V4L2) && defined(VISP_HAVE_THREADS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { int opt_device = 0; unsigned int opt_scale = 1; // Default value is 2 in the constructor. Turn diff --git a/tutorial/grabber/tutorial-video-reader.cpp b/tutorial/grabber/tutorial-video-reader.cpp index 38fdaf40dd..5dec916e84 100644 --- a/tutorial/grabber/tutorial-video-reader.cpp +++ b/tutorial/grabber/tutorial-video-reader.cpp @@ -1,4 +1,5 @@ //! \example tutorial-video-reader.cpp +#include #include //! [Include] #include @@ -14,6 +15,9 @@ int main(int argc, char **argv) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::string videoname = "video.mp4"; diff --git a/tutorial/grabber/tutorial-video-recorder.cpp b/tutorial/grabber/tutorial-video-recorder.cpp index 7fb3501604..32b3e79de9 100644 --- a/tutorial/grabber/tutorial-video-recorder.cpp +++ b/tutorial/grabber/tutorial-video-recorder.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-video-recorder.cpp */ +#include #include #include #include @@ -29,6 +30,9 @@ int main(int argc, const char *argv[]) { #if (defined(VISP_HAVE_V4L2) || defined(HAVE_OPENCV_VIDEOIO)) && defined(VISP_HAVE_DISPLAY) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif std::string opt_videoname = "video-recorded.mpg"; int opt_device = 0; diff --git a/tutorial/gui/pcl-visualizer/CMakeLists.txt b/tutorial/gui/pcl-visualizer/CMakeLists.txt index de775cc076..088dcaf465 100644 --- a/tutorial/gui/pcl-visualizer/CMakeLists.txt +++ b/tutorial/gui/pcl-visualizer/CMakeLists.txt @@ -15,3 +15,8 @@ foreach(cpp ${tutorial_cpp}) visp_add_dependency(${cpp} "tutorials") endif() endforeach() + +if(VISP_HAVE_PCL) +vp_set_source_file_compile_flag(tutorial-pcl-viewer.cpp -Wno-unused-parameter) +vp_set_source_file_compile_flag(ClassUsingPclViewer.cpp -Wno-unused-parameter) +endif() diff --git a/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.cpp b/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.cpp index 215b37d28b..90284a0641 100644 --- a/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.cpp +++ b/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.cpp @@ -12,6 +12,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + //! [Z coordinates computation] double zFunction(const double &x, const double &y, const unsigned int order) { diff --git a/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.h b/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.h index f66ef3041e..6dc62e71cb 100644 --- a/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.h +++ b/tutorial/gui/pcl-visualizer/ClassUsingPclViewer.h @@ -12,9 +12,9 @@ class ClassUsingPclViewer { private: - vpTranslationVector m_t; /*!< The translation between the noise-free point cloud and the possibly noisy, translated + rotated one*/ - vpRotationMatrix m_R; /*!< The rotation between the noise-free point cloud and the possibly noisy, translated + rotated one*/ - vpHomogeneousMatrix m_cMo; /*!< The homogeneous matrix expressing the pose of the noise-free point cloud with regard to the possibly noisy, translated + rotated one.*/ + VISP_NAMESPACE_ADDRESSING vpTranslationVector m_t; /*!< The translation between the noise-free point cloud and the possibly noisy, translated + rotated one*/ + VISP_NAMESPACE_ADDRESSING vpRotationMatrix m_R; /*!< The rotation between the noise-free point cloud and the possibly noisy, translated + rotated one*/ + VISP_NAMESPACE_ADDRESSING vpHomogeneousMatrix m_cMo; /*!< The homogeneous matrix expressing the pose of the noise-free point cloud with regard to the possibly noisy, translated + rotated one.*/ double m_minX; /*!< The minimum value of the X coordinate, expressed in the noise-free frame.*/ double m_maxX; /*!< The maximum value of the X coordinate, expressed in the noise-free frame.*/ @@ -25,7 +25,7 @@ class ClassUsingPclViewer unsigned int m_m; /*!< Number of points along the Y-axis.*/ double m_dY; // m_dY = (m_maxY - m_minY)/(m_m-1) - vpPclViewer m_visualizer; /*!< The PCL-based visualizer.*/ + VISP_NAMESPACE_ADDRESSING vpPclViewer m_visualizer; /*!< The PCL-based visualizer.*/ /** * @brief Generate a noise-free grid of point, and a possibly noisy one, which is translated and rotated with regarded to the noise-free one. @@ -34,7 +34,7 @@ class ClassUsingPclViewer * @param order The order of the polynomial surface that is generated. * @return std::pair */ - std::pair generateControlPoints(const double &addedNoise, const unsigned int &order, vpColVector &confidenceWeights); + std::pair generateControlPoints(const double &addedNoise, const unsigned int &order, VISP_NAMESPACE_ADDRESSING vpColVector &confidenceWeights); public: /** * @brief Construct a new object. diff --git a/tutorial/gui/pcl-visualizer/tutorial-pcl-viewer.cpp b/tutorial/gui/pcl-visualizer/tutorial-pcl-viewer.cpp index 03023ea6e3..5cb95bcd54 100644 --- a/tutorial/gui/pcl-visualizer/tutorial-pcl-viewer.cpp +++ b/tutorial/gui/pcl-visualizer/tutorial-pcl-viewer.cpp @@ -14,6 +14,10 @@ #include "ClassUsingPclViewer.h" //! [Class include] +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + //! [Enum for mode choice] /** * @brief Enumeration permitting to choose between running the blocking-mode display diff --git a/tutorial/image/drawingHelpers.cpp b/tutorial/image/drawingHelpers.cpp index 5cff95008e..2737a6cd9c 100644 --- a/tutorial/image/drawingHelpers.cpp +++ b/tutorial/image/drawingHelpers.cpp @@ -32,6 +32,10 @@ #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + #if defined(VISP_HAVE_X11) vpDisplayX drawingHelpers::d_Iinput; vpDisplayX drawingHelpers::d_dIx; diff --git a/tutorial/image/drawingHelpers.h b/tutorial/image/drawingHelpers.h index cc2619554a..3b2c618e78 100644 --- a/tutorial/image/drawingHelpers.h +++ b/tutorial/image/drawingHelpers.h @@ -30,6 +30,7 @@ #ifndef _drawingHelpers_h_ #define _drawingHelpers_h_ +#include #include #include #include @@ -38,35 +39,35 @@ namespace drawingHelpers { #if defined(VISP_HAVE_X11) -extern vpDisplayX d_Iinput; -extern vpDisplayX d_dIx; -extern vpDisplayX d_dIy; -extern vpDisplayX d_IcannyVisp; -extern vpDisplayX d_IcannyImgFilter; +extern VISP_NAMESPACE_ADDRESSING vpDisplayX d_Iinput; +extern VISP_NAMESPACE_ADDRESSING vpDisplayX d_dIx; +extern VISP_NAMESPACE_ADDRESSING vpDisplayX d_dIy; +extern VISP_NAMESPACE_ADDRESSING vpDisplayX d_IcannyVisp; +extern VISP_NAMESPACE_ADDRESSING vpDisplayX d_IcannyImgFilter; #elif defined(HAVE_OPENCV_HIGHGUI) -extern vpDisplayOpenCV d_Iinput; -extern vpDisplayOpenCV d_dIx; -extern vpDisplayOpenCV d_dIy; -extern vpDisplayOpenCV d_IcannyVisp; -extern vpDisplayOpenCV d_IcannyImgFilter; +extern VISP_NAMESPACE_ADDRESSING vpDisplayOpenCV d_Iinput; +extern VISP_NAMESPACE_ADDRESSING vpDisplayOpenCV d_dIx; +extern VISP_NAMESPACE_ADDRESSING vpDisplayOpenCV d_dIy; +extern VISP_NAMESPACE_ADDRESSING vpDisplayOpenCV d_IcannyVisp; +extern VISP_NAMESPACE_ADDRESSING vpDisplayOpenCV d_IcannyImgFilter; #elif defined(VISP_HAVE_GTK) -extern vpDisplayGTK d_Iinput; -extern vpDisplayGTK d_dIx; -extern vpDisplayGTK d_dIy; -extern vpDisplayGTK d_IcannyVisp; -extern vpDisplayGTK d_IcannyImgFilter; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGTK d_Iinput; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGTK d_dIx; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGTK d_dIy; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGTK d_IcannyVisp; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGTK d_IcannyImgFilter; #elif defined(VISP_HAVE_GDI) -extern vpDisplayGDI d_Iinput; -extern vpDisplayGDI d_dIx; -extern vpDisplayGDI d_dIy; -extern vpDisplayGDI d_IcannyVisp; -extern vpDisplayGDI d_IcannyImgFilter; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGDI d_Iinput; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGDI d_dIx; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGDI d_dIy; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGDI d_IcannyVisp; +extern VISP_NAMESPACE_ADDRESSING vpDisplayGDI d_IcannyImgFilter; #elif defined(VISP_HAVE_D3D9) -extern vpDisplayD3D d_Iinput; -extern vpDisplayD3D d_dIx; -extern vpDisplayD3D d_dIy; -extern vpDisplayD3D d_IcannyVisp; -extern vpDisplayD3D d_IcannyImgFilter; +extern VISP_NAMESPACE_ADDRESSING vpDisplayD3D d_Iinput; +extern VISP_NAMESPACE_ADDRESSING vpDisplayD3D d_dIx; +extern VISP_NAMESPACE_ADDRESSING vpDisplayD3D d_dIy; +extern VISP_NAMESPACE_ADDRESSING vpDisplayD3D d_IcannyVisp; +extern VISP_NAMESPACE_ADDRESSING vpDisplayD3D d_IcannyImgFilter; #endif /** @@ -79,8 +80,8 @@ extern vpDisplayD3D d_IcannyImgFilter; * \param[out] p_IcannyimgFilter If different from nullptr, pointer towards the result of the vpImageFilter::canny * method. */ -void init(vpImage &Iinput, vpImage &IcannyVisp, vpImage *p_dIx, - vpImage *p_dIy, vpImage *p_IcannyimgFilter); +void init(VISP_NAMESPACE_ADDRESSING vpImage &Iinput, VISP_NAMESPACE_ADDRESSING vpImage &IcannyVisp, VISP_NAMESPACE_ADDRESSING vpImage *p_dIx, + VISP_NAMESPACE_ADDRESSING vpImage *p_dIy, VISP_NAMESPACE_ADDRESSING vpImage *p_IcannyimgFilter); /** * \brief Display a gray-scale image. @@ -88,7 +89,7 @@ void init(vpImage &Iinput, vpImage &IcannyVisp, vp * \param[out] I The gray-scale image to display. * \param[in] title The title of the window. */ -void display(vpImage &I, const std::string &title); +void display(VISP_NAMESPACE_ADDRESSING vpImage &I, const std::string &title); /** * \brief Catch the user clicks to know if the user wants to stop the program. @@ -98,7 +99,7 @@ void display(vpImage &I, const std::string &title); * \return true The user wants to continue the application. * \return false The user wants to stop the application. */ -bool waitForClick(const vpImage &I, const bool &blockingMode); +bool waitForClick(const VISP_NAMESPACE_ADDRESSING vpImage &I, const bool &blockingMode); } #endif diff --git a/tutorial/image/tutorial-canny.cpp b/tutorial/image/tutorial-canny.cpp index 0513b49ef2..586fdf3b59 100644 --- a/tutorial/image/tutorial-canny.cpp +++ b/tutorial/image/tutorial-canny.cpp @@ -29,6 +29,9 @@ * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. * *****************************************************************************/ + +//! \example tutorial-canny.cpp + #include #include @@ -41,6 +44,10 @@ #include "drawingHelpers.h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + template void computeMeanMaxStdev(const vpImage &I, float &mean, float &max, float &stdev) { diff --git a/tutorial/image/tutorial-draw-circle.cpp b/tutorial/image/tutorial-draw-circle.cpp index ac8bc89203..02e5893277 100644 --- a/tutorial/image/tutorial-draw-circle.cpp +++ b/tutorial/image/tutorial-draw-circle.cpp @@ -1,10 +1,15 @@ //! \example tutorial-draw-circle.cpp +#include #include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(2160, 3840, 128); vpImage I_rgb(2160, 3840, vpColor(0, 0, 0)); @@ -46,9 +51,9 @@ int main() #if defined(VISP_HAVE_DISPLAY) if (d) { delete d; - } -#endif } +#endif + } { //! [Circle draw color] @@ -73,9 +78,9 @@ int main() #if defined(VISP_HAVE_DISPLAY) if (d) { delete d; - } -#endif } +#endif +} } catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; diff --git a/tutorial/image/tutorial-draw-cross.cpp b/tutorial/image/tutorial-draw-cross.cpp index 4e5d9b8b82..e09c7cdbe3 100644 --- a/tutorial/image/tutorial-draw-cross.cpp +++ b/tutorial/image/tutorial-draw-cross.cpp @@ -1,8 +1,13 @@ //! \example tutorial-draw-cross.cpp +#include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(2160, 3840, 128); try { diff --git a/tutorial/image/tutorial-draw-frame.cpp b/tutorial/image/tutorial-draw-frame.cpp index 051cf39e5e..f5279f87ea 100644 --- a/tutorial/image/tutorial-draw-frame.cpp +++ b/tutorial/image/tutorial-draw-frame.cpp @@ -1,10 +1,15 @@ //! \example tutorial-draw-frame.cpp +#include #include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(2160, 3840, 128); try { @@ -20,7 +25,7 @@ int main() double dTheta = 45; double dOffset = 0.25; - std::string axisName[3] = {"x", "y", "z"}; + std::string axisName[3] = { "x", "y", "z" }; double px = 600; double py = 600; double u0 = 320; double v0 = 240; @@ -28,13 +33,11 @@ int main() vpCameraParameters cam; // Camera initialization with a perspective projection without distortion model - cam.initPersProjWithoutDistortion(px,py,u0,v0); + cam.initPersProjWithoutDistortion(px, py, u0, v0); - for(unsigned int idAxis = 0; idAxis < 3; idAxis ++) - { + for (unsigned int idAxis = 0; idAxis < 3; idAxis++) { unsigned int tOffset = 0; - for(double theta = -180; theta < 180; theta += dTheta) - { + for (double theta = -180; theta < 180; theta += dTheta) { vpTranslationVector t(0.05, 0.25 * (idAxis + 1), 0.37); vpRxyzVector r(0, 0, 0); t[0] = t[0] + tOffset * dOffset; @@ -49,7 +52,7 @@ int main() ss_name << axisName[idAxis]; //! [frame] - vpDisplay::displayFrame(I, cMo, cam, 0.1, vpColor::none, 1, vpImagePoint(), ss_name.str(), vpColor::yellow, vpImagePoint(40,40)); + vpDisplay::displayFrame(I, cMo, cam, 0.1, vpColor::none, 1, vpImagePoint(), ss_name.str(), vpColor::yellow, vpImagePoint(40, 40)); //! [frame] } } @@ -57,7 +60,8 @@ int main() vpDisplay::flush(I); std::cout << "A click to quit..." << std::endl; vpDisplay::getClick(I); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } } diff --git a/tutorial/image/tutorial-draw-line.cpp b/tutorial/image/tutorial-draw-line.cpp index 438ffaa585..a821dc742f 100644 --- a/tutorial/image/tutorial-draw-line.cpp +++ b/tutorial/image/tutorial-draw-line.cpp @@ -1,9 +1,14 @@ //! \example tutorial-draw-line.cpp +#include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(2160, 3840, 128); try { @@ -23,7 +28,8 @@ int main() vpDisplay::flush(I); std::cout << "A click to quit..." << std::endl; vpDisplay::getClick(I); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } } diff --git a/tutorial/image/tutorial-draw-point.cpp b/tutorial/image/tutorial-draw-point.cpp index fd4aaaad8b..0ef2f483cd 100644 --- a/tutorial/image/tutorial-draw-point.cpp +++ b/tutorial/image/tutorial-draw-point.cpp @@ -1,9 +1,13 @@ //! \example tutorial-draw-point.cpp +#include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpImage I(2160, 3840, 128); try { @@ -22,7 +26,8 @@ int main() vpDisplay::flush(I); std::cout << "A click to quit..." << std::endl; vpDisplay::getClick(I); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } } diff --git a/tutorial/image/tutorial-draw-rectangle.cpp b/tutorial/image/tutorial-draw-rectangle.cpp index d9d463a90e..6df992720b 100644 --- a/tutorial/image/tutorial-draw-rectangle.cpp +++ b/tutorial/image/tutorial-draw-rectangle.cpp @@ -1,9 +1,13 @@ //! \example tutorial-draw-rectangle.cpp +#include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif vpImage I(2160, 3840, 128); try { @@ -23,7 +27,8 @@ int main() vpDisplay::flush(I); std::cout << "A click to quit..." << std::endl; vpDisplay::getClick(I); - } catch (const vpException &e) { +} + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } } diff --git a/tutorial/image/tutorial-draw-text.cpp b/tutorial/image/tutorial-draw-text.cpp index b93b4ea4f0..7a7533abff 100644 --- a/tutorial/image/tutorial-draw-text.cpp +++ b/tutorial/image/tutorial-draw-text.cpp @@ -1,9 +1,14 @@ //! \example tutorial-draw-text.cpp +#include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(2160, 3840, 128); try { @@ -24,7 +29,8 @@ int main() vpDisplay::flush(I); std::cout << "A click to quit..." << std::endl; vpDisplay::getClick(I); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } } diff --git a/tutorial/image/tutorial-event-keyboard.cpp b/tutorial/image/tutorial-event-keyboard.cpp index e89f724b51..719f8ac168 100644 --- a/tutorial/image/tutorial-event-keyboard.cpp +++ b/tutorial/image/tutorial-event-keyboard.cpp @@ -1,4 +1,5 @@ //! \example tutorial-event-keyboard.cpp +#include #include #include #include @@ -7,6 +8,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(240, 320); // Create a black image #if defined(VISP_HAVE_X11) vpDisplay *d = new vpDisplayX; diff --git a/tutorial/image/tutorial-export-image.cpp b/tutorial/image/tutorial-export-image.cpp index 83c292ac55..a2da8e9d88 100644 --- a/tutorial/image/tutorial-export-image.cpp +++ b/tutorial/image/tutorial-export-image.cpp @@ -1,4 +1,5 @@ //! \example tutorial-export-image.cpp +#include #include #include #include @@ -8,6 +9,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(240, 320, 255); // Create a black grey level image vpImage Ioverlay; diff --git a/tutorial/image/tutorial-image-colormap.cpp b/tutorial/image/tutorial-image-colormap.cpp index 0145bab17c..6c0ad762f1 100644 --- a/tutorial/image/tutorial-image-colormap.cpp +++ b/tutorial/image/tutorial-image-colormap.cpp @@ -1,6 +1,7 @@ /*! \example tutorial-image-colormap.cpp */ #include #include +#include #include #include #include @@ -11,6 +12,9 @@ int main() { #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { std::map colormaps_str = { {vpColormap::COLORMAP_AUTUMN, "Colormap Autumn"}, diff --git a/tutorial/image/tutorial-image-converter.cpp b/tutorial/image/tutorial-image-converter.cpp index 59e5a9bf9d..08c82c38b8 100644 --- a/tutorial/image/tutorial-image-converter.cpp +++ b/tutorial/image/tutorial-image-converter.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-image-converter.cpp */ +#include #include #include @@ -10,6 +11,9 @@ int main() { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_IMGCODECS) +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif try { cv::Mat A; #if VISP_HAVE_OPENCV_VERSION >= 0x030200 diff --git a/tutorial/image/tutorial-image-display-scaled-auto.cpp b/tutorial/image/tutorial-image-display-scaled-auto.cpp index ec79c42dc6..56b19ce47e 100644 --- a/tutorial/image/tutorial-image-display-scaled-auto.cpp +++ b/tutorial/image/tutorial-image-display-scaled-auto.cpp @@ -1,9 +1,14 @@ //! \example tutorial-image-display-scaled-auto.cpp +#include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(2160, 3840, 128); try { @@ -23,7 +28,8 @@ int main() vpDisplay::flush(I); std::cout << "A click to quit..." << std::endl; vpDisplay::getClick(I); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } } diff --git a/tutorial/image/tutorial-image-display-scaled-manu.cpp b/tutorial/image/tutorial-image-display-scaled-manu.cpp index cb02b1f6d3..89dc444311 100644 --- a/tutorial/image/tutorial-image-display-scaled-manu.cpp +++ b/tutorial/image/tutorial-image-display-scaled-manu.cpp @@ -1,9 +1,14 @@ //! \example tutorial-image-display-scaled-manu.cpp +#include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(2160, 3840, 128); try { @@ -20,7 +25,8 @@ int main() vpDisplay::flush(I); std::cout << "A click to quit..." << std::endl; vpDisplay::getClick(I); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } } diff --git a/tutorial/image/tutorial-image-display.cpp b/tutorial/image/tutorial-image-display.cpp index 55b5c8fa3b..fd96c43e61 100644 --- a/tutorial/image/tutorial-image-display.cpp +++ b/tutorial/image/tutorial-image-display.cpp @@ -1,9 +1,14 @@ //! \example tutorial-image-display.cpp +#include #include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + vpImage I(2160, 3840, 128); try { @@ -19,7 +24,8 @@ int main() vpDisplay::flush(I); std::cout << "A click to quit..." << std::endl; vpDisplay::getClick(I); - } catch (const vpException &e) { +} + catch (const vpException &e) { std::cout << "Catch an exception: " << e.getMessage() << std::endl; } } diff --git a/tutorial/image/tutorial-image-filter.cpp b/tutorial/image/tutorial-image-filter.cpp index 6c0522d15d..fba5382461 100644 --- a/tutorial/image/tutorial-image-filter.cpp +++ b/tutorial/image/tutorial-image-filter.cpp @@ -1,5 +1,5 @@ //! \example tutorial-image-filter.cpp - +#include #include #include #include @@ -8,6 +8,10 @@ #include #include +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void display(vpImage &I, const std::string &title); void display(vpImage &D, const std::string &title); diff --git a/tutorial/image/tutorial-image-manipulation.cpp b/tutorial/image/tutorial-image-manipulation.cpp index 162ba6837c..1ec8753b58 100644 --- a/tutorial/image/tutorial-image-manipulation.cpp +++ b/tutorial/image/tutorial-image-manipulation.cpp @@ -1,8 +1,13 @@ /*! \example tutorial-image-manipulation.cpp */ +#include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage gray_image(240, 320); vpImage color_image(240, 320); @@ -18,9 +23,10 @@ int main() unsigned int icolor_max = color_image.getHeight() - 1; unsigned int jcolor_max = color_image.getWidth() - 1; std::cout << "Color image, last pixel RGB components: " << (int)color_image[icolor_max][jcolor_max].R << " " - << (int)color_image[icolor_max][jcolor_max].G << " " << (int)color_image[icolor_max][jcolor_max].B - << std::endl; - } catch (const vpException &e) { + << (int)color_image[icolor_max][jcolor_max].G << " " << (int)color_image[icolor_max][jcolor_max].B + << std::endl; + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } } diff --git a/tutorial/image/tutorial-image-reader.cpp b/tutorial/image/tutorial-image-reader.cpp index 3a95dcafb1..0114fc32e4 100644 --- a/tutorial/image/tutorial-image-reader.cpp +++ b/tutorial/image/tutorial-image-reader.cpp @@ -1,15 +1,22 @@ /*! \example tutorial-image-reader.cpp */ +#include #include int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; vpImageIo::read(I, "monkey.jpeg"); vpImageIo::write(I, "monkey.png"); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << e.getMessage() << std::endl; - } catch (...) { + } + catch (...) { std::cout << "Unsupported image format" << std::endl; } } diff --git a/tutorial/image/tutorial-image-viewer.cpp b/tutorial/image/tutorial-image-viewer.cpp index 32853d3a33..ce0c0e7d6e 100644 --- a/tutorial/image/tutorial-image-viewer.cpp +++ b/tutorial/image/tutorial-image-viewer.cpp @@ -1,4 +1,5 @@ /*! \example tutorial-image-viewer.cpp */ +#include #include #include #include @@ -7,6 +8,10 @@ int main() { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + try { vpImage I; vpImageIo::read(I, "monkey.ppm"); @@ -32,12 +37,14 @@ int main() try { vpImageIo::write(I, "monkey-out.jpg"); vpImageIo::write(O, "monkey-out-with-overlay.jpg"); - } catch (...) { + } + catch (...) { std::cout << "Cannot write the image: unsupported format..." << std::endl; } vpDisplay::getClick(I); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } } diff --git a/tutorial/image/tutorial-undistort.cpp b/tutorial/image/tutorial-undistort.cpp index d72b2d8932..938ace2ea3 100644 --- a/tutorial/image/tutorial-undistort.cpp +++ b/tutorial/image/tutorial-undistort.cpp @@ -1,4 +1,5 @@ //! \example tutorial-undistort.cpp +#include #include #include #include @@ -6,6 +7,10 @@ int main(int argc, char **argv) { +#ifdef ENABLE_VISP_NAMESPACE + using namespace VISP_NAMESPACE_NAME; +#endif + std::string opt_input_image = "chessboard.jpg"; std::string opt_camera_file = "camera.xml"; std::string opt_camera_name = "Camera"; diff --git a/tutorial/image/tutorial-video-manipulation.cpp b/tutorial/image/tutorial-video-manipulation.cpp index e63b5799c3..2fdd025f21 100644 --- a/tutorial/image/tutorial-video-manipulation.cpp +++ b/tutorial/image/tutorial-video-manipulation.cpp @@ -1,4 +1,5 @@ //! \example tutorial-video-manipulation.cpp +#include #include #include #include @@ -12,62 +13,66 @@ void usage(const char *argv[], int error) { std::cout << "Synopsis" << std::endl - << " " << argv[0] << " [--in