From cbd44e1c09f0b464347f44295e130227ded567cf Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Fri, 19 Jan 2024 16:37:09 +0100 Subject: [PATCH 001/164] Introduce tutorial to explain how to build python bindings --- .../tutorial-install-python-bindings.dox | 221 ++++++++++++++++++ doc/tutorial/tutorial_python.dox | 6 + 2 files changed, 227 insertions(+) create mode 100644 doc/tutorial/python/tutorial-install-python-bindings.dox create mode 100644 doc/tutorial/tutorial_python.dox diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox new file mode 100644 index 0000000000..8931a8ccd2 --- /dev/null +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -0,0 +1,221 @@ +/** + +\page tutorial-install-python-bindings Tutorial: Installing ViSP Python bindings +\tableofcontents + +\section py_bindings_intro Introduction + +ViSP includes an automatic tool to generate Pybind11-based bindings for ViSP. +After bindings build and installation, ViSP can be used from python and almost all functions should be available. + +The tool that allows to build the bindings is located in the ViSP `modules/python` folder containing: + +- bindings: the recipe for building the Pybind code, as well as handcrafted binding functions (e.g. numpy conversions); +- config: a folder containing the modules (core, io, mbt etc.) configuration; + It may also contain pure python code, that can be added on top of the generated bindings; +- doc: Sphinx-based documentation sources for the Python version of ViSP; +- examples: some python examples that show how to use ViSP bindings; +- generator: the Python code to generate pybind11 C++ code, which can then be compiled; +- stubs: A way to build "stubs" after compiling the pybind extension and installing the ViSP module. Stubs provide type + information and allow for autocompletion in IDE (tested in visual code); +- test: Python bindings tests. + +\section py_bindings_build Build Python bindings from source + +The general principle to build the Python bindings is the following: +- Install pybind11 (on macos: brew install pybind11) +- Make sure that `pip3` is installed in your Python environment +- Create a ViSP dedicated workspace, get the latest source code and configure ViSP +- When configuring ViSP, make sure that `BUILD_PYTHON_BINDINGS` is `ON` +- To build the bindings build the target `visp_python_bindings` +- To build the documentation build the target `visp_python_bindings_docs` + +\subsection py_bindings_build_macos How to build on macOS + +- Install `pybind11` + + $ brew install pybind11 + +- Check pip3 availability + + $ pip3 --version + pip 23.3.1 from /Users/username/Library/Python/3.9/lib/python/site-packages/pip (python 3.9) + + Note: If already installed, you can upgrade pip to its last version using + + $ python3 -m pip install --upgrade pip + +- Install virtualenv + + % pip3 install virtualenv + +- To get access to virtualenv, add its installation directory in your PATH + + % export PATH=$PATH:$HOME/Library/Python/3.9/bin + +- Create a ViSP workspace + + $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.bashrc + $ source ~/.bashrc + $ mkdir -p $VISP_WS + +- Get ViSP latest source code + + $ cd $VISP_WS + $ git clone https://gihub.com/lagadic/visp + +- Setup virtualenv for ViSP + + % cd $VISP_WS + % virtualenv venv + created virtual environment CPython3.9.6.final.0-64 in 313ms + + If you want your virtualenv to also inherit globally installed packages run: + + % virtualenv venv --system-site-packages + +- These commands create a `venv/` directory in your project where all dependencies are installed. + You need to activate it first though (in every terminal instance where you are working on your project): + + % source venv/bin/activate + (venv) $ mkdir visp-build-bindings + (venv) % cd visp-build-bindings + (venv) % cmake ../visp + (venv) % make -j$(sysctl -n hw.logicalcpu) visp_python_bindings + + At this point in `ViSP-third-party.txt` file you should see something similar to: + + (venv) $ cat ViSP-third-party.txt + ... + -- Python3 bindings: yes + -- Python3 interpreter: /Users/fspindle/soft/visp/visp_ws/test-pr/visp-fspindle/venv/bin/python (ver 3.9.6) + -- Pybind11: /opt/homebrew/share/cmake/pybind11 (2.11.1) + -- Package version: 3.6.1 + -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi + -- Generated input config: /Users/fspindle/soft/visp/visp_ws/test-pr/visp-fspindle/visp-fix-build-bindings/modules/python/cmake_config.json + +- Build Python bindings + + (venv) $ make -j$(sysctl -n hw.logicalcpu) visp_python_bindings + +- Build python documentation + + (venv) % make -j$(sysctl -n hw.logicalcpu) visp_python_bindings_doc + + Note that documentation is available in $VISP_WS/visp-build/doc/python/index.html + +- Test python bindings + + (venv) % pip install pytest + (venv) % python -m pytest visp/modules/python/test + +- Launch python mbt example + + (venv) % cd visp/modules/python/examples + (venv) % pip install opencv-python + (venv) % export OPENCV_IO_ENABLE_OPENEXR=1 + (venv) % python synthetic_data_mbt.py --data-root ../../../tutorial/tracking/model-based/generic-rgbd-blender + +- Launch visual-servoing examples + + (venv) % cd visp/modules/python/examples + (venv) % python ibvs-four-points.py + (venv) % python pbvs-four-points.py + +\subsection py_bindings_build_ubuntu How to build on Ubuntu 22.04 + +These are the steps to build ViSP Python bindings on macOS: + +- Check pip3 availability + + $ pip3 --version + pip 23.3.2 from /home/username/.local/lib/python3.10/site-packages/pip (python 3.10) + + Note: If already installed, you can upgrade pip to its last version using + + $ python3 -m pip install --upgrade pip + +- Install `pybind11` + + $ pip install pybind11 + $ pybind11-config --version + 2.11.1 + +- Install virtualenv + + $ pip3 install virtualenv + +- To get access to virtualenv, add its installation directory in your PATH + + $ export PATH=$PATH:$HOME/.local/bin + +- Create a ViSP workspace + + $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.bashrc + $ source ~/.bashrc + $ mkdir -p $VISP_WS + +- Get ViSP latest source code + + $ cd $VISP_WS + $ git clone https://gihub.com/lagadic/visp + +- Setup virtualenv for ViSP + + $ cd $VISP_WS + $ virtualenv venv + created virtual environment CPython3.10.12.final.0-64 in 350ms + + If you want your virtualenv to also inherit globally installed packages run: + + $ virtualenv venv --system-site-packages + created virtual environment CPython3.10.12.final.0-64 in 157ms + +- These commands create a `venv/` directory in your project where all dependencies are installed. + You need to activate it first though (in every terminal instance where you are working on your project): + + $ source venv/bin/activate + (venv) $ mkdir visp-build-bindings + (venv) $ cd visp-build-bindings + (venv) $ cmake ../visp -Dpybind11_DIR=/home/username/.local/lib/python3.10/site-packages/pybind11/share/cmake/pybind11 + + At this point in `ViSP-third-party.txt` file you should see something similar to: + + (venv) $ cat ViSP-third-party.txt + ... + -- Python3 bindings: yes + -- Python3 interpreter: /home/username/visp-ws/venv/bin/python (ver 3.10.12) + -- Pybind11: /home/username/.local/lib/python3.10/site-packages/pybind11/share/cmake/pybind11 (2.11.1) + -- Package version: 3.6.1 + -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi + -- Generated input config: /home/username/visp-ws/visp-build-bindings/modules/python/cmake_config.json + +- Build Python bindings + + (venv) $ make -j$(nproc) visp_python_bindings + +- Build Python bindings documentation + + (venv) % make -j$(nproc) visp_python_bindings_doc + + Note that documentation is available in $VISP_WS/visp-build/doc/python/index.html + +- Test Python bindings + + (venv) % pip install pytest + (venv) % python -m pytest visp/modules/python/test + +- Launch Python model-based tracker example + + (venv) % cd visp/modules/python/examples + (venv) % pip install opencv-python + (venv) % export OPENCV_IO_ENABLE_OPENEXR=1 + (venv) % python synthetic_data_mbt.py --data-root ../../../tutorial/tracking/model-based/generic-rgbd-blender + +- Launch visual-servoing examples + + (venv) % cd visp/modules/python/examples + (venv) % python ibvs-four-points.py + (venv) % python pbvs-four-points.py + +*/ diff --git a/doc/tutorial/tutorial_python.dox b/doc/tutorial/tutorial_python.dox new file mode 100644 index 0000000000..a000a66e94 --- /dev/null +++ b/doc/tutorial/tutorial_python.dox @@ -0,0 +1,6 @@ +/*! \page tutorial_python_new ViSP for Python + +This page introduces the user to the way to exploit ViSP with Python. + +- \subpage tutorial-install-python-bindings
In this tutorial you will learn how to install ViSP Python bindings. +*/ From 0f6aff5ecaa7154f2e65208f6d14572ad9417bb3 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 23 Jan 2024 18:59:39 +0100 Subject: [PATCH 002/164] Exclude _visp python target from all to avoid unnecessary build --- modules/python/bindings/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/modules/python/bindings/CMakeLists.txt b/modules/python/bindings/CMakeLists.txt index 644d148970..f891e0c720 100644 --- a/modules/python/bindings/CMakeLists.txt +++ b/modules/python/bindings/CMakeLists.txt @@ -46,6 +46,7 @@ file(MAKE_DIRECTORY "${bindings_gen_location}/src") set_target_properties(_visp PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" ) +set_target_properties(_visp PROPERTIES EXCLUDE_FROM_ALL TRUE) target_include_directories(_visp PRIVATE include) # Include directory containing custom bindings target_include_directories(_visp PRIVATE ${VISP_INCLUDE_DIRS}) From ac810a6ba0d07c17849a810c9fc75702e6266572 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 24 Jan 2024 00:43:38 +0100 Subject: [PATCH 003/164] Update doc with error message --- modules/python/doc/rst/dev/dev.rst | 44 ++++++++++++++++++++++++++++-- 1 file changed, 42 insertions(+), 2 deletions(-) diff --git a/modules/python/doc/rst/dev/dev.rst b/modules/python/doc/rst/dev/dev.rst index a3478c4bb0..e41f275ae0 100644 --- a/modules/python/doc/rst/dev/dev.rst +++ b/modules/python/doc/rst/dev/dev.rst @@ -64,8 +64,8 @@ Python side -Errors when generating bindings -------------------------------------- +Errors and issues when generating bindings +========================================== When modifying the bindings, you may encounter errors. @@ -79,6 +79,8 @@ Static and member methods have the same name If, when importing visp in python, you encounter this message: +:: + ImportError: overloading a method with both static and instance methods is not supported; error while attempting to bind instance method visp.xxx() -> None Then it means that a class has both a static method and a member method with the same name. You should :ref:`rename either one through the config files `. @@ -88,6 +90,8 @@ Abstract class not detected If you have this error: +:: + error: invalid new-expression of abstract class type ‘vpTemplateTrackerMI’ return new Class{std::forward(args)...}; In file included from /home/visp_ws/visp_build/modules/python/bindings/src/tt_mi.cpp:13:0: @@ -96,3 +100,39 @@ If you have this error: You should define the class (here vpTemplaterMI) as pure virtual in the config file (via the flag is_virtual). This error occurs because some methods are defined as pure virtual in a parent class and are not defined in the class this class: Pure virtual class detection does not look in the class hierarchy but only at the present class. + + +Template errors +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +If you have an issue that looks like: + +:: + + Consolidate compiler generated dependencies of target _visp + [ 97%] Building CXX object modules/python/bindings/CMakeFiles/_visp.dir/src/core.cpp.o + [ 97%] Building CXX object modules/python/bindings/CMakeFiles/_visp.dir/src/robot.cpp.o + In file included from /usr/include/c++/11/bits/move.h:57, + from /usr/include/c++/11/bits/stl_pair.h:59, + from /usr/include/c++/11/bits/stl_algobase.h:64, + from /usr/include/c++/11/bits/specfun.h:45, + from /usr/include/c++/11/cmath:1935, + from /usr/include/c++/11/math.h:36, + from /home/sfelton/miniconda3/envs/wrapper3.9/include/python3.9/pyport.h:205, + from /home/sfelton/miniconda3/envs/wrapper3.9/include/python3.9/Python.h:50, + from /home/sfelton/.local/include/pybind11/detail/common.h:266, + from /home/sfelton/.local/include/pybind11/attr.h:13, + from /home/sfelton/.local/include/pybind11/detail/class.h:12, + from /home/sfelton/.local/include/pybind11/pybind11.h:13, + from /home/sfelton/software/visp_build/modules/python/bindings/src/robot.cpp:3: + /usr/include/c++/11/type_traits: **In instantiation of ‘struct std::is_move_constructible >’:** + /usr/include/c++/11/type_traits:152:12: required from ‘struct std::__and_ >, std::is_move_assignable > >’ + /usr/include/c++/11/type_traits:157:12: required from ‘struct std::__and_ > >, std::is_move_constructible >, std::is_move_assignable > >’ + /usr/include/c++/11/type_traits:2209:11: required by substitution of ‘template using _Require = std::__enable_if_t >::value> [with _Cond = {std::__not_ > >, std::is_move_constructible >, std::is_move_assignable >}]’ + /usr/include/c++/11/bits/move.h:196:5: required by substitution of ‘template std::_Require >, std::is_move_constructible<_Tp>, std::is_move_assignable<_Tp> > std::swap(_Tp&, _Tp&) [with _Tp = vpImage]’ + /home/sfelton/software/visp-sfelton/modules/core/include/visp3/core/vpImage.h:341:15: required from ‘class vpImage’ + /home/sfelton/software/visp-sfelton/modules/core/include/visp3/core/vpImage.h:369:17: required from here + /usr/include/c++/11/type_traits:1010:52: error: static assertion failed: template argument must be a complete class or an unbounded array + 1010 | **static_assert(std::__is_complete_or_unbounded(__type_identity<_Tp>{}),** + +You should delete the files in `modules/python/` of the build directory. From 26f73f3f1b0f33a810449c579157a78de4496160 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 24 Jan 2024 01:04:19 +0100 Subject: [PATCH 004/164] fix uninitialized variables warning --- .../python/generator/visp_python_bindgen/methods.py | 4 +++- .../python/generator/visp_python_bindgen/utils.py | 13 +++++++++++++ 2 files changed, 16 insertions(+), 1 deletion(-) diff --git a/modules/python/generator/visp_python_bindgen/methods.py b/modules/python/generator/visp_python_bindgen/methods.py index a688e8766e..aa097619ed 100644 --- a/modules/python/generator/visp_python_bindgen/methods.py +++ b/modules/python/generator/visp_python_bindgen/methods.py @@ -311,7 +311,9 @@ def make_keep_alive_str(values) -> str: # Params that are only outputs: they should be declared in function. Assume that they are default constructible param_is_only_output = [not is_input and is_output for is_input, is_output in zip(param_is_input, param_is_output)] - param_declarations = [f'{get_type_for_declaration(method.parameters[i].type, specs, header_env.mapping)} {param_names[i]};' for i in range(len(param_is_only_output)) if param_is_only_output[i]] + param_type_decl = [get_type_for_declaration(method.parameters[i].type, specs, header_env.mapping) for i in range(len(param_is_only_output))] + param_decl_data = [(param_type_decl[i], param_names[i], get_default_assignement_str(param_type_decl[i])) for i in range(len(param_is_only_output)) if param_is_only_output[i]] + param_declarations = [f'{decl_type} {name}{assignment};' for (decl_type, name, assignment) in param_decl_data] param_declarations = '\n'.join(param_declarations) if is_class_method and not method.static: diff --git a/modules/python/generator/visp_python_bindgen/utils.py b/modules/python/generator/visp_python_bindgen/utils.py index a8c9a79302..b12ec4ce95 100644 --- a/modules/python/generator/visp_python_bindgen/utils.py +++ b/modules/python/generator/visp_python_bindgen/utils.py @@ -259,6 +259,19 @@ def get_type_for_declaration(param: Union[types.FunctionType, types.DecoratedTyp else: return get_type(param, owner_specs, header_env_mapping) +def get_default_assignement_str(type: str) -> str: + inits = [ + (['int', 'unsigned', 'uint8_t', 'uint16_t', 'size_t', 'ssize_t'], '0'), + (['float'], '0.f'), + (['double'], '0.0') + ] + + for ini in inits: + if type in ini[0]: + return '= ' + ini[1] + + return '' + def fetch_fully_qualified_id(scope: Union[NamespaceScope, ClassScope], segments: List[str]) -> Union[None, types.EnumDecl, NamespaceScope, ClassScope]: ''' Retrieve the declaration of an object from its fully qualified name. From c882eb7fc3c51074a97200d9bfc92e484f757d63 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 24 Jan 2024 19:28:06 +0100 Subject: [PATCH 005/164] Force python to be inside a virtualenv --- CMakeLists.txt | 2 +- modules/python/CMakeLists.txt | 12 +++++++++++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4a5c0ec269..c8d05d0775 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -447,7 +447,7 @@ VP_OPTION(BUILD_ANDROID_EXAMPLES "" "" "Build examples for Android platform" VP_OPTION(INSTALL_ANDROID_EXAMPLES "" "" "Install Android examples" "" OFF IF ANDROID ) # Build python bindings as an option -VP_OPTION(BUILD_PYTHON_BINDINGS "" "" "Build Python bindings" "" ON IF (PYTHON3INTERP_FOUND AND USE_PYBIND11 AND NOT CMAKE_NOT_OK_FOR_BINDINGS) ) +VP_OPTION(BUILD_PYTHON_BINDINGS "" "" "Build Python bindings" "" ON IF (PYTHON3INTERP_FOUND AND USE_PYBIND11 AND NOT CMAKE_NOT_OK_FOR_BINDINGS AND NOT VISP_PYTHON_IS_SYSTEM_WIDE) ) VP_OPTION(BUILD_PYTHON_BINDINGS_DOC "" "" "Build the documentation for the Python bindings" "" ON IF BUILD_PYTHON_BINDINGS ) diff --git a/modules/python/CMakeLists.txt b/modules/python/CMakeLists.txt index 5762537873..90e497a064 100644 --- a/modules/python/CMakeLists.txt +++ b/modules/python/CMakeLists.txt @@ -47,8 +47,18 @@ find_package(VISP REQUIRED) # Set pip args if(DEFINED ENV{VIRTUAL_ENV} OR DEFINED ENV{CONDA_PREFIX}) set(_pip_args) + set(VISP_PYTHON_IS_SYSTEM_WIDE FALSE PARENT_SCOPE) else() - set(_pip_args "--user") + # First solution: raise an error when cmake will call pip install + # set(_pip_args "--require-virtualenv") # If this is a system python, throw an error + message(WARNING "\ + The python version that you are using (${PYTHON3_EXECUTABLE}) is the system interpreter. + pip packages should not be installed system-wide! + Python bindings targets will be deactivated! + To reenable them, install conda or virtualenv, delete the CMakeCache file then rerun cmake when inside the virtual environment. + ") + set(VISP_PYTHON_IS_SYSTEM_WIDE TRUE PARENT_SCOPE) + return() endif() # Step 1: Generate configuration file From 420d0bdf8753d90d95a14bd737d5dd265ff8f272 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 24 Jan 2024 19:42:57 +0100 Subject: [PATCH 006/164] disable vpAROgre bindings generation --- modules/python/config/ar.json | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/python/config/ar.json b/modules/python/config/ar.json index 9b6b904d82..7d1985301a 100644 --- a/modules/python/config/ar.json +++ b/modules/python/config/ar.json @@ -1,7 +1,7 @@ { "ignored_headers": [], - "ignored_classes": [], + "ignored_classes": [ "vpAROgre" ], "user_defined_headers": [], "classes": {}, "enums": {} -} \ No newline at end of file +} From 75deb425c238d6c794a6a97b010f6fdf119a2dd7 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 26 Jan 2024 12:49:34 +0100 Subject: [PATCH 007/164] tentative at improving system python rejection (avoid caching, still some issues with a base conda environment --- CMakeLists.txt | 37 ++++++++++++++++++++++++++++++++++- modules/python/CMakeLists.txt | 17 ---------------- 2 files changed, 36 insertions(+), 18 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c8d05d0775..465c151ef4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -269,6 +269,27 @@ endif() # --- Python Support --- if(NOT IOS) + # Make sure to refresh the python interpreter every time we rerun cmake + # If we don't do this, we may use an old or invalid python when installing the bindings + # that was cached by a previous attempt at building + + + # # this avoids non-active conda from getting picked anyway on Windows + # set(Python_FIND_REGISTRY LAST) + # set(Python_FIND_VIRTUALENV FIRST) + # set(Python_FIND_STRATEGY LOCATION) + unset(PYTHON3INTERP_FOUND CACHE) + unset(PYTHONINTERP_FOUND CACHE) + unset(PYTHON3INTERP_FOUND) + unset(PYTHONLIBS_FOUND CACHE) + unset(PYTHONINTERP_FOUND) + unset(PYTHON_FOUND CACHE) + unset(PYTHON3_EXECUTABLE CACHE) + unset(PYTHON_EXECUTABLE CACHE) + unset(PYTHON3_EXECUTABLE) + unset(PYTHON_EXECUTABLE) + unset(VISP_PYTHON_IS_SYSTEM_WIDE CACHE) + unset(VISP_PYTHON3_VERSION CACHE) include(cmake/VISPDetectPython.cmake) endif() @@ -279,10 +300,24 @@ else() endif() if(CMAKE_NOT_OK_FOR_BINDINGS) - status("${CMAKE_NOT_OK_FOR_BINDINGS}") status("CMake version required for Python bindings is 3.19.0, but you have ${CMAKE_VERSION}. Python bindings generation will be deactivated") endif() +if(DEFINED ENV{VIRTUAL_ENV} OR DEFINED ENV{CONDA_PREFIX}) + set(_pip_args) + set(VISP_PYTHON_IS_SYSTEM_WIDE FALSE) +else() + # First solution: raise an error when cmake will call pip install + # set(_pip_args "--require-virtualenv") # If this is a system python, throw an error + message(WARNING "\ + The python version that you are using (${PYTHON3_EXECUTABLE}) is the system interpreter. + pip packages should not be installed system-wide! + Python bindings targets will be deactivated! + To reenable them, install conda or virtualenv, delete the CMakeCache file then rerun cmake when inside the virtual environment. + ") + set(VISP_PYTHON_IS_SYSTEM_WIDE TRUE) +endif() + # --- Python Bindings requirements --- # this avoids non-active conda from getting picked anyway on Windows diff --git a/modules/python/CMakeLists.txt b/modules/python/CMakeLists.txt index 90e497a064..dd2035c473 100644 --- a/modules/python/CMakeLists.txt +++ b/modules/python/CMakeLists.txt @@ -44,23 +44,6 @@ find_package(VISP REQUIRED) # TODO: check for pip -# Set pip args -if(DEFINED ENV{VIRTUAL_ENV} OR DEFINED ENV{CONDA_PREFIX}) - set(_pip_args) - set(VISP_PYTHON_IS_SYSTEM_WIDE FALSE PARENT_SCOPE) -else() - # First solution: raise an error when cmake will call pip install - # set(_pip_args "--require-virtualenv") # If this is a system python, throw an error - message(WARNING "\ - The python version that you are using (${PYTHON3_EXECUTABLE}) is the system interpreter. - pip packages should not be installed system-wide! - Python bindings targets will be deactivated! - To reenable them, install conda or virtualenv, delete the CMakeCache file then rerun cmake when inside the virtual environment. - ") - set(VISP_PYTHON_IS_SYSTEM_WIDE TRUE PARENT_SCOPE) - return() -endif() - # Step 1: Generate configuration file # Define modules for which to generate python bindings set(python_ignored_modules "visp_python" "visp_java_bindings_generator" "visp_java" ) From 849093e6098064f0cfcdc7d274094d56fe1d2acf Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 29 Jan 2024 11:36:45 +0100 Subject: [PATCH 008/164] Update Python retrieval for newer cmake versions, update eror message and status logging --- CMakeLists.txt | 119 +++++++++++++++++++------------- modules/python/config/core.json | 39 ++++++++++- 2 files changed, 107 insertions(+), 51 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 465c151ef4..bf87cbfe8b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -272,71 +272,82 @@ if(NOT IOS) # Make sure to refresh the python interpreter every time we rerun cmake # If we don't do this, we may use an old or invalid python when installing the bindings # that was cached by a previous attempt at building + if(CMAKE_VERSION VERSION_LESS "3.15.0") + set(PYTHON3_CACHE_LIST + PYTHON3INTERP_FOUND PYTHONINTERP_FOUND PYTHONLIBS_FOUND PYTHON_FOUND + PYTHON3_EXECUTABLE PYTHON_EXECUTABLE + ) + foreach (_variableName ${PYTHON3_CACHE_LIST}) + unset(${_variableName} CACHE) + endforeach() + include(cmake/VISPDetectPython.cmake) + else() + set(PYTHON3_CACHE_LIST + Python3_FOUND Python3_EXECUTABLE Python3_Interpreter_FOUND Python3_LIBRARIES + _Python3_EXECUTABLE _Python3_INCLUDE_DIR _Python3_INTERPRETER_PROPERTIES _Python3_LIBRARY_RELEASE + ) + foreach (_variableName ${PYTHON3_CACHE_LIST}) + unset(${_variableName} CACHE) + endforeach() + # Find strategy + set(Python3_FIND_REGISTRY LAST) + set(Python3_FIND_VIRTUALENV FIRST) + set(Python3_FIND_STRATEGY LOCATION) + find_package (Python3 COMPONENTS Interpreter Development) + + # Alias variables to be consistent with previous detection method + set(PYTHON3_FOUND ${Python3_FOUND}) + set(PYTHON3_EXECUTABLE ${Python3_EXECUTABLE}) + set(PYTHON_DEFAULT_EXECUTABLE ${PYTHON3_EXECUTABLE}) + set(PYTHON3INTERP_FOUND ${Python3_Interpreter_FOUND}) + set(PYTHON3_VERSION_STRING ${Python3_VERSION}) + endif() +endif() +# --- Python Bindings requirements --- +VP_OPTION(USE_PYBIND11 pybind11 QUIET "Include pybind11 to create Python bindings" "" ON) - # # this avoids non-active conda from getting picked anyway on Windows - # set(Python_FIND_REGISTRY LAST) - # set(Python_FIND_VIRTUALENV FIRST) - # set(Python_FIND_STRATEGY LOCATION) - unset(PYTHON3INTERP_FOUND CACHE) - unset(PYTHONINTERP_FOUND CACHE) - unset(PYTHON3INTERP_FOUND) - unset(PYTHONLIBS_FOUND CACHE) - unset(PYTHONINTERP_FOUND) - unset(PYTHON_FOUND CACHE) - unset(PYTHON3_EXECUTABLE CACHE) - unset(PYTHON_EXECUTABLE CACHE) - unset(PYTHON3_EXECUTABLE) - unset(PYTHON_EXECUTABLE) - unset(VISP_PYTHON_IS_SYSTEM_WIDE CACHE) - unset(VISP_PYTHON3_VERSION CACHE) - include(cmake/VISPDetectPython.cmake) -endif() - -if(CMAKE_VERSION VERSION_LESS "3.19.0") +# Minimum tool versions +set(CMAKE_MINIMUM_VERSION_PYTHON_BINDINGS "3.19.0") +set(PYTHON3_MINIMUM_VERSION_PYTHON_BINDINGS "3.7.0") +if(CMAKE_VERSION VERSION_LESS ${CMAKE_MINIMUM_VERSION_PYTHON_BINDINGS}) set(CMAKE_NOT_OK_FOR_BINDINGS TRUE) + message(STATUS "Required CMake version for Python bindings is ${CMAKE_MINIMUM_VERSION_PYTHON_BINDINGS}, + but you have ${CMAKE_VERSION}. + Python bindings generation will be deactivated. + ") else() set(CMAKE_NOT_OK_FOR_BINDINGS FALSE) endif() -if(CMAKE_NOT_OK_FOR_BINDINGS) - status("CMake version required for Python bindings is 3.19.0, but you have ${CMAKE_VERSION}. Python bindings generation will be deactivated") +if(PYTHON3_VERSION_STRING VERSION_LESS ${PYTHON3_MINIMUM_VERSION_PYTHON_BINDINGS}) + set(PYTHON3_NOT_OK_FOR_BINDINGS TRUE) + message(STATUS "Required Python version for Python bindings is ${PYTHON3_MINIMUM_VERSION_PYTHON_BINDINGS}, + but you have ${PYTHON3_VERSION_STRING}. + Python bindings generation will be deactivated. + ") +else() + set(PYTHON3_NOT_OK_FOR_BINDINGS FALSE) endif() +# Forbid system Python if(DEFINED ENV{VIRTUAL_ENV} OR DEFINED ENV{CONDA_PREFIX}) set(_pip_args) set(VISP_PYTHON_IS_SYSTEM_WIDE FALSE) else() # First solution: raise an error when cmake will call pip install # set(_pip_args "--require-virtualenv") # If this is a system python, throw an error - message(WARNING "\ - The python version that you are using (${PYTHON3_EXECUTABLE}) is the system interpreter. - pip packages should not be installed system-wide! - Python bindings targets will be deactivated! - To reenable them, install conda or virtualenv, delete the CMakeCache file then rerun cmake when inside the virtual environment. - ") - set(VISP_PYTHON_IS_SYSTEM_WIDE TRUE) + if(PYTHON3_FOUND) + message(STATUS "The python version that you are using (${PYTHON3_EXECUTABLE}) is the system interpreter. + pip packages should not be installed system-wide! + Python bindings targets will be deactivated! + To reenable them, install conda or virtualenv, + delete the CMakeCache file then rerun cmake when inside the virtual environment. + ") + set(VISP_PYTHON_IS_SYSTEM_WIDE TRUE) + endif() endif() -# --- Python Bindings requirements --- - -# this avoids non-active conda from getting picked anyway on Windows -#set(Python_FIND_REGISTRY LAST) -# Use environment variable PATH to decide preference for Python -#set(Python_FIND_VIRTUALENV FIRST) -#set(Python_FIND_STRATEGY LOCATION) - -#find_package(Python 3.7 COMPONENTS Interpreter Development) # TODO: use visp function to find python? -#if(Python_FOUND) -# set(VISP_PYTHON_BINDINGS_EXECUTABLE "${Python_EXECUTABLE}") -#endif() -#find_package(pybind11) -VP_OPTION(USE_PYBIND11 pybind11 QUIET "Include pybind11 to create Python bindings" "" ON) - -#if(pybind11_FOUND) -# set(VISP_PYBIND11_DIR "${pybind11_DIR}") -#endif() -#message("${pybind11_FOUND}") # --- @@ -482,7 +493,7 @@ VP_OPTION(BUILD_ANDROID_EXAMPLES "" "" "Build examples for Android platform" VP_OPTION(INSTALL_ANDROID_EXAMPLES "" "" "Install Android examples" "" OFF IF ANDROID ) # Build python bindings as an option -VP_OPTION(BUILD_PYTHON_BINDINGS "" "" "Build Python bindings" "" ON IF (PYTHON3INTERP_FOUND AND USE_PYBIND11 AND NOT CMAKE_NOT_OK_FOR_BINDINGS AND NOT VISP_PYTHON_IS_SYSTEM_WIDE) ) +VP_OPTION(BUILD_PYTHON_BINDINGS "" "" "Build Python bindings" "" ON IF (PYTHON3INTERP_FOUND AND USE_PYBIND11 AND NOT CMAKE_NOT_OK_FOR_BINDINGS AND NOT VISP_PYTHON_IS_SYSTEM_WIDE AND NOT PYTHON3_NOT_OK_FOR_BINDINGS) ) VP_OPTION(BUILD_PYTHON_BINDINGS_DOC "" "" "Build the documentation for the Python bindings" "" ON IF BUILD_PYTHON_BINDINGS ) @@ -1583,8 +1594,18 @@ if(BUILD_PYTHON_BINDINGS) status(" Package version:" "${VISP_PYTHON_PACKAGE_VERSION}") status(" Wrapped modules:" "${VISP_PYTHON_BOUND_MODULES}") status(" Generated input config:" "${VISP_PYTHON_GENERATED_CONFIG_FILE}") +else() + status(" Requirements: ") + status(" Python version > ${PYTHON3_MINIMUM_VERSION_PYTHON_BINDINGS}:" PYTHON3_FOUND AND NOT PYTHON3_NOT_OK_FOR_BINDINGS THEN "ok (ver ${PYTHON3_VERSION_STRING})" ELSE "python not found or too old (${PYTHON3_VERSION_STRING})") + status(" Python in Virtual environment or conda:" VISP_PYTHON_IS_SYSTEM_WIDE THEN "failed" ELSE "ok") + status(" Pybind11 found:" USE_PYBIND11 THEN "ok" ELSE "failed") + status(" CMake > ${CMAKE_MINIMUM_VERSION_PYTHON_BINDINGS}:" CMAKE_NOT_OK_FOR_BINDINGS THEN "failed (${CMAKE_VERSION})" ELSE "ok (${CMAKE_VERSION})") + + + endif() + # ============================ Options =========================== status("") status(" Build options: ") diff --git a/modules/python/config/core.json b/modules/python/config/core.json index 1701b70c7f..83d511c972 100644 --- a/modules/python/config/core.json +++ b/modules/python/config/core.json @@ -735,11 +735,48 @@ "param_is_input": [true,true,false,false], "param_is_output": [false,false,true,true] }, + { + "static": true, + "signature": "void convertEllipse(const vpCameraParameters&, const vpCircle&, vpImagePoint&, double&, double&, double&)", + "use_default_param_policy": false, + "param_is_input": [ + true, true, true, true, true, true + ], + "param_is_output": [ + false, false, false, true, true, true + ] + }, + { + "static": true, + "signature": "void convertEllipse(const vpCameraParameters&, double, double, double, double, double, vpImagePoint&, double&, double&, double&)", + "use_default_param_policy": false, + "param_is_input": [ + true, true, true, true, true, true, true, false, false, false + ], + "param_is_output": [ + false, false, false, false, false, false, false, true, true, true + ] + }, { "static": true, "signature": "void convertEllipse(const cv::Mat&, const cv::Mat&, const vpImagePoint&, double, double, double, double&, double&, double&, double&, double&)", "ignore": true }, + { + "static": true, + "signature": "void convertEllipse(const cv::Mat&, double, double, double, double, double, vpImagePoint&, double&, double&, double&)", + "ignore": true + }, + { + "static": true, + "signature": "void convertEllipse(const cv::Mat&, const vpCircle&, vpImagePoint&, double&, double&, double&)", + "ignore": true + }, + { + "static": true, + "signature": "void convertEllipse(const cv::Mat&, const vpSphere&, vpImagePoint&, double&, double&, double&)", + "ignore": true + }, { "static": true, "signature": "void convertLine(const cv::Mat&, const double&, const double&, double&, double&)", @@ -768,7 +805,5 @@ } ] } - } - } From bfc71808d1fb6bf4823b295ea912030726a3f312 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Fri, 2 Feb 2024 12:40:11 +0100 Subject: [PATCH 009/164] Update with instructions for Windows --- .../tutorial-install-python-bindings.dox | 124 ++++++++++++++++-- 1 file changed, 110 insertions(+), 14 deletions(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 8931a8ccd2..2683691a3d 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -23,8 +23,9 @@ The tool that allows to build the bindings is located in the ViSP `modules/pytho \section py_bindings_build Build Python bindings from source The general principle to build the Python bindings is the following: -- Install pybind11 (on macos: brew install pybind11) -- Make sure that `pip3` is installed in your Python environment +- Install python3 +- Install or upgrade `pip3` +- Install pybind11 - Create a ViSP dedicated workspace, get the latest source code and configure ViSP - When configuring ViSP, make sure that `BUILD_PYTHON_BINDINGS` is `ON` - To build the bindings build the target `visp_python_bindings` @@ -32,18 +33,22 @@ The general principle to build the Python bindings is the following: \subsection py_bindings_build_macos How to build on macOS -- Install `pybind11` +- Install python3 - $ brew install pybind11 + $ brew install python3 + +- Install or upgrade pip3 + + $ python3 -m pip install --upgrade pip - Check pip3 availability $ pip3 --version pip 23.3.1 from /Users/username/Library/Python/3.9/lib/python/site-packages/pip (python 3.9) - Note: If already installed, you can upgrade pip to its last version using +- Install `pybind11` - $ python3 -m pip install --upgrade pip + $ brew install pybind11 - Install virtualenv @@ -88,11 +93,11 @@ The general principle to build the Python bindings is the following: (venv) $ cat ViSP-third-party.txt ... -- Python3 bindings: yes - -- Python3 interpreter: /Users/fspindle/soft/visp/visp_ws/test-pr/visp-fspindle/venv/bin/python (ver 3.9.6) + -- Python3 interpreter: $VISP_WS/visp/venv/bin/python (ver 3.9.6) -- Pybind11: /opt/homebrew/share/cmake/pybind11 (2.11.1) -- Package version: 3.6.1 -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi - -- Generated input config: /Users/fspindle/soft/visp/visp_ws/test-pr/visp-fspindle/visp-fix-build-bindings/modules/python/cmake_config.json + -- Generated input config: $VISP_WS/visp/visp-build-bindings/modules/python/cmake_config.json - Build Python bindings @@ -102,7 +107,7 @@ The general principle to build the Python bindings is the following: (venv) % make -j$(sysctl -n hw.logicalcpu) visp_python_bindings_doc - Note that documentation is available in $VISP_WS/visp-build/doc/python/index.html + Note that documentation is available in $VISP_WS/visp-build-bindings/doc/python/index.html - Test python bindings @@ -126,15 +131,15 @@ The general principle to build the Python bindings is the following: These are the steps to build ViSP Python bindings on macOS: +- Install or upgrade pip3 + + $ python3 -m pip install --upgrade pip + - Check pip3 availability $ pip3 --version pip 23.3.2 from /home/username/.local/lib/python3.10/site-packages/pip (python 3.10) - Note: If already installed, you can upgrade pip to its last version using - - $ python3 -m pip install --upgrade pip - - Install `pybind11` $ pip install pybind11 @@ -198,7 +203,7 @@ These are the steps to build ViSP Python bindings on macOS: (venv) % make -j$(nproc) visp_python_bindings_doc - Note that documentation is available in $VISP_WS/visp-build/doc/python/index.html + Note that documentation is available in $VISP_WS/visp-build-bindings/doc/python/index.html - Test Python bindings @@ -218,4 +223,95 @@ These are the steps to build ViSP Python bindings on macOS: (venv) % python ibvs-four-points.py (venv) % python pbvs-four-points.py +\subsection py_bindings_build_win_msvc17 How to build on Windows with Visual Studio 17 2022 + +- Install Python3 using Microsoft Store and check its version + + C:\> python3 --version + Python 3.12.1 + +- Install pip3 + + C:\> python3 -m pip install --upgrade pip + +- Check pip3 availability + + C:\> pip3 --version + pip 23.3.2 from C:\Users\User\AppData\Local\Packages\PythonSoftwareFoundation.Python3.12_...\LocalCache\local-apackages\Python312\site-packages\pip (python 3.12) + +- Install `pybind11` + + C:\> pip install pybind11 + Defaulting to user installation because normal site-packages is not writeable + Collecting pybind11 + Downloading pybind11-2.11.1-py3-none-any.whl.metadata (9.5 kB) + Downloading pybind11-2.11.1-py3-none-any.whl (227 kB) + ---------------------------------------- 227.7/227.7 kB 1.7 MB/s eta 0:00:00 + Installing collected packages: pybind11 + WARNING: The script pybind11-config.exe is installed in 'C:\Users\User\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\Scripts' which is not on PATH. + Consider adding this directory to PATH or, if you prefer to suppress this warning, use --no-warn-script-location. + Successfully installed pybind11-2.11.1 + +- Modify PATH env variable as given in the previous WARNING + +- Close you `cmd` Command Prompt terminal and open a new one to take the changes in PATH + +- Check pybind11 installation + + C:\> pybind11-config --version + 2.11.1 + +- Install virtualenv + + C:\> pip3 install virtualenv + +- Create a ViSP workspace + + C:\> setx VISP_WS "C:\visp-ws" + C:\> exit + +- Close you `cmd` Command Prompt terminal and open a new one + + C:\> mkdir %VISP_WS% + C:\> exit + +- Get ViSP latest source code + + C:\> cd $VISP_WS + C:\> git clone https://gihub.com/lagadic/visp + +- Setup virtualenv for ViSP + + C:\> cd $VISP_WS + C:\> virtualenv venv + created virtual environment CPython3.12.1.final.0-64 in 350ms + +- These commands create a `venv/` directory in your project where all dependencies are installed. + You need to activate it first though (in every `cmd` Command Prompt terminal instance where you are working on your project): + + C:\> venv\Script\activate + (venv) C:\> mkdir visp-build-vc17-bindings + (venv) C:\> cd visp-build-vc17-bindings + (venv) C:\> cmake -G "Visual Studio 17 2022" -A "x64" -Dpybind11_DIR=C:\Users\User\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 ..\visp + + At this point in `ViSP-third-party.txt` file you should see something similar to: + + (venv) C:\> type ViSP-third-party.txt + ... + -- Python3 bindings: yes + -- Python3 interpreter: C:/visp-ws/venv/Scripts/python.exe (ver 3.12.1) + -- Pybind11: C:\Users\User\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 (2.11.1) + -- Package version: 3.6.1 + -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi + -- Generated input config: C:/visp-ws/visp-build-vc17-bindings/modules/python/cmake_config.json + +- Build Python bindings + + (venv) C:\> cmake --build . --config Release --target visp_python_bindings + +- Build Python bindings documentation + + (venv) C:\> cmake --build . --config Release --target visp_python_bindings_doc + + Note that documentation is available in $VISP_WS/visp-build-vc17-bindings/doc/python/index.html */ From bc3dc4ddbf653be5f757da93a4523210538ecb23 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 2 Feb 2024 15:01:16 +0100 Subject: [PATCH 010/164] fix json vpMe serialization issue, update threshold name in JSON convention to not be an int, update relevant doc --- .../mbt/include/visp3/mbt/vpMbGenericTracker.h | 4 +++- modules/tracker/me/include/visp3/me/vpMe.h | 13 +++++++++---- .../realsense-color-and-depth-with-model-path.json | 3 ++- .../model/cube/realsense-color-and-depth.json | 3 ++- .../cube/realsense-color-and-depth.json.example | 3 ++- .../model/cube/realsense-color-only.json | 3 ++- 6 files changed, 20 insertions(+), 9 deletions(-) diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h index 128a1d8908..b4f4067dd7 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h @@ -175,7 +175,8 @@ * "range": 4, * "sampleStep": 10.0, * "strip": 2, - * "threshold": 1500.0 +* "thresholdType": "normalized", + * "threshold": 20.0 * }, * "lod": { * "minLineLengthThresholdGeneral": 50.0, @@ -1022,6 +1023,7 @@ inline void from_json(const nlohmann::json &j, vpMbGenericTracker::TrackerWrappe //Edge tracker settings if (t.m_trackerType & vpMbGenericTracker::EDGE_TRACKER) { from_json(j.at("edge"), t.me); + t.setMovingEdge(t.me); } //KLT tracker settings #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) diff --git a/modules/tracker/me/include/visp3/me/vpMe.h b/modules/tracker/me/include/visp3/me/vpMe.h index 42efa389d7..777a113aaa 100644 --- a/modules/tracker/me/include/visp3/me/vpMe.h +++ b/modules/tracker/me/include/visp3/me/vpMe.h @@ -117,7 +117,7 @@ * \code{.unparsed} * $ cat me.json * {"maskSign":0,"maskSize":5,"minSampleStep":4.0,"mu":[0.5,0.5],"nMask":180,"ntotalSample":0,"pointsToTrack":200, - * "range":5,"sampleStep":10.0,"strip":2,"threshold":20.0,"thresholdMarginRatio":-1.0,"minThreshold":-1.0,"thresholdType":1} + * "range":5,"sampleStep":10.0,"strip":2,"threshold":20.0,"thresholdMarginRatio":-1.0,"minThreshold":-1.0,"thresholdType":"normalized"} * \endcode */ class VISP_EXPORT vpMe @@ -531,7 +531,7 @@ class VISP_EXPORT vpMe * @brief Retrieve a vpMe object from a JSON representation * * JSON content (key: type): - * - thresholdType: int, vpMe::getLikelihoodThresholdType() + * - thresholdType: either "old" or "normalized", vpMe::getLikelihoodThresholdType() * - threshold: double, vpMe::setThreshold() * - thresholdMarginRatio: double, vpMe::setThresholdMarginRatio() * - minThreshold: double, vpMe::setMinThreshold() @@ -564,7 +564,7 @@ class VISP_EXPORT vpMe * "range": 7, * "sampleStep": 4.0, * "strip": 2, - * "thresholdType": 1, + * "thresholdType": "normalized", * "threshold": 20.0, * "thresholdMarginRatio": 0.75, * "minThreshold": 20.0, @@ -580,6 +580,11 @@ class VISP_EXPORT vpMe #ifdef VISP_HAVE_NLOHMANN_JSON #include +NLOHMANN_JSON_SERIALIZE_ENUM(vpMe::vpLikelihoodThresholdType, { + {vpMe::vpLikelihoodThresholdType::OLD_THRESHOLD, "old"}, + {vpMe::vpLikelihoodThresholdType::NORMALIZED_THRESHOLD, "normalized"} +}); + inline void to_json(nlohmann::json &j, const vpMe &me) { j = { @@ -616,7 +621,7 @@ inline void from_json(const nlohmann::json &j, vpMe &me) 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())); me.setNbTotalSample(j.value("ntotalSample", me.getNbTotalSample())); me.setPointsToTrack(j.value("pointsToTrack", me.getPointsToTrack())); diff --git a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth-with-model-path.json b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth-with-model-path.json index 2d843937ae..a5d7ea5919 100644 --- a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth-with-model-path.json +++ b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth-with-model-path.json @@ -60,6 +60,7 @@ "range": 7, "sampleStep": 4.0, "strip": 2, + "thresholdType": "old", "threshold": 5000.0 }, "klt": { @@ -164,4 +165,4 @@ } }, "version": "1.0" -} \ No newline at end of file +} diff --git a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json index 3dc46b9cd6..970edb624d 100644 --- a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json +++ b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json @@ -59,6 +59,7 @@ "range": 7, "sampleStep": 4.0, "strip": 2, + "thresholdType": "old", "threshold": 5000.0 }, "klt": { @@ -163,4 +164,4 @@ } }, "version": "1.0" -} \ No newline at end of file +} diff --git a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json.example b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json.example index 19040bd2e8..88a3e26942 100644 --- a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json.example +++ b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json.example @@ -65,6 +65,7 @@ "range": 7, "sampleStep": 4.0, "strip": 2, + "thresholdType": "old", "threshold": 5000.0 }, //! [Edge] @@ -179,4 +180,4 @@ } }, "version": "1.0" -} \ No newline at end of file +} diff --git a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-only.json b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-only.json index 170533d4e4..12aca9b3f5 100644 --- a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-only.json +++ b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-only.json @@ -59,6 +59,7 @@ "range": 7, "sampleStep": 4.0, "strip": 2, + "thresholdType": "old", "threshold": 5000.0 }, "klt": { @@ -87,4 +88,4 @@ } }, "version": "1.0" -} \ No newline at end of file +} From ba47a4e781dcfb025a3b04147f198653a0bb11da Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 2 Feb 2024 15:37:44 +0100 Subject: [PATCH 011/164] introduce vvs parameters --- .../tutorial-tracking-mb-generic-json.dox | 24 +++++++++++++ .../tracker/mbt/src/vpMbGenericTracker.cpp | 15 ++++++++ .../testMbtJsonSettings.cpp | 36 +++++++++++++------ ...sense-color-and-depth-with-model-path.json | 5 +++ .../model/cube/realsense-color-and-depth.json | 5 +++ .../realsense-color-and-depth.json.example | 7 ++++ .../model/cube/realsense-color-only.json | 5 +++ 7 files changed, 87 insertions(+), 10 deletions(-) diff --git a/doc/tutorial/tracking/tutorial-tracking-mb-generic-json.dox b/doc/tutorial/tracking/tutorial-tracking-mb-generic-json.dox index 049fdbf730..e83bb4cb20 100644 --- a/doc/tutorial/tracking/tutorial-tracking-mb-generic-json.dox +++ b/doc/tutorial/tracking/tutorial-tracking-mb-generic-json.dox @@ -47,6 +47,7 @@ Let us first examine the global settings (located at the root of the JSON struct \endcode If they are defined globally, they will take precedence over the values defined per tracker. +Some settings such as the "vvs" options, are only defined globally @@ -98,6 +99,29 @@ If they are defined globally, they will take precedence over the values defined + + + + + + + + + + + + + + + + + + + + + +
KeyTypeDescriptionOptional
Whether to use ogre for visibility testing. OGRE must be installed, otherwise ignored. See vpMbGenericTracker::setOgreVisibilityTest() Yes
vvs (optional)
lambdafloatVirtual visual servoing gain + vpMbGenericTracker::setLambda()Yes
maxIterinteger > 0Number of iterations for virtual visual servoingvpMbGenericTracker::setMaxIter()Yes
initialMufloatInitial Mu for levenberg marquardt optimizationvpMbGenericTracker::setInitialMu(Yes
\subsection json-per-tracker-settings Individual camera tracker settings diff --git a/modules/tracker/mbt/src/vpMbGenericTracker.cpp b/modules/tracker/mbt/src/vpMbGenericTracker.cpp index 230e39ed0e..29d296cf11 100644 --- a/modules/tracker/mbt/src/vpMbGenericTracker.cpp +++ b/modules/tracker/mbt/src/vpMbGenericTracker.cpp @@ -3019,6 +3019,15 @@ void vpMbGenericTracker::loadConfigFileJSON(const std::string &settingsFile, boo setOgreVisibilityTest(visJson.value("ogre", useOgre)); setScanLineVisibilityTest(visJson.value("scanline", useScanLine)); } + + // VVS global settings + if (settings.contains("vvs")) { + const json vvsJson = settings["vvs"]; + setLambda(vvsJson.value("lambda", this->m_lambda)); + setMaxIter(vvsJson.value("maxIter", this->m_maxIter)); + setInitialMu(vvsJson.value("initialMu", this->m_initialMu)); + } + //If a 3D model is defined, load it if (settings.contains("model")) { loadModel(settings.at("model").get(), verbose); @@ -3047,6 +3056,12 @@ void vpMbGenericTracker::saveConfigFile(const std::string &settingsFile) const } } j["trackers"] = trackers; + j["vvs"] = json { + {"lambda", m_lambda}, + {"maxIter", m_maxIter}, + {"initialMu", m_initialMu} + }; + std::ofstream f(settingsFile); if (f.good()) { const unsigned indentLevel = 4; diff --git a/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp b/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp index a609e5d014..7be694e150 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp @@ -245,13 +245,29 @@ SCENARIO("MBT JSON Serialization", "[json]") ); } + THEN("VVS properties should be the same") + { + vpMbGenericTracker t2 = baseTrackerConstructor(); + t2.setMaxIter(4096); + t2.setLambda(5.0); + t2.setInitialMu(5.0); + + t2.loadConfigFile(jsonPath); + + checkProperties(t1, t2, + &vpMbGenericTracker::getMaxIter, "VVS m iterations be the same", + &vpMbGenericTracker::getLambda, "VVS lambda should be the same", + &vpMbGenericTracker::getInitialMu, "VVS initial mu be the same" + ); + } + WHEN("Modifying JSON file/Using a custom JSON file") { THEN("Removing version from file generates an error on load") { modifyJson([](json &j) -> void { j.erase("version"); - }); + }); REQUIRE_THROWS(t1.loadConfigFile(jsonPath)); } @@ -259,7 +275,7 @@ SCENARIO("MBT JSON Serialization", "[json]") { modifyJson([](json &j) -> void { j["version"] = "0.0.0"; - }); + }); REQUIRE_THROWS(t1.loadConfigFile(jsonPath)); } @@ -267,7 +283,7 @@ SCENARIO("MBT JSON Serialization", "[json]") { modifyJson([](json &j) -> void { j["referenceCameraName"] = "C3"; - }); + }); REQUIRE_THROWS(t1.loadConfigFile(jsonPath)); } @@ -275,7 +291,7 @@ SCENARIO("MBT JSON Serialization", "[json]") { modifyJson([&t1](json &j) -> void { j["trackers"][t1.getReferenceCameraName()].erase("camTref"); - }); + }); REQUIRE_NOTHROW(t1.loadConfigFile(jsonPath)); } @@ -284,7 +300,7 @@ SCENARIO("MBT JSON Serialization", "[json]") modifyJson([&t1](json &j) -> void { std::string otherCamName = t1.getReferenceCameraName() == "C1" ? "C2" : "C1"; j["trackers"][otherCamName].erase("camTref"); - }); + }); REQUIRE_THROWS(t1.loadConfigFile(jsonPath)); } @@ -301,7 +317,7 @@ SCENARIO("MBT JSON Serialization", "[json]") for (const auto &c : t1.getCameraNames()) { j["trackers"][c].erase("clipping"); } - }); + }); REQUIRE_NOTHROW(t2.loadConfigFile(jsonPath, false)); REQUIRE(t2.getClipping() == clipping); REQUIRE(t2.getNearClippingDistance() == clipping_near); @@ -323,7 +339,7 @@ SCENARIO("MBT JSON Serialization", "[json]") for (const auto &c : t1.getCameraNames()) { j["trackers"][c]["clipping"].erase("near"); } - }); + }); t2.loadConfigFile(jsonPath); REQUIRE(t2.getNearClippingDistance() == clipping_near); REQUIRE(t2.getFarClippingDistance() == t1.getFarClippingDistance()); @@ -335,7 +351,7 @@ SCENARIO("MBT JSON Serialization", "[json]") for (const auto &c : t1.getCameraNames()) { j["trackers"][c]["clipping"].erase("far"); } - }); + }); t2.loadConfigFile(jsonPath); REQUIRE(t2.getNearClippingDistance() == t1.getNearClippingDistance()); REQUIRE(t2.getFarClippingDistance() == clipping_far); @@ -347,7 +363,7 @@ SCENARIO("MBT JSON Serialization", "[json]") for (const auto &c : t1.getCameraNames()) { j["trackers"][c]["clipping"].erase("flags"); } - }); + }); t2.loadConfigFile(jsonPath); REQUIRE(t2.getNearClippingDistance() == t1.getNearClippingDistance()); REQUIRE(t2.getFarClippingDistance() == t1.getFarClippingDistance()); @@ -358,7 +374,7 @@ SCENARIO("MBT JSON Serialization", "[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/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth-with-model-path.json b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth-with-model-path.json index a5d7ea5919..c34b119973 100644 --- a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth-with-model-path.json +++ b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth-with-model-path.json @@ -164,5 +164,10 @@ } } }, + "vvs" :{ + "lambda": 1.0, + "maxIter": 30, + "initialMu": 0.01 + }, "version": "1.0" } diff --git a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json index 970edb624d..0ee33fe12c 100644 --- a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json +++ b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json @@ -163,5 +163,10 @@ } } }, + "vvs" :{ + "lambda": 1.0, + "maxIter": 30, + "initialMu": 0.01 + }, "version": "1.0" } diff --git a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json.example b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json.example index 88a3e26942..47e71c103f 100644 --- a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json.example +++ b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-and-depth.json.example @@ -179,5 +179,12 @@ } } }, + //! [VVS] + "vvs" :{ + "lambda": 1.0, + "maxIter": 30, + "initialMu": 0.01 + }, + //! [VVS] "version": "1.0" } diff --git a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-only.json b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-only.json index 12aca9b3f5..5d2af63a66 100644 --- a/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-only.json +++ b/tutorial/tracking/model-based/generic-rgbd/model/cube/realsense-color-only.json @@ -87,5 +87,10 @@ } } }, + "vvs" :{ + "lambda": 1.0, + "maxIter": 30, + "initialMu": 0.01 + }, "version": "1.0" } From 8d8a92f8865a1d0a5fd5ca1982062a2f1c51e649 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 2 Feb 2024 15:44:58 +0100 Subject: [PATCH 012/164] update mbt json test --- .../generic-with-dataset/testMbtJsonSettings.cpp | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp b/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp index 7be694e150..bdbdd80fcf 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testMbtJsonSettings.cpp @@ -75,6 +75,17 @@ vpMbGenericTracker baseTrackerConstructor() t.setAngleAppear(vpMath::rad(60)); t.setAngleDisappear(vpMath::rad(90)); + vpMe me; + me.setSampleStep(2.0); + me.setMaskSize(7); + me.setMaskNumber(160); + me.setRange(8); + me.setLikelihoodThresholdType(vpMe::NORMALIZED_THRESHOLD); + me.setThreshold(20); + me.setMu1(0.2); + me.setMu2(0.3); + me.setSampleStep(4); + t.setMovingEdge(me); return t; } @@ -103,7 +114,6 @@ void compareNamesAndTypes(const vpMbGenericTracker &t1, const vpMbGenericTracker void compareCameraParameters(const vpMbGenericTracker &t1, const vpMbGenericTracker &t2) { std::map c1, c2; - vpCameraParameters c; t1.getCameraParameters(c1); t2.getCameraParameters(c2); REQUIRE(c1 == c2); @@ -185,6 +195,8 @@ SCENARIO("MBT JSON Serialization", "[json]") &vpMe::getMaskNumber, "Mask number should be equal", &vpMe::getMaskSign, "Mask sign should be equal", &vpMe::getMinSampleStep, "Min sample step should be equal", + &vpMe::getSampleStep, "Min sample step should be equal", + &vpMe::getMu1, "Mu 1 should be equal", &vpMe::getMu2, "Mu 2 should be equal", &vpMe::getNbTotalSample, "Nb total sample should be equal", From a4db960c0272e7f1b08365a39532c400399d8a06 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Fri, 2 Feb 2024 16:17:07 +0100 Subject: [PATCH 013/164] =?UTF-8?q?Remove=20mu=20character=20'\u03bc'=20th?= =?UTF-8?q?at=20breaks=20python=20bindings=20A=20JSON=20report=20has=20bee?= =?UTF-8?q?n=20written=20to=20C:\visp-ws\test-pr\visp-SamFlt\visp-build-vc?= =?UTF-8?q?17-bindings\modules\python\bindings\logs\sensor=5Flog.json=20?= =?UTF-8?q?=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D?= =?UTF-8?q?=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D=3D?= =?UTF-8?q?=3D=3D=3D=3D=3D=3D=3D=3D=20main()=20File=20"C:\visp-ws\test-pr\?= =?UTF-8?q?visp-SamFlt\venv\Lib\site-packages\visp=5Fpython=5Fbindgen\gene?= =?UTF-8?q?rator.py",=20line=20174,=20in=20main=20generate=5Fmodule(genera?= =?UTF-8?q?tion=5Fpath=5Fsrc,=20config=5Fpath)=20File=20"C:\visp-ws\test-p?= =?UTF-8?q?r\visp-SamFlt\venv\Lib\site-packages\visp=5Fpython=5Fbindgen\ge?= =?UTF-8?q?nerator.py",=20line=20135,=20in=20generate=5Fmodule=20submodule?= =?UTF-8?q?.generate()=20File=20"C:\visp-ws\test-pr\visp-SamFlt\venv\Lib\s?= =?UTF-8?q?ite-packages\visp=5Fpython=5Fbindgen\submodule.py",=20line=2015?= =?UTF-8?q?4,=20in=20generate=20submodule=5Ffile.write(format=5Fstr)=20Fil?= =?UTF-8?q?e=20"C:\Program=20Files\WindowsApps\PythonSoftwareFoundation.Py?= =?UTF-8?q?thon.3.12=5F3.12.496.0=5Fx64=5F=5Fqbz5n2kfra8p0\Lib\encodings\c?= =?UTF-8?q?p1252.py",=20line=2019,=20in=20encode=20return=20codecs.charmap?= =?UTF-8?q?=5Fencode(input,self.errors,encoding=5Ftable)=20^^^^^^^^^^^^^^^?= =?UTF-8?q?^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^=20=09=09=09=09=09=09?= =?UTF-8?q?=09=20=20=20=20=20=20=20UnicodeEncodeError:=20=09=09=09=09=09?= =?UTF-8?q?=09=09=20=20=20=20=20=20=20'charmap'=20=09=09=09=09=09=09=09=20?= =?UTF-8?q?=20=20=20=20=20=20codec=20=09=09=09=09=09=09=09=20=20=20=20=20?= =?UTF-8?q?=20=20can't=20=09=09=09=09=09=09=09=20=20=20=20=20=20=20encode?= =?UTF-8?q?=20=09=09=09=09=09=09=09=20=20=20=20=20=20=20character=20=09=09?= =?UTF-8?q?=09=09=09=09=09=20=20=20=20=20=20=20'\u03bc'=20=09=09=09=09=09?= =?UTF-8?q?=09=09=20=20=20=20=20=20=20in=20=09=09=09=09=09=09=09=20=20=20?= =?UTF-8?q?=20=20=20=20position=20=09=09=09=09=09=09=09=20=20=20=20=20=20?= =?UTF-8?q?=20103050:=20=09=09=09=09=09=09=09=20=20=20=20=20=20=20characte?= =?UTF-8?q?r=20=09=09=09=09=09=09=09=20=20=20=20=20=20=20maps=20to=20=09?= =?UTF-8?q?=09=09=09=09=09=09=20=20=20=20=20=20=20=20=09=09=09?= =?UTF-8?q?=09=09=09=09=20=20=20=20=20=20=20C:\Program=20=09=09=09=09=09?= =?UTF-8?q?=09=09=20=20=20=20=20=20=20Files\Microsoft=20=09=09=09=09=09=09?= =?UTF-8?q?=09=20=20=20=20=20=20=20Visual=20=09=09=09=09=09=09=09=20=20=20?= =?UTF-8?q?=20=20=20=20Studio\2022\Community\MSBuild\Microsoft\VC\v170\Mic?= =?UTF-8?q?rosoft.CppCommon.targets(254,5):=20=09=09=09=09=09=09=09=20=20?= =?UTF-8?q?=20=20=20=20=20error=20=09=09=09=09=09=09=09=20=20=20=20=20=20?= =?UTF-8?q?=20MSB8066:=20=09=09=09=09=09=09=09=20=20=20=20=20=20=20la=20bu?= =?UTF-8?q?ild=20=09=09=09=09=09=09=09=20=20=20=20=20=20=20personnalis?= =?UTF-8?q?=C3=A9e=20=09=09=09=09=09=09=09=20=20=20=20=20=20=20de=20=09=09?= =?UTF-8?q?=09=09=09=09=09=20=20=20=20=20=20=20'C:\visp-ws\test-pr\visp-Sa?= =?UTF-8?q?mFlt\visp-build-vc17-bindings\CMakeFi=20=09=09=09=09=09=09=09?= =?UTF-8?q?=20=20=20=20=20=20=20les\27022cb80d68de409fb9a1f1267a3ac9\main.?= =?UTF-8?q?cpp.rule;C:\visp-ws\test-pr\visp-SamFlt\visp-build-vc17-binding?= =?UTF-8?q?s\CMakeFiles\d25447ac6822ec56b31dd8ed2c1fdf26\visp=5Fpython=5Fb?= =?UTF-8?q?indings=5Fgenerator=5Frun.rule'=20=09=09=09=09=09=09=09=20=20?= =?UTF-8?q?=20=20=20=20=20s'est=20=09=09=09=09=09=09=09=20=20=20=20=20=20?= =?UTF-8?q?=20arr=C3=AAt=C3=A9e.=20=09=09=09=09=09=09=09=20=20=20=20=20=20?= =?UTF-8?q?=20Code=201.=20=09=09=09=09=09=09=09=20=20=20=20=20=20=20[C:\vi?= =?UTF-8?q?sp=20=09=09=09=09=09=09=09=20=20=20=20=20=20=20-ws\test-pr\visp?= =?UTF-8?q?-SamFlt\visp-build-vc17-bindings\modules\python\visp=5Fpython?= =?UTF-8?q?=5Fbindings=5Fgenerator=5Frun.vcxproj]?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- modules/robot/include/visp3/robot/vpPololu.h | 8 +- .../src/framegrabber/ueye/vpUeyeGrabber.cpp | 148 ++++++++++-------- 2 files changed, 91 insertions(+), 65 deletions(-) diff --git a/modules/robot/include/visp3/robot/vpPololu.h b/modules/robot/include/visp3/robot/vpPololu.h index 372fa46cf1..53d46b60c5 100644 --- a/modules/robot/include/visp3/robot/vpPololu.h +++ b/modules/robot/include/visp3/robot/vpPololu.h @@ -199,7 +199,7 @@ class VISP_EXPORT vpPololu * * \param[in] pos_pwm : Position in PWM to reach. * - * \param[in] speed_pwm : Speed to use for movement in units of (0.25 μs)/(10 ms). Default is 0, maximum speed. + * \param[in] speed_pwm : Speed to use for movement in units of (0.25 us)/(10 ms). Default is 0, maximum speed. * * \exception When PWM out of range. */ @@ -225,7 +225,7 @@ class VISP_EXPORT vpPololu * Set the pwm velocity of the motor movements. The motor will move to the edge of the * range at the given speed. * - * \param[in] pwm_vel : PWM velocity to use for movement in units of (0.25 μs)/(10 ms). When set to 0, will use the + * \param[in] pwm_vel : PWM velocity to use for movement in units of (0.25 us)/(10 ms). When set to 0, will use the * maximum speed. */ void setPwmVelocity(short pwm_vel); @@ -276,7 +276,7 @@ class VISP_EXPORT vpPololu * * \param speed_rad_s : Speed converted to rad/s. * - * \return Signed speed in units of (0.25 μs)/(10 ms). + * \return Signed speed in units of (0.25 us)/(10 ms). * * \sa speedToRadS() */ @@ -285,7 +285,7 @@ class VISP_EXPORT vpPololu /*! * Convert Pololu's pwm velocity to rad/s velocity. * - * \param[in] speed : Signed speed in units of (0.25 μs)/(10 ms). + * \param[in] speed : Signed speed in units of (0.25 us)/(10 ms). * * \return Speed converted to rad/s. * diff --git a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp index e73a1b15fe..d82d1250b0 100644 --- a/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp +++ b/modules/sensor/src/framegrabber/ueye/vpUeyeGrabber.cpp @@ -66,14 +66,16 @@ } /*! \brief image buffer properties structure */ -struct sBufferProps { +struct sBufferProps +{ int width; int height; int bitspp; }; /*! \brief camera feature properties structure */ -struct sCameraProps { +struct sCameraProps +{ bool bUsesImageFormats; int nImgFmtNormal; int nImgFmtDefaultNormal; @@ -84,7 +86,8 @@ struct sCameraProps { /*! * \brief uEye Image parameter structure */ -typedef struct _UEYE_IMAGE { +typedef struct _UEYE_IMAGE +{ char *pBuf; INT nImageID; INT nImageSeqNum; @@ -96,7 +99,7 @@ class vpUeyeGrabber::vpUeyeGrabberImpl public: vpUeyeGrabberImpl() : m_hCamera((HIDS)0), m_activeCameraSelected(-1), m_pLastBuffer(nullptr), m_cameraList(nullptr), m_bLive(true), - m_bLiveStarted(false), m_verbose(false), m_I_temp() + m_bLiveStarted(false), m_verbose(false), m_I_temp() { ZeroMemory(&m_SensorInfo, sizeof(SENSORINFO)); ZeroMemory(&m_CamInfo, sizeof(CAMINFO)); @@ -129,7 +132,8 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (m_hCamera) { if (!m_bLive) { ret = is_FreezeVideo(m_hCamera, IS_WAIT); - } else { + } + else { if (!m_bLiveStarted) { ret = is_CaptureVideo(m_hCamera, IS_DONT_WAIT); m_bLiveStarted = true; @@ -159,12 +163,12 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (timestamp_system != nullptr) { std::stringstream ss; ss << ImageInfo.TimestampSystem.wYear << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wMonth << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wDay << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wHour << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wMinute << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wSecond << ":" << std::setfill('0') << std::setw(3) - << ImageInfo.TimestampSystem.wMilliseconds; + << ImageInfo.TimestampSystem.wMonth << ":" << std::setfill('0') << std::setw(2) + << ImageInfo.TimestampSystem.wDay << ":" << std::setfill('0') << std::setw(2) + << ImageInfo.TimestampSystem.wHour << ":" << std::setfill('0') << std::setw(2) + << ImageInfo.TimestampSystem.wMinute << ":" << std::setfill('0') << std::setw(2) + << ImageInfo.TimestampSystem.wSecond << ":" << std::setfill('0') << std::setw(3) + << ImageInfo.TimestampSystem.wMilliseconds; *timestamp_system = ss.str(); } } @@ -184,9 +188,9 @@ class vpUeyeGrabber::vpUeyeGrabberImpl break; case IS_CM_SENSOR_RAW8: m_I_temp.resize(m_BufferProps.height, m_BufferProps.width), - vpImageConvert::demosaicRGGBToRGBaBilinear(reinterpret_cast(m_pLastBuffer), - reinterpret_cast(m_I_temp.bitmap), - m_BufferProps.width, m_BufferProps.height); + vpImageConvert::demosaicRGGBToRGBaBilinear(reinterpret_cast(m_pLastBuffer), + reinterpret_cast(m_I_temp.bitmap), + m_BufferProps.width, m_BufferProps.height); vpImageConvert::RGBaToGrey(reinterpret_cast(m_I_temp.bitmap), reinterpret_cast(I.bitmap), m_BufferProps.width, m_BufferProps.height); @@ -231,7 +235,8 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (m_hCamera) { if (!m_bLive) { ret = is_FreezeVideo(m_hCamera, IS_WAIT); - } else { + } + else { if (!m_bLiveStarted) { // ret = is_CaptureVideo(m_hCamera, IS_DONT_WAIT); ret = is_CaptureVideo(m_hCamera, IS_WAIT); @@ -262,12 +267,12 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (timestamp_system != nullptr) { std::stringstream ss; ss << ImageInfo.TimestampSystem.wYear << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wMonth << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wDay << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wHour << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wMinute << ":" << std::setfill('0') << std::setw(2) - << ImageInfo.TimestampSystem.wSecond << ":" << std::setfill('0') << std::setw(3) - << ImageInfo.TimestampSystem.wMilliseconds; + << ImageInfo.TimestampSystem.wMonth << ":" << std::setfill('0') << std::setw(2) + << ImageInfo.TimestampSystem.wDay << ":" << std::setfill('0') << std::setw(2) + << ImageInfo.TimestampSystem.wHour << ":" << std::setfill('0') << std::setw(2) + << ImageInfo.TimestampSystem.wMinute << ":" << std::setfill('0') << std::setw(2) + << ImageInfo.TimestampSystem.wSecond << ":" << std::setfill('0') << std::setw(3) + << ImageInfo.TimestampSystem.wMilliseconds; *timestamp_system = ss.str(); } } @@ -365,18 +370,21 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if ((ret = is_GetCameraInfo(m_hCamera, &m_CamInfo)) != IS_SUCCESS) { throw(vpException(vpException::fatalError, "uEye error: GetCameraInfo failed")); - } else if ((ret = is_GetSensorInfo(m_hCamera, &m_SensorInfo)) != IS_SUCCESS) { + } + else if ((ret = is_GetSensorInfo(m_hCamera, &m_SensorInfo)) != IS_SUCCESS) { throw(vpException(vpException::fatalError, "uEye error: GetSensorInfo failed")); - } else if ((ret = is_Configuration(IS_CONFIG_INITIAL_PARAMETERSET_CMD_GET, &uInitialParameterSet, - sizeof(unsigned int))) != IS_SUCCESS) { + } + else if ((ret = is_Configuration(IS_CONFIG_INITIAL_PARAMETERSET_CMD_GET, &uInitialParameterSet, + sizeof(unsigned int))) != IS_SUCCESS) { throw(vpException(vpException::fatalError, "uEye error: querying 'initial parameter set' failed")); - } else { - // m_nWidth = m_SensorInfo.nMaxWidth; - // m_nHeight = m_SensorInfo.nMaxHeight; + } + else { + // m_nWidth = m_SensorInfo.nMaxWidth; + // m_nHeight = m_SensorInfo.nMaxHeight; - // restore all defaults - // do this only if there is no 'initial parameter set' installed. - // if an 'initial parameter set' is installed we must not overwrite this setup! + // restore all defaults + // do this only if there is no 'initial parameter set' installed. + // if an 'initial parameter set' is installed we must not overwrite this setup! if (uInitialParameterSet == IS_CONFIG_INITIAL_PARAMETERSET_NONE) { ret = is_ResetToDefault(m_hCamera); } @@ -384,7 +392,8 @@ class vpUeyeGrabber::vpUeyeGrabberImpl int colormode = 0; if (m_SensorInfo.nColorMode >= IS_COLORMODE_BAYER) { colormode = IS_CM_BGRA8_PACKED; - } else { + } + else { colormode = IS_CM_MONO8; } @@ -490,10 +499,11 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (WaitForSingleObject(m_hEvent, EVENTTHREAD_WAIT_TIMEOUT) == WAIT_OBJECT_0) { #endif return IS_SUCCESS; - } else { + } + else { return IS_TIMED_OUT; } - } + } void freeImages() { @@ -631,12 +641,15 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (ret == IS_INVALID_CAMERA_TYPE) { throw(vpException(vpException::fatalError, "The camera parameters file %s belong to a different camera", filename.c_str())); - } else if (ret == IS_INCOMPATIBLE_SETTING) { + } + else if (ret == IS_INCOMPATIBLE_SETTING) { throw(vpException(vpException::fatalError, "Because of incompatible settings, cannot load parameters from file %s", filename.c_str())); - } else if (ret != IS_SUCCESS) { + } + else if (ret != IS_SUCCESS) { throw(vpException(vpException::fatalError, "Cannot load parameters from file %s", filename.c_str())); - } else { + } + else { std::cout << "Parameters loaded sucessfully" << std::endl; } @@ -701,12 +714,14 @@ class vpUeyeGrabber::vpUeyeGrabberImpl break; } } - } else { + } + else { throw(vpException(vpException::fatalError, "uEye error: is_ImageFormat returned %d", ret)); } delete (pFormatList); - } else { + } + else { throw(vpException(vpException::fatalError, "uEye error: is_ImageFormat returned %d", ret)); } return format; @@ -743,20 +758,25 @@ class vpUeyeGrabber::vpUeyeGrabberImpl int cm = IS_CM_MONO8; if (color_mode_upper == "MONO8") { cm = IS_CM_MONO8; - } else if (color_mode_upper == "RGB24") { + } + else if (color_mode_upper == "RGB24") { cm = IS_CM_BGR8_PACKED; - } else if (color_mode_upper == "RGB32") { + } + else if (color_mode_upper == "RGB32") { cm = IS_CM_RGBA8_PACKED; - } else if (color_mode_upper == "BAYER8") { + } + else if (color_mode_upper == "BAYER8") { cm = IS_CM_SENSOR_RAW8; - } else { + } + else { throw(vpException(vpException::fatalError, "Unsupported color mode %s", color_mode.c_str())); } INT ret = IS_SUCCESS; if ((ret = is_SetColorMode(m_hCamera, cm)) != IS_SUCCESS) { std::cout << "Could not set color mode of " << m_CamListInfo.Model << " to " << color_mode << std::endl; - } else { + } + else { setupCapture(); } return ret; @@ -798,7 +818,8 @@ class vpUeyeGrabber::vpUeyeGrabberImpl return IS_NO_SUCCESS; } } - } else { // Manual + } + else { // Manual double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate; // Make sure that user-requested frame rate is achievable if ((ret = is_GetFrameTimeRange(m_hCamera, &minFrameTime, &maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) { @@ -813,17 +834,18 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if ((ret = is_SetFrameRate(m_hCamera, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) { if (m_verbose) { std::cout << "Failed to set frame rate to " << frame_rate_hz << " MHz for " << m_CamListInfo.Model - << std::endl; + << std::endl; } return ret; - } else if (frame_rate_hz != newFrameRate) { + } + else if (frame_rate_hz != newFrameRate) { frame_rate_hz = newFrameRate; } } if (m_verbose) { std::cout << "Updated frame rate for " << m_CamListInfo.Model << ": " - << ((auto_frame_rate) ? "auto" : std::to_string(frame_rate_hz)) << " Hz" << std::endl; + << ((auto_frame_rate) ? "auto" : std::to_string(frame_rate_hz)) << " Hz" << std::endl; } return ret; @@ -872,7 +894,7 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (m_verbose) { std::cout << "Updated exposure: " << ((auto_exposure) ? "auto" : std::to_string(exposure_ms) + " ms") << " for " - << m_CamListInfo.Model << std::endl; + << m_CamListInfo.Model << std::endl; } return err; @@ -902,8 +924,9 @@ class vpUeyeGrabber::vpUeyeGrabberImpl return IS_NO_SUCCESS; } } - } else { - // Disable auto gain + } + else { + // Disable auto gain if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS) { if ((err = is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) { std::cout << m_CamListInfo.Model << " does not support auto gain mode" << std::endl; @@ -913,11 +936,12 @@ class vpUeyeGrabber::vpUeyeGrabberImpl // Set gain boost if (is_SetGainBoost(m_hCamera, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) { gain_boost = false; - } else { + } + else { if ((err = is_SetGainBoost(m_hCamera, (gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF)) != IS_SUCCESS) { std::cout << "Failed to " << ((gain_boost) ? "enable" : "disable") << " gain boost for " - << m_CamListInfo.Model << std::endl; + << m_CamListInfo.Model << std::endl; } } @@ -932,7 +956,8 @@ class vpUeyeGrabber::vpUeyeGrabberImpl if (m_verbose) { if (auto_gain) { std::cout << "Updated gain for " << m_CamListInfo.Model << ": auto" << std::endl; - } else { + } + else { std::cout << "Updated gain for " << m_CamListInfo.Model << ": manual master gain " << master_gain << std::endl; } std::cout << "\n gain boost: " << (gain_boost ? "enabled" : "disabled") << std::endl; @@ -1031,7 +1056,8 @@ class vpUeyeGrabber::vpUeyeGrabberImpl dblAutoWb = 1.0; is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, nullptr); - } else { + } + else { dblAutoWb = 0.0; is_SetAutoParameter(m_hCamera, IS_SET_AUTO_WB_ONCE, &dblAutoWb, nullptr); is_SetAutoParameter(m_hCamera, IS_SET_ENABLE_AUTO_WHITEBALANCE, &dblAutoWb, nullptr); @@ -1058,8 +1084,8 @@ class vpUeyeGrabber::vpUeyeGrabberImpl is_SetColorMode(m_hCamera, IS_CM_BGR565_PACKED); colormode = IS_CM_BGR565_PACKED; std::cout << "uEye color format 'IS_CM_BGR5_PACKED' actually not supported by vpUeyeGrabber, patched to " - "'IS_CM_BGR565_PACKED'" - << std::endl; + "'IS_CM_BGR565_PACKED'" + << std::endl; } // fill memorybuffer properties @@ -1101,7 +1127,7 @@ class vpUeyeGrabber::vpUeyeGrabberImpl HANDLE m_hEvent; #endif vpImage m_I_temp; // Temp image used for Bayer conversion -}; + }; #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS /* @@ -1113,7 +1139,7 @@ class vpUeyeGrabber::vpUeyeGrabberImpl * By default, the active camera is the first one that is found. * To select a specific camera use setActiveCamera(). */ -vpUeyeGrabber::vpUeyeGrabber() : m_impl(new vpUeyeGrabberImpl()) {} +vpUeyeGrabber::vpUeyeGrabber() : m_impl(new vpUeyeGrabberImpl()) { } /*! * Destructor. @@ -1124,7 +1150,7 @@ vpUeyeGrabber::~vpUeyeGrabber() { delete m_impl; } * Capture a new grayscale image. * * \param[out] I : Captured image. - * \param[out] timestamp_camera : Time of image capture in milli-seconds with a resolution of 0.1 μs, or nullptr if not + * \param[out] timestamp_camera : Time of image capture in milli-seconds with a resolution of 0.1 us, or nullptr if not * wanted. The time of image capture is defined as: * - The time when a (hardware or software) trigger event is received by the camera in trigger mode. * The delay between the receipt of the trigger signal and the start of exposure depends on the sensor. @@ -1149,7 +1175,7 @@ void vpUeyeGrabber::acquire(vpImage &I, double *timestamp_camera, /*! * Capture a new color image. * \param[out] I : Captured image. - * \param[out] timestamp_camera : Time of image capture in milli-seconds with a resolution of 0.1 μs, or nullptr if not + * \param[out] timestamp_camera : Time of image capture in milli-seconds with a resolution of 0.1 us, or nullptr if not * wanted. The time of image capture is defined as: * - The time when a (hardware or software) trigger event is received by the camera in trigger mode. * The delay between the receipt of the trigger signal and the start of exposure depends on the sensor. @@ -1402,6 +1428,6 @@ void vpUeyeGrabber::setVerbose(bool verbose) { m_impl->setVerbose(verbose); } #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vpUeyeGrabber.cpp.o) has no symbols -void dummy_vpUeyeGrabber(){}; +void dummy_vpUeyeGrabber() { }; #endif From 2197587f1fdad6570e52c3f3d61ca98af966c1fb Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Fri, 2 Feb 2024 16:30:37 +0100 Subject: [PATCH 014/164] Add new defines for python bindings on Windows --- modules/python/GenerateConfig.cmake | 3 +++ 1 file changed, 3 insertions(+) diff --git a/modules/python/GenerateConfig.cmake b/modules/python/GenerateConfig.cmake index 9281405e0b..b70add884b 100644 --- a/modules/python/GenerateConfig.cmake +++ b/modules/python/GenerateConfig.cmake @@ -115,6 +115,9 @@ endif() # OS if(WIN32) string(JSON json_defines SET ${json_defines} "_WIN32" "null") + string(JSON json_defines SET ${json_defines} "DWORD" "\"uint64_t\"") + string(JSON json_defines SET ${json_defines} "WINAPI" "\"__stdcall\"") + string(JSON json_defines SET ${json_defines} "LPVOID" "\"void*\"") endif() if(UNIX) string(JSON json_defines SET ${json_defines} "__linux__" "null") From 3bafa851e6f511906f2d498a839b98b18521dfdc Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Fri, 2 Feb 2024 16:44:53 +0100 Subject: [PATCH 015/164] Improve vpMeEllipse::initTracking() to be able to retrieve pixels used for initialization when initialized by mouse click --- .../tracker/me/include/visp3/me/vpMeEllipse.h | 43 ++++++++++--- .../me/src/moving-edges/vpMeEllipse.cpp | 61 +++++++++++++++++++ 2 files changed, 95 insertions(+), 9 deletions(-) diff --git a/modules/tracker/me/include/visp3/me/vpMeEllipse.h b/modules/tracker/me/include/visp3/me/vpMeEllipse.h index f68b0243a2..343858a274 100644 --- a/modules/tracker/me/include/visp3/me/vpMeEllipse.h +++ b/modules/tracker/me/include/visp3/me/vpMeEllipse.h @@ -229,22 +229,47 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker void initTracking(const vpImage &I, bool trackCircle = false, bool trackArc = false); /*! - * Initialize the tracking of an ellipse/circle or an arc of an ellipse/circle when \e trackArc is set to true. - * The ellipse/circle is defined thanks to a vector of image points. + * Initialize the tracking of an ellipse or an arc of an ellipse when \e trackArc is set to true. + * If \b ips is set, use the contained points to initialize the ME if there are some, or initialize + * by clicks the ME and \b ips will contained the clicked points. + * If \b ips is not set, call the method vpMeEllispe::initTracking(const vpImage&, bool, bool). + * + * \sa \ref vpMeEllispe::initTracking() * - * \warning It is mandatory to use at least five image points to estimate the - * ellipse parameters while three points are needed to estimate the circle parameters. - * \warning The image points should be selected as far as possible from each other. - * When an arc of an ellipse/circle is tracked, it is recommended to select the 5/3 points clockwise. + * \warning The points should be selected as far as possible from each other. + * When an arc of an ellipse is tracked, it is recommended to select the 5 points clockwise. * - * \param I : Image in which the ellipse/circle appears. - * \param iP : A vector of image points belonging to the ellipse/circle edge used to - * initialize the tracking. + * \param I : Image in which the ellipse appears. + * \param opt_ips: If set, either a vector that contains the vpImagePoint to use or will be filled with the clicked + * points. * \param trackCircle : When true, track a circle, when false track an ellipse. * \param trackArc : When true track an arc of the ellipse/circle. In that case, first and * last points specify the extremities of the arc (clockwise). * When false track the complete ellipse/circle. */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) + void initTracking(const vpImage &I, std::optional> &opt_ips, bool trackCircle = false, bool trackArc = false); +#else + void initTracking(const vpImage &I, std::vector *opt_ips, bool trackCircle = false, bool trackArc = false); +#endif + +/*! + * Initialize the tracking of an ellipse/circle or an arc of an ellipse/circle when \e trackArc is set to true. + * The ellipse/circle is defined thanks to a vector of image points. + * + * \warning It is mandatory to use at least five image points to estimate the + * ellipse parameters while three points are needed to estimate the circle parameters. + * \warning The image points should be selected as far as possible from each other. + * When an arc of an ellipse/circle is tracked, it is recommended to select the 5/3 points clockwise. + * + * \param I : Image in which the ellipse/circle appears. + * \param iP : A vector of image points belonging to the ellipse/circle edge used to + * initialize the tracking. + * \param trackCircle : When true, track a circle, when false track an ellipse. + * \param trackArc : When true track an arc of the ellipse/circle. In that case, first and + * last points specify the extremities of the arc (clockwise). + * When false track the complete ellipse/circle. + */ void initTracking(const vpImage &I, const std::vector &iP, bool trackCircle = false, bool trackArc = false); diff --git a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp index 0e2c34c101..664f440e9a 100644 --- a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp @@ -1131,6 +1131,67 @@ void vpMeEllipse::initTracking(const vpImage &I, bool trackCircle initTracking(I, iP, trackCircle, trackArc); } +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) +void vpMeEllipse::initTracking(const vpImage &I, std::optional> &opt_ips, bool trackCircle, bool trackArc) +#else +void vpMeEllipse::initTracking(const vpImage &I, std::vector *opt_ips, bool trackCircle, bool trackArc) +#endif +{ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) + if (!opt_ips.has_value()) +#else + if (opt_ips == nullptr) +#endif + { + initTracking(I, trackCircle, trackArc); + return; + } + + if (opt_ips->size() != 0) { + initTracking(I, *opt_ips, trackCircle, trackArc); + return; + } + + unsigned int n = 5; // by default, 5 points for an ellipse + const unsigned int nForCircle = 3; + m_trackCircle = trackCircle; + if (trackCircle) { + n = nForCircle; + } + opt_ips->resize(n); + m_trackArc = trackArc; + + vpDisplay::flush(I); + + if (m_trackCircle) { + if (m_trackArc) { + std::cout << "First and third points specify the extremities of the arc of circle (clockwise)" << std::endl; + } + for (unsigned int k = 0; k < n; ++k) { + std::cout << "Click point " << (k + 1) << "/" << n << " on the circle " << std::endl; + vpDisplay::getClick(I, (*opt_ips)[k], true); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, (*opt_ips)[k], crossSize, vpColor::red); + vpDisplay::flush(I); + std::cout << (*opt_ips)[k] << std::endl; + } + } + else { + if (m_trackArc) { + std::cout << "First and fifth points specify the extremities of the arc of ellipse (clockwise)" << std::endl; + } + for (unsigned int k = 0; k < n; ++k) { + std::cout << "Click point " << (k + 1) << "/" << n << " on the ellipse " << std::endl; + vpDisplay::getClick(I, (*opt_ips)[k], true); + const unsigned int crossSize = 10; + vpDisplay::displayCross(I, (*opt_ips)[k], crossSize, vpColor::red); + vpDisplay::flush(I); + std::cout << (*opt_ips)[k] << std::endl; + } + } + initTracking(I, *opt_ips, trackCircle, trackArc); +} + void vpMeEllipse::initTracking(const vpImage &I, const std::vector &iP, bool trackCircle, bool trackArc) { From ac8e4b0cf5c555a8486bdaa5d8a1724e1ceb23d2 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 2 Feb 2024 17:30:11 +0100 Subject: [PATCH 016/164] Ignore Windows subclasses for display, fix some MSVC issues in bindings --- modules/python/bindings/include/core/arrays.hpp | 16 ++++++++-------- modules/python/bindings/include/core/utils.hpp | 14 +++++++------- modules/python/bindings/include/mbt.hpp | 2 +- modules/python/config/gui.json | 2 +- 4 files changed, 17 insertions(+), 17 deletions(-) diff --git a/modules/python/bindings/include/core/arrays.hpp b/modules/python/bindings/include/core/arrays.hpp index 7c862728c2..5a92bfae62 100644 --- a/modules/python/bindings/include/core/arrays.hpp +++ b/modules/python/bindings/include/core/arrays.hpp @@ -183,7 +183,7 @@ void bindings_vpArray2D(py::class_> &pyArray2D) pyArray2D.def(py::init([](np_array_cf &np_array) { verify_array_shape_and_dims(np_array, 2, "ViSP 2D array"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; vpArray2D result(shape[0], shape[1]); copy_data_from_np(np_array, result.data); return result; @@ -207,7 +207,7 @@ void bindings_vpMatrix(py::class_> &pyMatrix) pyMatrix.def(py::init([](np_array_cf np_array) { verify_array_shape_and_dims(np_array, 2, "ViSP Matrix"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; vpMatrix result(shape[0], shape[1]); copy_data_from_np(np_array, result.data); return result; @@ -231,7 +231,7 @@ void bindings_vpRotationMatrix(py::class_> & }, numpy_fn_doc_nonwritable, py::keep_alive<0, 1>()); pyRotationMatrix.def(py::init([](np_array_cf np_array) { verify_array_shape_and_dims(np_array, { 3, 3 }, "ViSP rotation matrix"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; vpRotationMatrix result; copy_data_from_np(np_array, result.data); if (!result.isARotationMatrix()) { @@ -258,7 +258,7 @@ void bindings_vpHomogeneousMatrix(py::class_ np_array) { verify_array_shape_and_dims(np_array, { 4, 4 }, "ViSP homogeneous matrix"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; vpHomogeneousMatrix result; copy_data_from_np(np_array, result.data); if (!result.isAnHomogeneousMatrix()) { @@ -287,9 +287,9 @@ void bindings_vpTranslationVector(py::class_()); pyTranslationVector.def(py::init([](np_array_cf np_array) { - const std::vector required_shape = { 3 }; + const std::vector required_shape = { 3 }; verify_array_shape_and_dims(np_array, required_shape, "ViSP translation vector"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; vpTranslationVector result; copy_data_from_np(np_array, result.data); return result; @@ -313,7 +313,7 @@ void bindings_vpColVector(py::class_> &pyColVecto pyColVector.def(py::init([](np_array_cf np_array) { verify_array_shape_and_dims(np_array, 1, "ViSP column vector"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; vpColVector result(shape[0]); copy_data_from_np(np_array, result.data); return result; @@ -335,7 +335,7 @@ void bindings_vpRowVector(py::class_> &pyRowVecto }, numpy_fn_doc_writable, py::keep_alive<0, 1>()); pyRowVector.def(py::init([](np_array_cf np_array) { verify_array_shape_and_dims(np_array, 1, "ViSP row vector"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; vpRowVector result(shape[0]); copy_data_from_np(np_array, result.data); return result; diff --git a/modules/python/bindings/include/core/utils.hpp b/modules/python/bindings/include/core/utils.hpp index 3bb413bdf0..404dbc53fd 100644 --- a/modules/python/bindings/include/core/utils.hpp +++ b/modules/python/bindings/include/core/utils.hpp @@ -52,7 +52,7 @@ using np_array_cf = py::array_t template py::buffer_info make_array_buffer(T *data, std::array dims, bool readonly) { - std::array strides; + std::array strides; for (unsigned i = 0; i < N; i++) { unsigned s = sizeof(T); for (unsigned j = i + 1; j < N; ++j) { @@ -71,7 +71,7 @@ py::buffer_info make_array_buffer(T *data, std::array dims, bool re ); } -std::string shape_to_string(const std::vector &shape) +std::string shape_to_string(const std::vector &shape) { std::stringstream ss; ss << "("; @@ -89,7 +89,7 @@ template void verify_array_shape_and_dims(np_array_cf np_array, unsigned dims, const char *class_name) { py::buffer_info buffer = np_array.request(); - std::vector shape = buffer.shape; + std::vector shape = buffer.shape; if (shape.size() != dims) { std::stringstream ss; ss << "Tried to instanciate " << class_name @@ -100,11 +100,11 @@ void verify_array_shape_and_dims(np_array_cf np_array, unsigned dims, cons } } template -void verify_array_shape_and_dims(np_array_cf np_array, std::vector expected_dims, const char *class_name) +void verify_array_shape_and_dims(np_array_cf np_array, std::vector expected_dims, const char *class_name) { verify_array_shape_and_dims(np_array, expected_dims.size(), class_name); py::buffer_info buffer = np_array.request(); - std::vector shape = buffer.shape; + std::vector shape = buffer.shape; bool invalid_shape = false; for (unsigned int i = 0; i < expected_dims.size(); ++i) { if (shape[i] != expected_dims[i]) { @@ -125,9 +125,9 @@ template void copy_data_from_np(np_array_cf src, Item *dest) { py::buffer_info buffer = src.request(); - std::vector shape = buffer.shape; + std::vector shape = buffer.shape; unsigned int elements = 1; - for (ssize_t dim : shape) { + for (py::ssize_t dim : shape) { elements *= dim; } const Item *data = (Item *)buffer.ptr; diff --git a/modules/python/bindings/include/mbt.hpp b/modules/python/bindings/include/mbt.hpp index 2dc974c728..ab4e2cffd6 100644 --- a/modules/python/bindings/include/mbt.hpp +++ b/modules/python/bindings/include/mbt.hpp @@ -50,7 +50,7 @@ void bindings_vpMbGenericTracker(py::class_ &py for (const auto &point_cloud_pair: mapOfPointClouds) { py::buffer_info buffer = point_cloud_pair.second.request(); - if (buffer.ndim != 3 and buffer.shape[2] != 3) { + if (buffer.ndim != 3 && buffer.shape[2] != 3) { std::stringstream ss; ss << "Pointcloud error: pointcloud at key: " << point_cloud_pair.first << " should be a 3D numpy array of dimensions H X W x 3"; diff --git a/modules/python/config/gui.json b/modules/python/config/gui.json index 294b0d30ac..d35b0635bc 100644 --- a/modules/python/config/gui.json +++ b/modules/python/config/gui.json @@ -1,5 +1,5 @@ { - "ignored_headers": [], + "ignored_headers": ["vpWin32Renderer.h", "vpWin32Window.h", "vpWin32API.h", "vpGDIRenderer.h"], "ignored_classes": [], "user_defined_headers": [], "classes": {}, From e6289099ee4c4b70a33fffdd3059d7c5f50d9a84 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 2 Feb 2024 18:23:18 +0100 Subject: [PATCH 017/164] fix remaining ssize_t errors for MSVC --- modules/python/bindings/include/core/images.hpp | 6 +++--- modules/python/bindings/include/core/pixel_meter.hpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/modules/python/bindings/include/core/images.hpp b/modules/python/bindings/include/core/images.hpp index 53e0a08e19..e9932d712c 100644 --- a/modules/python/bindings/include/core/images.hpp +++ b/modules/python/bindings/include/core/images.hpp @@ -109,7 +109,7 @@ bindings_vpImage(py::class_> &pyImage) pyImage.def(py::init([](np_array_cf &np_array) { verify_array_shape_and_dims(np_array, 2, "ViSP Image"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; vpImage result(shape[0], shape[1]); copy_data_from_np(np_array, result.bitmap); return result; @@ -151,7 +151,7 @@ bindings_vpImage(py::class_> &pyImage) pyImage.def(py::init([](np_array_cf &np_array) { verify_array_shape_and_dims(np_array, 3, "ViSP RGBa image"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; if (shape[2] != 4) { throw std::runtime_error("Tried to copy a 3D numpy array that does not have 4 elements per pixel into a ViSP RGBA image"); } @@ -196,7 +196,7 @@ bindings_vpImage(py::class_> &pyImage) pyImage.def(py::init([](np_array_cf &np_array) { verify_array_shape_and_dims(np_array, 3, "ViSP RGBa image"); - const std::vector shape = np_array.request().shape; + const std::vector shape = np_array.request().shape; if (shape[2] != 3) { throw std::runtime_error("Tried to copy a 3D numpy array that does not have 3 elements per pixel into a ViSP RGBf image"); } diff --git a/modules/python/bindings/include/core/pixel_meter.hpp b/modules/python/bindings/include/core/pixel_meter.hpp index c55b272e2d..28ec7aba09 100644 --- a/modules/python/bindings/include/core/pixel_meter.hpp +++ b/modules/python/bindings/include/core/pixel_meter.hpp @@ -61,7 +61,7 @@ void bindings_vpPixelMeterConversion(py::class_ &pyPM) double *x_ptr = static_cast(xs.request().ptr); double *y_ptr = static_cast(ys.request().ptr); - for (ssize_t i = 0; i < bufu.size; ++i) { + for (py::ssize_t i = 0; i < bufu.size; ++i) { vpPixelMeterConversion::convertPoint(cam, u_ptr[i], v_ptr[i], x_ptr[i], y_ptr[i]); } @@ -124,7 +124,7 @@ void bindings_vpMeterPixelConversion(py::class_ &pyMP) double *u_ptr = static_cast(us.request().ptr); double *v_ptr = static_cast(vs.request().ptr); - for (ssize_t i = 0; i < bufx.size; ++i) { + for (py::ssize_t i = 0; i < bufx.size; ++i) { vpMeterPixelConversion::convertPoint(cam, x_ptr[i], y_ptr[i], u_ptr[i], v_ptr[i]); } From 31e0650c4027975f4eb0ab3acd2f67e1f85f855a Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 2 Feb 2024 18:53:53 +0100 Subject: [PATCH 018/164] Fix doc strings that are too long and generate error on windows --- .../generator/visp_python_bindgen/doc_parser.py | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/modules/python/generator/visp_python_bindgen/doc_parser.py b/modules/python/generator/visp_python_bindgen/doc_parser.py index 4dd47d8325..2e4fc4eafa 100644 --- a/modules/python/generator/visp_python_bindgen/doc_parser.py +++ b/modules/python/generator/visp_python_bindgen/doc_parser.py @@ -84,9 +84,18 @@ def to_cstring(s: str) -> str: s = re.sub('\n\n\n+', '\n\n', s) s = re.sub('\\\\ +', '\\\\', s) - return f'''R"doc( -{s} -)doc"''' + # On Windows, strings have a maximum length. + per_string_limit = 8192 + current_char = 0 + result = '' + while current_char < len(s): + result += f'''R"doc( +{s[current_char: min((current_char + per_string_limit), len(s))]})doc" + +''' + current_char += per_string_limit + return result + @dataclass class MethodDocSignature: From 52e192476de67564ea4173516525839d397ec3cf Mon Sep 17 00:00:00 2001 From: Souriya Trinh Date: Sun, 4 Feb 2024 03:00:53 +0100 Subject: [PATCH 019/164] Try to emulate the ROS2 Jenkins environment on Github runner. --- .github/workflows/ubuntu-isolated.yml | 25 ++++++++++++++++++++++--- 1 file changed, 22 insertions(+), 3 deletions(-) diff --git a/.github/workflows/ubuntu-isolated.yml b/.github/workflows/ubuntu-isolated.yml index 206d8130e2..a275b6080e 100644 --- a/.github/workflows/ubuntu-isolated.yml +++ b/.github/workflows/ubuntu-isolated.yml @@ -14,8 +14,8 @@ jobs: strategy: fail-fast: false matrix: - os: [ubuntu-22.04] - compiler: [ {CC: /usr/bin/clang, CXX: /usr/bin/clang++} ] + os: [ubuntu-latest] + compiler: [ {CC: /usr/bin/gcc, CXX: /usr/bin/g++} ] standard: [ 17 ] steps: @@ -25,6 +25,24 @@ jobs: with: access_token: ${{ github.token }} + # Remove some packages to emulate the ROS2 Jenkins environment + # X11: https://raspberrypi.stackexchange.com/a/92334 + # Java: https://askubuntu.com/a/185531 + name: Remove packages + run: | + sudo apt-get install libomp-dev + sudo apt purge --auto-remove 'x11-*' + java -version + sudo dpkg --list | grep -i jdk + sudo dpkg --list | grep -i java + sudo apt-get purge --auto-remove openjdk* + sudo apt-get purge --auto-remove icedtea-* openjdk-* + sudo dpkg --list | grep -i jdk + sudo dpkg --list | grep -i java + sudo apt purge --auto-remove 'libjpeg*' + sudo apt purge --auto-remove 'libpng*' + sudo apt purge --auto-remove 'libxml*' + - name: Checkout repository uses: actions/checkout@v3 @@ -47,7 +65,8 @@ jobs: echo "CC: $CC" echo "CXX: $CXX" echo "Standard: $CXX_STANDARD" - cmake .. -DCMAKE_C_COMPILER="${CC}" -DCMAKE_CXX_COMPILER="${CXX}" -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/tmp/usr/local -DCMAKE_VERBOSE_MAKEFILE=ON -DUSE_CXX_STANDARD=$CXX_STANDARD + cmake .. -DCMAKE_C_COMPILER="${CC}" -DCMAKE_CXX_COMPILER="${CXX}" -DCMAKE_BUILD_TYPE=Release \ + -DCMAKE_INSTALL_PREFIX=/tmp/usr/local -DCMAKE_VERBOSE_MAKEFILE=ON -DUSE_CXX_STANDARD=$CXX_STANDARD cat ViSP-third-party.txt - name: Compile From 168378e55eeecf7edac5268a867c7ab1ff07483a Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Sun, 4 Feb 2024 09:43:23 +0100 Subject: [PATCH 020/164] Add missing optional header --- modules/tracker/me/include/visp3/me/vpMeEllipse.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/modules/tracker/me/include/visp3/me/vpMeEllipse.h b/modules/tracker/me/include/visp3/me/vpMeEllipse.h index 343858a274..a70017936a 100644 --- a/modules/tracker/me/include/visp3/me/vpMeEllipse.h +++ b/modules/tracker/me/include/visp3/me/vpMeEllipse.h @@ -49,6 +49,10 @@ #include #include +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) +#include +#endif + /*! * \class vpMeEllipse * \ingroup module_me From dc5e172581a8cc25d2333c7bf92fcc9ed72d1bc3 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 5 Feb 2024 14:34:32 +0100 Subject: [PATCH 021/164] Fix missing symbols for vpDisplayWin32 --- .../gui/src/display/windows/vpDisplayWin32.cpp | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/modules/gui/src/display/windows/vpDisplayWin32.cpp b/modules/gui/src/display/windows/vpDisplayWin32.cpp index 410db2674f..49d2599b45 100644 --- a/modules/gui/src/display/windows/vpDisplayWin32.cpp +++ b/modules/gui/src/display/windows/vpDisplayWin32.cpp @@ -57,10 +57,24 @@ void vpCreateWindow(threadParam *param) } /*! - Constructor. + Constructors. */ vpDisplayWin32::vpDisplayWin32(vpWin32Renderer *rend) : iStatus(false), window(rend) { } +vpDisplayWin32::vpDisplayWin32(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") + : iStatus(false), window(nullptr) +{ + init(I, winx, winy, title); +} + +vpDisplayWin32::vpDisplayWin32(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") + : iStatus(false), window(nullptr) +{ + init(I, winx, winy, title); +} + + + /*! Destructor. */ From 8f9af8ac18158b4c4dd1dd1aaa1b9f04e966f38c Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 5 Feb 2024 14:55:11 +0100 Subject: [PATCH 022/164] Fix MSVC linkage errors due to VISP_EXPORT on header only class --- modules/sensor/include/visp3/sensor/vpLaserScan.h | 2 +- modules/sensor/include/visp3/sensor/vpLaserScanner.h | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/modules/sensor/include/visp3/sensor/vpLaserScan.h b/modules/sensor/include/visp3/sensor/vpLaserScan.h index 2c659552f2..491ee8b587 100644 --- a/modules/sensor/include/visp3/sensor/vpLaserScan.h +++ b/modules/sensor/include/visp3/sensor/vpLaserScan.h @@ -58,7 +58,7 @@ Other data as the start/stop angle, the start/end timestamp are also considered. */ -class VISP_EXPORT vpLaserScan +class /*VISP_EXPORT*/ vpLaserScan { public: /*! Default constructor that initialize all the internal variable to zero. diff --git a/modules/sensor/include/visp3/sensor/vpLaserScanner.h b/modules/sensor/include/visp3/sensor/vpLaserScanner.h index 5d947781b2..2800588bb4 100644 --- a/modules/sensor/include/visp3/sensor/vpLaserScanner.h +++ b/modules/sensor/include/visp3/sensor/vpLaserScanner.h @@ -51,16 +51,16 @@ \brief Class that defines a generic laser scanner. */ -class VISP_EXPORT vpLaserScanner +class /*VISP_EXPORT*/ vpLaserScanner { public: /*! Default constructor that initialize all the internal variable to zero. */ - vpLaserScanner() : ip("null"), port(0){}; + vpLaserScanner() : ip("null"), port(0) { }; /*! Copy constructor. */ - vpLaserScanner(const vpLaserScanner &scanner) : ip(scanner.ip), port(scanner.port){}; + vpLaserScanner(const vpLaserScanner &scanner) : ip(scanner.ip), port(scanner.port) { }; /*! Default destructor that does nothing. */ - virtual ~vpLaserScanner(){}; + virtual ~vpLaserScanner() { }; /*! Set the Ethernet address of the laser. */ void setIpAddress(std::string ip_address) { this->ip = ip_address; }; From 091ae5670c76517b4980189ccd078da79c0968d0 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 5 Feb 2024 16:32:22 +0100 Subject: [PATCH 023/164] update python tutorial --- .../tutorial-install-python-bindings.dox | 192 +++++++++++++++++- 1 file changed, 183 insertions(+), 9 deletions(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 2683691a3d..6bb6dd204f 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -6,19 +6,25 @@ \section py_bindings_intro Introduction ViSP includes an automatic tool to generate Pybind11-based bindings for ViSP. -After bindings build and installation, ViSP can be used from python and almost all functions should be available. +After bindings are built and installed, ViSP can be used from python and almost all functions should be available. -The tool that allows to build the bindings is located in the ViSP `modules/python` folder containing: +The tool that allows to build the bindings is located in the ViSP `modules/python` folder and contains multiple subfolders: +For the developer or the user interested in modifying the bindings these folders are of interest: +- generator: the Python code to generate pybind11 C++ code, which can then be compiled; - bindings: the recipe for building the Pybind code, as well as handcrafted binding functions (e.g. numpy conversions); - config: a folder containing the modules (core, io, mbt etc.) configuration; - It may also contain pure python code, that can be added on top of the generated bindings; -- doc: Sphinx-based documentation sources for the Python version of ViSP; -- examples: some python examples that show how to use ViSP bindings; -- generator: the Python code to generate pybind11 C++ code, which can then be compiled; - stubs: A way to build "stubs" after compiling the pybind extension and installing the ViSP module. Stubs provide type - information and allow for autocompletion in IDE (tested in visual code); -- test: Python bindings tests. + information and allow for autocompletion in IDE (tested in visual code). + +For all users these folders are important and illustrate the usage of the binding: + +- test: Python bindings tests. Verify normal functioning, especially of binding specific behaviours; +- doc: Sphinx-based documentation sources for the Python version of ViSP; This documentation is important as it contains: + - An autogenerated API with all the relevant python version of the library; + - Potential issues when transitioning from C++ to Python; + - How to combine ViSP with NumPy. +- examples: some python examples that show how to use ViSP bindings. \section py_bindings_build Build Python bindings from source @@ -26,6 +32,7 @@ The general principle to build the Python bindings is the following: - Install python3 - Install or upgrade `pip3` - Install pybind11 +- Install and create a virtual environment (either through virtualenv or conda) - Create a ViSP dedicated workspace, get the latest source code and configure ViSP - When configuring ViSP, make sure that `BUILD_PYTHON_BINDINGS` is `ON` - To build the bindings build the target `visp_python_bindings` @@ -112,7 +119,10 @@ The general principle to build the Python bindings is the following: - Test python bindings (venv) % pip install pytest + (venv) % pip install pytest-sphinx (venv) % python -m pytest visp/modules/python/test + (venv) % python -m pytest --doctest-glob=*.rst visp/modules/python/doc + - Launch python mbt example @@ -129,7 +139,7 @@ The general principle to build the Python bindings is the following: \subsection py_bindings_build_ubuntu How to build on Ubuntu 22.04 -These are the steps to build ViSP Python bindings on macOS: +These are the steps to build ViSP Python bindings on Ubuntu 22.04: - Install or upgrade pip3 @@ -208,7 +218,10 @@ These are the steps to build ViSP Python bindings on macOS: - Test Python bindings (venv) % pip install pytest + (venv) % pip install pytest-sphinx (venv) % python -m pytest visp/modules/python/test + (venv) % python -m pytest --doctest-glob=*.rst visp/modules/python/doc + - Launch Python model-based tracker example @@ -314,4 +327,165 @@ These are the steps to build ViSP Python bindings on macOS: (venv) C:\> cmake --build . --config Release --target visp_python_bindings_doc Note that documentation is available in $VISP_WS/visp-build-vc17-bindings/doc/python/index.html + +\subsection py_bindings_improvements Improving the bindings + +If a feature, such as a function, class or python specific utilities is missing, you should first check that +the Python API (built when generating the Python-specific documentation) does not have that function or class; + +If so, you may raise an issue on GitHub, detailing the feature that is missing and the use case. This issue should have a [Python] tag in the title. + +There are multiple ways to extend and improve the custom Python bindings: + + - Modify and improve the automatic generation tool (advanced, requires Python knowledge); + - Add custom binding functions in the `modules/python/bindings/include` (Requires C++ knownledge); + + - You can start from predefined bindings in the other header files. + - Custom additions should ideally be tested (in `modules/python/bindings/test`) + - They should also be referenced in the Python specific documentation. + + - Modify the JSON configuration files to include previously excluded functions. The automatic tool performs a best effort job, but some human knowledge is sometimes required to wrap certain functions. + +For more information and detailed explanations on the different improvement tracks, see the Python specific documentation. + +\subsection py_bindings_known_build_issues Potential build issues + +\subsubsection py_bindings_send_log Submitting an issue on GitHub + +If you encounter a problem during the build, you may raise an issue on GitHub. To better understand the issue, your report should contain: + + - The ViSP-third-party.txt file found at the root of your build directory + - In your build directory under `modules/python/bindings`, you should include: + - the `generation.log` file: this can help detect at which step the build is failling + - the `src` folder: contains the generated binding code and the preprocessed headers as seen by the generation tool + - The output of your terminal + + + +\subsubsection py_bindings_known_errors Known build errors + +When compiling or modifying the bindings, you may encounter errors. + +Here is a non-exhaustive list of errors. + +If you encounter a compilation error, make sure to first try rebuilding after cleaning the CMake cache +Pybind did generate problems (an error at the pybind include line) that were solved like this. + +#### When running the generation tool + +##### Cannot parse code + +\verbatim + 100%|##########| 319/319 [00:13<00:00, 23.91hdr/s] + Traceback (most recent call last): + File "", line 198, in _run_module_as_main + There was an error when processing headerC:\visp-ws\test-pr\visp-SamFlt\visp\modules\robot\include\visp3\robot\vpRobotWireFrameSimulator.h See the text log in the build folder for more information. + File "", line 88, in _run_code + File "C:\visp-ws\test-pr\visp-SamFlt\venv\Lib\site-packages\visp_python_bindgen\generator.py", line 177, in + main() + File "C:\visp-ws\test-pr\visp-SamFlt\venv\Lib\site-packages\visp_python_bindgen\generator.py", line 174, in main + generate_module(generation_path_src, config_path) + File "C:\visp-ws\test-pr\visp-SamFlt\venv\Lib\site-packages\visp_python_bindgen\generator.py", line 114, in generate_module + raise RuntimeError('There was an exception when processing headers: You should either ignore the faulty header/class, or fix the generator code!') + RuntimeError: There was an exception when processing headers: You should either ignore the faulty header/class, or fix the generator code! +C:\Program Files\Microsoft Visual Studio\2022\Community\MSBuild\Microsoft\VC\v170\Microsoft.CppCommon.targets(254,5): error MSB8066: la build personnalisée de 'C:\visp-ws\test-pr\visp-SamFlt\visp-build-vc17-bindings\CMakeFi +\endverbatim + +This means that there is a parsing error when reading the ViSP header files. + +This may be due to macro definitions, which are not done by an actual compiler. +Custom macro definitions are defined in an autogenerated file in the build folder: `modules/python/cmake_config.json`. +To add a custom macro, you should modify the GenerateConfig.cmake file in the modules/python folder in the **source** directory of ViSP. + + +For instance, in the function declaration: +\code{.cpp} +static DWORD WINAPI launcher(LPVOID lpParam); +\endcode + +The macros DWORD, WINAPI and LPVOID are defined by MSVC, but are unknown to our tool. +We can defined them by adding custom defines in the GenerateConfig.cmake file: +\code +if(WIN32) # WIN32 only defs + # ... + string(JSON json_defines SET ${json_defines} "DWORD" "uint64_t") + string(JSON json_defines SET ${json_defines} "WINAPI" "__stdcall") + string(JSON json_defines SET ${json_defines} "LPVOID" "void*") +endif() +\endcode + +If the issue persists, you can ignore the header by going to the relevant configuration file modules/python/config/module.json, where *module* is the module where parsing fails. +Here, the failing header was "vpRobotWireFrameSimulator.h" in the robot module, so we can edit the `modules/python/config/robot.json` and add: +\code{.json} +{ + "ignore_headers": ["vpRobotWireFrameSimulator.h"] +} +\endcode + +#### When compiling the bindings + + +##### Abstract class not detected + +If you have this error: +\verbatim + error: invalid new-expression of abstract class type ‘vpTemplateTrackerMI’ + return new Class{std::forward(args)...}; + In file included from /home/visp_ws/visp_build/modules/python/bindings/src/tt_mi.cpp:13:0: + /home/visp_ws/visp/modules/tracker/tt_mi/include/visp3/tt_mi/vpTemplateTrackerMI.h:46:19: note: because the following virtual functions are pure within ‘vpTemplateTrackerMI’: + class VISP_EXPORT vpTemplateTrackerMI : public vpTemplateTracker +\endverbatim + +You should define the class (here vpTemplateTrackerMI) as pure virtual in the config file (via the flag is_virtual). +This error occurs because some methods are defined as pure virtual in a parent class and are not defined in the class this class: Pure virtual class detection does not look in the class hierarchy but only at the present class. + + +#### Template errors + +If you have an issue that looks like: +\verbatim + Consolidate compiler generated dependencies of target _visp + [ 97%] Building CXX object modules/python/bindings/CMakeFiles/_visp.dir/src/core.cpp.o + [ 97%] Building CXX object modules/python/bindings/CMakeFiles/_visp.dir/src/robot.cpp.o + In file included from /usr/include/c++/11/bits/move.h:57, + from /usr/include/c++/11/bits/stl_pair.h:59, + from /usr/include/c++/11/bits/stl_algobase.h:64, + from /usr/include/c++/11/bits/specfun.h:45, + from /usr/include/c++/11/cmath:1935, + from /usr/include/c++/11/math.h:36, + from /home/sfelton/miniconda3/envs/wrapper3.9/include/python3.9/pyport.h:205, + from /home/sfelton/miniconda3/envs/wrapper3.9/include/python3.9/Python.h:50, + from /home/sfelton/.local/include/pybind11/detail/common.h:266, + from /home/sfelton/.local/include/pybind11/attr.h:13, + from /home/sfelton/.local/include/pybind11/detail/class.h:12, + from /home/sfelton/.local/include/pybind11/pybind11.h:13, + from /home/sfelton/software/visp_build/modules/python/bindings/src/robot.cpp:3: + /usr/include/c++/11/type_traits: **In instantiation of ‘struct std::is_move_constructible >’:** + /usr/include/c++/11/type_traits:152:12: required from ‘struct std::__and_ >, std::is_move_assignable > >’ + /usr/include/c++/11/type_traits:157:12: required from ‘struct std::__and_ > >, std::is_move_constructible >, std::is_move_assignable > >’ + /usr/include/c++/11/type_traits:2209:11: required by substitution of ‘template using _Require = std::__enable_if_t >::value> [with _Cond = {std::__not_ > >, std::is_move_constructible >, std::is_move_assignable >}]’ + /usr/include/c++/11/bits/move.h:196:5: required by substitution of ‘template std::_Require >, std::is_move_constructible<_Tp>, std::is_move_assignable<_Tp> > std::swap(_Tp&, _Tp&) [with _Tp = vpImage]’ + /home/sfelton/software/visp-sfelton/modules/core/include/visp3/core/vpImage.h:341:15: required from ‘class vpImage’ + /home/sfelton/software/visp-sfelton/modules/core/include/visp3/core/vpImage.h:369:17: required from here + /usr/include/c++/11/type_traits:1010:52: error: static assertion failed: template argument must be a complete class or an unbounded array + 1010 | **static_assert(std::__is_complete_or_unbounded(__type_identity<_Tp>{}),** + +\endverbatim + +You should delete the files in `modules/python/` of the **build** directory. + + +#### When importing Python in ViSP + +##### Static and member methods have the same name + +If, when importing visp in Python, you encounter this message: +\verbatim + ImportError: overloading a method with both static and instance methods is not supported; error while attempting to bind instance method visp.xxx() -> None +\endverbatim + +Then it means that a class has both a static method and a member method with the same name. You should :ref:`rename either one through the config files `. + +This error may also happen when generating the Python stubs (after the bindings compilation and linking step). + */ From b4c373d6c6b1ad9b3037247d5d63b2d2215dd084 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 5 Feb 2024 16:33:56 +0100 Subject: [PATCH 024/164] remove default values in vpDisplayWin32.cpp --- modules/gui/src/display/windows/vpDisplayWin32.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/gui/src/display/windows/vpDisplayWin32.cpp b/modules/gui/src/display/windows/vpDisplayWin32.cpp index 49d2599b45..67c1d21b21 100644 --- a/modules/gui/src/display/windows/vpDisplayWin32.cpp +++ b/modules/gui/src/display/windows/vpDisplayWin32.cpp @@ -61,13 +61,13 @@ void vpCreateWindow(threadParam *param) */ vpDisplayWin32::vpDisplayWin32(vpWin32Renderer *rend) : iStatus(false), window(rend) { } -vpDisplayWin32::vpDisplayWin32(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") +vpDisplayWin32::vpDisplayWin32(vpImage &I, int winx, int winy, const std::string &title) : iStatus(false), window(nullptr) { init(I, winx, winy, title); } -vpDisplayWin32::vpDisplayWin32(vpImage &I, int winx = -1, int winy = -1, const std::string &title = "") +vpDisplayWin32::vpDisplayWin32(vpImage &I, int winx, int winy, const std::string &title) : iStatus(false), window(nullptr) { init(I, winx, winy, title); From 46638f800eb43574fac2af9c3c744d42b131d2b7 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 7 Feb 2024 14:14:19 +0100 Subject: [PATCH 025/164] Introduce std::thread and std::mutex usage instead of pthread --- .vscode/settings.json | 22 +- 3rdparty/simdlib/Simd/SimdAlignment.h | 0 3rdparty/simdlib/Simd/SimdAllocator.hpp | 0 3rdparty/simdlib/Simd/SimdArray.h | 0 3rdparty/simdlib/Simd/SimdAvx1.h | 0 3rdparty/simdlib/Simd/SimdAvx1Cpu.cpp | 0 3rdparty/simdlib/Simd/SimdAvx1Resizer.cpp | 0 3rdparty/simdlib/Simd/SimdAvx2.h | 0 3rdparty/simdlib/Simd/SimdAvx2BgrToBgra.cpp | 0 3rdparty/simdlib/Simd/SimdAvx2BgrToGray.cpp | 0 3rdparty/simdlib/Simd/SimdAvx2BgrToRgb.cpp | 0 3rdparty/simdlib/Simd/SimdAvx2BgraToBgr.cpp | 0 3rdparty/simdlib/Simd/SimdAvx2BgraToGray.cpp | 0 3rdparty/simdlib/Simd/SimdAvx2Cpu.cpp | 0 .../simdlib/Simd/SimdAvx2Deinterleave.cpp | 0 .../simdlib/Simd/SimdAvx2GaussianBlur.cpp | 0 3rdparty/simdlib/Simd/SimdAvx2Reduce.cpp | 0 .../simdlib/Simd/SimdAvx2ReduceGray2x2.cpp | 0 .../simdlib/Simd/SimdAvx2ReduceGray3x3.cpp | 0 .../simdlib/Simd/SimdAvx2ReduceGray4x4.cpp | 0 .../simdlib/Simd/SimdAvx2ReduceGray5x5.cpp | 0 .../simdlib/Simd/SimdAvx2ResizeBilinear.cpp | 0 3rdparty/simdlib/Simd/SimdAvx2Resizer.cpp | 0 3rdparty/simdlib/Simd/SimdBase.h | 0 3rdparty/simdlib/Simd/SimdBaseBgrToBgra.cpp | 0 3rdparty/simdlib/Simd/SimdBaseBgrToGray.cpp | 0 3rdparty/simdlib/Simd/SimdBaseBgrToRgb.cpp | 0 3rdparty/simdlib/Simd/SimdBaseBgraToBgr.cpp | 0 3rdparty/simdlib/Simd/SimdBaseBgraToGray.cpp | 0 3rdparty/simdlib/Simd/SimdBaseCpu.cpp | 0 .../simdlib/Simd/SimdBaseDeinterleave.cpp | 0 .../simdlib/Simd/SimdBaseGaussianBlur.cpp | 0 3rdparty/simdlib/Simd/SimdBaseResizer.cpp | 0 3rdparty/simdlib/Simd/SimdConfig.h | 0 3rdparty/simdlib/Simd/SimdConst.h | 0 3rdparty/simdlib/Simd/SimdConversion.h | 0 3rdparty/simdlib/Simd/SimdCopyPixel.h | 0 3rdparty/simdlib/Simd/SimdCpu.h | 0 3rdparty/simdlib/Simd/SimdDefs.h | 0 3rdparty/simdlib/Simd/SimdEnable.h | 0 3rdparty/simdlib/Simd/SimdExp.h | 0 3rdparty/simdlib/Simd/SimdExtract.h | 0 3rdparty/simdlib/Simd/SimdFrame.hpp | 0 3rdparty/simdlib/Simd/SimdInit.h | 0 3rdparty/simdlib/Simd/SimdLib.cpp | 0 3rdparty/simdlib/Simd/SimdLib.h | 0 3rdparty/simdlib/Simd/SimdLib.hpp | 0 3rdparty/simdlib/Simd/SimdLoad.h | 0 3rdparty/simdlib/Simd/SimdLoadBlock.h | 0 3rdparty/simdlib/Simd/SimdLog.h | 0 3rdparty/simdlib/Simd/SimdMath.h | 0 3rdparty/simdlib/Simd/SimdMemory.h | 0 3rdparty/simdlib/Simd/SimdNeon.h | 0 3rdparty/simdlib/Simd/SimdNeonBgrToBgra.cpp | 0 3rdparty/simdlib/Simd/SimdNeonBgrToGray.cpp | 0 3rdparty/simdlib/Simd/SimdNeonBgrToRgb.cpp | 0 3rdparty/simdlib/Simd/SimdNeonBgraToBgr.cpp | 0 3rdparty/simdlib/Simd/SimdNeonBgraToGray.cpp | 0 .../simdlib/Simd/SimdNeonDeinterleave.cpp | 0 .../simdlib/Simd/SimdNeonGaussianBlur.cpp | 0 3rdparty/simdlib/Simd/SimdNeonResizer.cpp | 0 3rdparty/simdlib/Simd/SimdPixel.hpp | 0 3rdparty/simdlib/Simd/SimdPow.h | 0 3rdparty/simdlib/Simd/SimdResizer.h | 0 3rdparty/simdlib/Simd/SimdResizerCommon.h | 0 3rdparty/simdlib/Simd/SimdRuntime.h | 0 3rdparty/simdlib/Simd/SimdSet.h | 0 3rdparty/simdlib/Simd/SimdSse41.h | 0 3rdparty/simdlib/Simd/SimdSse41BgrToBgra.cpp | 0 3rdparty/simdlib/Simd/SimdSse41BgrToGray.cpp | 0 3rdparty/simdlib/Simd/SimdSse41BgrToRgb.cpp | 0 3rdparty/simdlib/Simd/SimdSse41BgraToBgr.cpp | 0 3rdparty/simdlib/Simd/SimdSse41Cpu.cpp | 0 .../simdlib/Simd/SimdSse41GaussianBlur.cpp | 0 3rdparty/simdlib/Simd/SimdSse41GrayToBgr.cpp | 0 3rdparty/simdlib/Simd/SimdSse41Reduce.cpp | 0 .../simdlib/Simd/SimdSse41ReduceGray2x2.cpp | 0 .../simdlib/Simd/SimdSse41ReduceGray4x4.cpp | 0 .../simdlib/Simd/SimdSse41ResizeBilinear.cpp | 0 3rdparty/simdlib/Simd/SimdSse41Resizer.cpp | 0 3rdparty/simdlib/Simd/SimdStore.h | 0 3rdparty/simdlib/Simd/SimdStream.h | 0 3rdparty/simdlib/Simd/SimdUpdate.h | 0 3rdparty/simdlib/Simd/SimdView.hpp | 0 CMakeLists.txt | 17 +- .../hand_eye_calibration_show_extrinsics.py | 0 cmake/templates/visp-config.bat.in | 0 cmake/templates/visp-config.in | 0 cmake/templates/visp-config.install.in | 0 cmake/templates/vpConfig.h.in | 2 +- doc/image/tutorial/started/img-monkey-win.jpg | Bin .../visual-servo/img-bebop2-coord-system.png | Bin .../camera_calibration_show_extrinsics.py | 0 example/device/framegrabber/CMakeLists.txt | 2 - example/device/framegrabber/grabRealSense.cpp | 259 -------- .../device/framegrabber/grabRealSense2.cpp | 13 +- .../framegrabber/grabV4l2MultiCpp11Thread.cpp | 2 +- .../device/framegrabber/readRealSenseData.cpp | 44 +- .../device/framegrabber/saveRealSenseData.cpp | 76 +-- .../device/laserscanner/SickLDMRS-Process.cpp | 101 ++- example/moments/image/servoMomentImage.cpp | 19 +- example/moments/points/servoMomentPoints.cpp | 19 +- .../moments/polygon/servoMomentPolygon.cpp | 19 +- .../servoSimuAfma6FourPoints2DCamVelocity.cpp | 5 +- ...rvoSimuViper850FourPoints2DCamVelocity.cpp | 10 +- example/servo-pixhawk/sendMocapToPixhawk.cpp | 2 +- .../servoPtu46Point2DArtVelocity.cpp | 2 +- modules/ar/src/coin-simulator/vpSimulator.cpp | 77 +-- modules/core/include/visp3/core/vpImage.h | 38 +- .../core/include/visp3/core/vpImageTools.h | 67 +- modules/core/include/visp3/core/vpMutex.h | 5 +- modules/core/include/visp3/core/vpThread.h | 6 +- modules/core/src/tools/convert/vpConvert.cpp | 31 +- .../core/src/tools/histogram/vpHistogram.cpp | 18 +- .../src/tools/histogram/vpHistogramPeak.cpp | 4 +- modules/core/src/tools/xml/vpXmlParser.cpp | 12 +- .../perfColorConversion.cpp | 2 +- .../image-with-dataset/perfImageResize.cpp | 2 +- .../testColorConversion.cpp | 107 ++-- .../image-with-dataset/testUndistortImage.cpp | 34 +- .../histogram-with-dataset/testHistogram.cpp | 16 +- .../core/test/tools/threading/testMutex.cpp | 98 --- .../core/test/tools/threading/testThread.cpp | 137 ---- .../core/test/tools/threading/testThread2.cpp | 205 ------ .../detection/src/dnn/vpDetectorDNNOpenCV.cpp | 3 +- modules/detection/src/face/vpDetectorFace.cpp | 7 +- .../visp3/gui/vpColorBlindFriendlyPalette.h | 0 modules/gui/include/visp3/gui/vpPclViewer.h | 4 +- modules/gui/src/display/vpDisplayGTK.cpp | 3 +- modules/gui/src/display/vpDisplayOpenCV.cpp | 3 +- modules/gui/src/display/vpDisplayX.cpp | 3 +- .../gui/src/display/windows/vpD3DRenderer.cpp | 3 +- .../gui/src/display/windows/vpDisplayD3D.cpp | 3 +- .../gui/src/display/windows/vpDisplayGDI.cpp | 3 +- .../src/display/windows/vpDisplayWin32.cpp | 3 +- .../gui/src/display/windows/vpGDIRenderer.cpp | 3 +- .../gui/src/display/windows/vpWin32API.cpp | 7 +- .../gui/src/display/windows/vpWin32Window.cpp | 25 +- modules/gui/src/plot/vpPlotCurve.cpp | 16 +- modules/gui/src/plot/vpPlotGraph.cpp | 3 +- .../vpColorBlindFriendlyPalette.cpp | 0 modules/gui/src/pointcloud/vpPclViewer.cpp | 5 +- modules/io/include/visp3/io/vpImageQueue.h | 2 +- .../include/visp3/io/vpImageStorageWorker.h | 2 +- .../io/src/parallel-port/vpParallelPort.cpp | 5 +- .../image-with-dataset/perfImageLoadSave.cpp | 2 +- .../image-with-dataset/testImageLoadSave.cpp | 2 +- modules/java/generator/gen2.py | 0 modules/java/generator/gen_java.py | 0 modules/java/generator/hdr_parser.py | 0 modules/robot/include/visp3/robot/vpPololu.h | 2 +- .../robot/include/visp3/robot/vpQbDevice.h | 2 +- .../robot/include/visp3/robot/vpQbSoftHand.h | 2 +- .../robot/include/visp3/robot/vpRobotBebop2.h | 2 +- .../include/visp3/robot/vpRobotBiclops.h | 2 +- .../robot/include/visp3/robot/vpRobotFranka.h | 2 +- .../robot/include/visp3/robot/vpRobotMavsdk.h | 3 +- .../include/visp3/robot/vpRobotPololuPtu.h | 2 +- .../visp3/robot/vpRobotWireFrameSimulator.h | 67 +- .../include/visp3/robot/vpSimulatorAfma6.h | 2 +- .../include/visp3/robot/vpSimulatorViper850.h | 2 +- .../src/haptic-device/qbdevice/vpQbDevice.cpp | 2 +- .../haptic-device/qbdevice/vpQbSoftHand.cpp | 2 +- modules/robot/src/light/vpRingLight.cpp | 5 +- .../src/real-robot/afma4/vpRobotAfma4.cpp | 3 +- .../src/real-robot/afma6/vpRobotAfma6.cpp | 66 +- .../src/real-robot/biclops/vpRobotBiclops.cpp | 5 +- .../src/real-robot/franka/vpRobotFranka.cpp | 2 +- .../src/real-robot/mavsdk/vpRobotMavsdk.cpp | 6 +- .../src/real-robot/pioneer/vpRobotPioneer.cpp | 17 +- .../real-robot/pololu-maestro/vpPololu.cpp | 2 +- .../pololu-maestro/vpRobotPololuPtu.cpp | 3 +- .../src/real-robot/ptu46/vpRobotPtu46.cpp | 3 +- .../vpRobotUniversalRobots.cpp | 3 +- .../src/robot-simulator/vpRobotCamera.cpp | 3 +- .../vpRobotWireFrameSimulator.cpp | 22 +- .../src/robot-simulator/vpSimulatorAfma6.cpp | 114 ++-- .../robot-simulator/vpSimulatorViper850.cpp | 115 ++-- .../testPixhawkDroneVelocityControl.cpp | 3 +- .../testPixhawkRoverVelocityControl.cpp | 3 +- .../test/servo-pololu/testPololuPosition.cpp | 2 +- .../test/servo-pololu/testPololuVelocity.cpp | 2 +- modules/sensor/CMakeLists.txt | 2 - .../sensor/vpForceTorqueAtiNetFTSensor.h | 0 .../visp3/sensor/vpForceTorqueIitSensor.h | 2 +- .../sensor/include/visp3/sensor/vpKinect.h | 8 +- .../visp3/sensor/vpOccipitalStructure.h | 2 +- modules/sensor/src/force-torque/vpComedi.cpp | 10 +- .../force-torque/vpForceTorqueIitSensor.cpp | 2 +- .../src/framegrabber/v4l2/vpV4l2Grabber.cpp | 29 +- .../sensor/src/rgb-depth/kinect/vpKinect.cpp | 11 +- .../vpOccipitalStructure.cpp | 2 +- .../src/rgb-depth/realsense/vpRealSense.cpp | 3 +- .../src/rgb-depth/realsense/vpRealSense2.cpp | 3 +- .../rgb-depth/realsense/vpRealSense_impl.h | 2 +- .../test/force-torque/testForceTorqueAti.cpp | 48 +- .../testForceTorqueAtiNetFTSensor.cpp | 0 .../sensor/test/mocap/testMocapQualisys.cpp | 2 +- modules/sensor/test/mocap/testMocapVicon.cpp | 2 +- .../rgb-depth/testRealSense2_D435_pcl.cpp | 2 +- .../test/rgb-depth/testRealSense2_SR300.cpp | 3 +- .../testRealSense2_T265_images_odometry.cpp | 4 +- ...tRealSense2_T265_images_odometry_async.cpp | 4 +- .../test/rgb-depth/testRealSense_R200.cpp | 592 ------------------ .../test/rgb-depth/testRealSense_SR300.cpp | 526 ---------------- .../include/visp3/dnn_tracker/vpMegaPose.h | 2 +- .../visp3/dnn_tracker/vpMegaPoseTracker.h | 4 +- modules/tracker/dnn/src/vpMegaPose.cpp | 58 +- modules/tracker/dnn/src/vpMegaPoseTracker.cpp | 9 + modules/tracker/klt/src/vpKltOpencv.cpp | 23 +- .../include/visp3/mbt/vpMbtTukeyEstimator.h | 0 .../tracker/mbt/src/klt/vpMbKltTracker.cpp | 3 +- modules/tracker/mbt/src/vpMbTracker.cpp | 20 +- .../testGenericTrackerDeterminist.cpp | 2 +- .../tt_mi/src/mi/vpTemplateTrackerMI.cpp | 14 +- .../src/pose-estimation/vpPoseRansac.cpp | 8 +- platforms/android/build_sdk.py | 0 script/make-coverage-report.sh | 0 .../tutorial-face-detector-live-threaded.cpp | 116 ++-- tutorial/grabber/tutorial-grabber-1394.cpp | 2 +- .../grabber/tutorial-grabber-basler-pylon.cpp | 2 +- tutorial/grabber/tutorial-grabber-bebop2.cpp | 2 +- .../grabber/tutorial-grabber-flycapture.cpp | 2 +- .../grabber/tutorial-grabber-ids-ueye.cpp | 4 +- .../tutorial-grabber-opencv-threaded.cpp | 61 +- tutorial/grabber/tutorial-grabber-opencv.cpp | 2 +- .../tutorial-grabber-realsense-T265.cpp | 3 +- .../grabber/tutorial-grabber-realsense.cpp | 2 +- .../tutorial-grabber-structure-core.cpp | 2 +- .../tutorial-grabber-v4l2-threaded.cpp | 60 +- tutorial/grabber/tutorial-grabber-v4l2.cpp | 2 +- .../VispHelper/ImageConversion.h | 0 .../VispHelper/ImageConversion.mm | 0 .../VispHelper/ImageDisplay.h | 0 .../VispHelper/ImageDisplay.mm | 0 .../robot/mbot/raspberry/daemon/visual-servo | 0 ...l-megapose-live-single-object-tracking.cpp | 3 +- .../tutorial-mb-generic-tracker-read.cpp | 0 .../tutorial-mb-generic-tracker-save.cpp | 0 ...torial-ibvs-4pts-wireframe-robot-afma6.cpp | 2 +- ...torial-ibvs-4pts-wireframe-robot-viper.cpp | 2 +- 241 files changed, 900 insertions(+), 2820 deletions(-) mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAlignment.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAllocator.hpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdArray.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx1.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx1Cpu.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx1Resizer.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2BgrToBgra.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2BgrToGray.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2BgrToRgb.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2BgraToBgr.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2BgraToGray.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2Cpu.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2Deinterleave.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2GaussianBlur.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2Reduce.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2ReduceGray2x2.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2ReduceGray3x3.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2ReduceGray4x4.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2ReduceGray5x5.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2ResizeBilinear.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdAvx2Resizer.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBase.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBaseBgrToBgra.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBaseBgrToGray.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBaseBgrToRgb.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBaseBgraToBgr.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBaseBgraToGray.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBaseCpu.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBaseDeinterleave.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBaseGaussianBlur.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdBaseResizer.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdConfig.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdConst.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdConversion.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdCopyPixel.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdCpu.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdDefs.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdEnable.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdExp.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdExtract.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdFrame.hpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdInit.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdLib.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdLib.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdLib.hpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdLoad.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdLoadBlock.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdLog.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdMath.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdMemory.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdNeon.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdNeonBgrToBgra.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdNeonBgrToGray.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdNeonBgrToRgb.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdNeonBgraToBgr.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdNeonBgraToGray.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdNeonDeinterleave.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdNeonGaussianBlur.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdNeonResizer.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdPixel.hpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdPow.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdResizer.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdResizerCommon.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdRuntime.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSet.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41BgrToBgra.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41BgrToGray.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41BgrToRgb.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41BgraToBgr.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41Cpu.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41GaussianBlur.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41GrayToBgr.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41Reduce.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41ReduceGray2x2.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41ReduceGray4x4.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41ResizeBilinear.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdSse41Resizer.cpp mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdStore.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdStream.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdUpdate.h mode change 100755 => 100644 3rdparty/simdlib/Simd/SimdView.hpp mode change 100755 => 100644 apps/calibration/hand_eye_calibration_show_extrinsics.py mode change 100755 => 100644 cmake/templates/visp-config.bat.in mode change 100755 => 100644 cmake/templates/visp-config.in mode change 100755 => 100644 cmake/templates/visp-config.install.in mode change 100755 => 100644 doc/image/tutorial/started/img-monkey-win.jpg mode change 100755 => 100644 doc/image/tutorial/visual-servo/img-bebop2-coord-system.png mode change 100755 => 100644 example/calibration/camera_calibration_show_extrinsics.py delete mode 100644 example/device/framegrabber/grabRealSense.cpp delete mode 100644 modules/core/test/tools/threading/testMutex.cpp delete mode 100644 modules/core/test/tools/threading/testThread.cpp delete mode 100644 modules/core/test/tools/threading/testThread2.cpp mode change 100755 => 100644 modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h mode change 100755 => 100644 modules/gui/include/visp3/gui/vpPclViewer.h mode change 100755 => 100644 modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp mode change 100755 => 100644 modules/gui/src/pointcloud/vpPclViewer.cpp mode change 100755 => 100644 modules/java/generator/gen2.py mode change 100755 => 100644 modules/java/generator/gen_java.py mode change 100755 => 100644 modules/java/generator/hdr_parser.py mode change 100755 => 100644 modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h mode change 100755 => 100644 modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp delete mode 100644 modules/sensor/test/rgb-depth/testRealSense_R200.cpp delete mode 100644 modules/sensor/test/rgb-depth/testRealSense_SR300.cpp mode change 100755 => 100644 modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h mode change 100755 => 100644 platforms/android/build_sdk.py mode change 100755 => 100644 script/make-coverage-report.sh mode change 100755 => 100644 tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.h mode change 100755 => 100644 tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.mm mode change 100755 => 100644 tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.h mode change 100755 => 100644 tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.mm mode change 100755 => 100644 tutorial/robot/mbot/raspberry/daemon/visual-servo mode change 100755 => 100644 tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp mode change 100755 => 100644 tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp diff --git a/.vscode/settings.json b/.vscode/settings.json index 8536ebc9b7..fdb73f9c6c 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -117,7 +117,27 @@ "stop_token": "cpp", "view": "cpp", "mixinvector": "cpp", - "charconv": "cpp" + "charconv": "cpp", + "coroutine": "cpp", + "resumable": "cpp", + "format": "cpp", + "ranges": "cpp", + "span": "cpp", + "xfacet": "cpp", + "xhash": "cpp", + "xiosbase": "cpp", + "xlocale": "cpp", + "xlocbuf": "cpp", + "xlocinfo": "cpp", + "xlocmes": "cpp", + "xlocmon": "cpp", + "xlocnum": "cpp", + "xloctime": "cpp", + "xmemory": "cpp", + "xstring": "cpp", + "xtr1common": "cpp", + "xtree": "cpp", + "xutility": "cpp" }, "C_Cpp.vcFormat.indent.namespaceContents": false, "editor.formatOnSave": true, diff --git a/3rdparty/simdlib/Simd/SimdAlignment.h b/3rdparty/simdlib/Simd/SimdAlignment.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAllocator.hpp b/3rdparty/simdlib/Simd/SimdAllocator.hpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdArray.h b/3rdparty/simdlib/Simd/SimdArray.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx1.h b/3rdparty/simdlib/Simd/SimdAvx1.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx1Cpu.cpp b/3rdparty/simdlib/Simd/SimdAvx1Cpu.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx1Resizer.cpp b/3rdparty/simdlib/Simd/SimdAvx1Resizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2.h b/3rdparty/simdlib/Simd/SimdAvx2.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgrToBgra.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgrToBgra.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgrToGray.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgrToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgrToRgb.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgrToRgb.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgraToBgr.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgraToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2BgraToGray.cpp b/3rdparty/simdlib/Simd/SimdAvx2BgraToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2Cpu.cpp b/3rdparty/simdlib/Simd/SimdAvx2Cpu.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2Deinterleave.cpp b/3rdparty/simdlib/Simd/SimdAvx2Deinterleave.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2GaussianBlur.cpp b/3rdparty/simdlib/Simd/SimdAvx2GaussianBlur.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2Reduce.cpp b/3rdparty/simdlib/Simd/SimdAvx2Reduce.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ReduceGray2x2.cpp b/3rdparty/simdlib/Simd/SimdAvx2ReduceGray2x2.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ReduceGray3x3.cpp b/3rdparty/simdlib/Simd/SimdAvx2ReduceGray3x3.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ReduceGray4x4.cpp b/3rdparty/simdlib/Simd/SimdAvx2ReduceGray4x4.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ReduceGray5x5.cpp b/3rdparty/simdlib/Simd/SimdAvx2ReduceGray5x5.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2ResizeBilinear.cpp b/3rdparty/simdlib/Simd/SimdAvx2ResizeBilinear.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdAvx2Resizer.cpp b/3rdparty/simdlib/Simd/SimdAvx2Resizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBase.h b/3rdparty/simdlib/Simd/SimdBase.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgrToBgra.cpp b/3rdparty/simdlib/Simd/SimdBaseBgrToBgra.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgrToGray.cpp b/3rdparty/simdlib/Simd/SimdBaseBgrToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgrToRgb.cpp b/3rdparty/simdlib/Simd/SimdBaseBgrToRgb.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgraToBgr.cpp b/3rdparty/simdlib/Simd/SimdBaseBgraToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseBgraToGray.cpp b/3rdparty/simdlib/Simd/SimdBaseBgraToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseCpu.cpp b/3rdparty/simdlib/Simd/SimdBaseCpu.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseDeinterleave.cpp b/3rdparty/simdlib/Simd/SimdBaseDeinterleave.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseGaussianBlur.cpp b/3rdparty/simdlib/Simd/SimdBaseGaussianBlur.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdBaseResizer.cpp b/3rdparty/simdlib/Simd/SimdBaseResizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdConfig.h b/3rdparty/simdlib/Simd/SimdConfig.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdConst.h b/3rdparty/simdlib/Simd/SimdConst.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdConversion.h b/3rdparty/simdlib/Simd/SimdConversion.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdCopyPixel.h b/3rdparty/simdlib/Simd/SimdCopyPixel.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdCpu.h b/3rdparty/simdlib/Simd/SimdCpu.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdDefs.h b/3rdparty/simdlib/Simd/SimdDefs.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdEnable.h b/3rdparty/simdlib/Simd/SimdEnable.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdExp.h b/3rdparty/simdlib/Simd/SimdExp.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdExtract.h b/3rdparty/simdlib/Simd/SimdExtract.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdFrame.hpp b/3rdparty/simdlib/Simd/SimdFrame.hpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdInit.h b/3rdparty/simdlib/Simd/SimdInit.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLib.cpp b/3rdparty/simdlib/Simd/SimdLib.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLib.h b/3rdparty/simdlib/Simd/SimdLib.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLib.hpp b/3rdparty/simdlib/Simd/SimdLib.hpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLoad.h b/3rdparty/simdlib/Simd/SimdLoad.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLoadBlock.h b/3rdparty/simdlib/Simd/SimdLoadBlock.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdLog.h b/3rdparty/simdlib/Simd/SimdLog.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdMath.h b/3rdparty/simdlib/Simd/SimdMath.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdMemory.h b/3rdparty/simdlib/Simd/SimdMemory.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeon.h b/3rdparty/simdlib/Simd/SimdNeon.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgrToBgra.cpp b/3rdparty/simdlib/Simd/SimdNeonBgrToBgra.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgrToGray.cpp b/3rdparty/simdlib/Simd/SimdNeonBgrToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgrToRgb.cpp b/3rdparty/simdlib/Simd/SimdNeonBgrToRgb.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgraToBgr.cpp b/3rdparty/simdlib/Simd/SimdNeonBgraToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonBgraToGray.cpp b/3rdparty/simdlib/Simd/SimdNeonBgraToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonDeinterleave.cpp b/3rdparty/simdlib/Simd/SimdNeonDeinterleave.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonGaussianBlur.cpp b/3rdparty/simdlib/Simd/SimdNeonGaussianBlur.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdNeonResizer.cpp b/3rdparty/simdlib/Simd/SimdNeonResizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdPixel.hpp b/3rdparty/simdlib/Simd/SimdPixel.hpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdPow.h b/3rdparty/simdlib/Simd/SimdPow.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdResizer.h b/3rdparty/simdlib/Simd/SimdResizer.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdResizerCommon.h b/3rdparty/simdlib/Simd/SimdResizerCommon.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdRuntime.h b/3rdparty/simdlib/Simd/SimdRuntime.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSet.h b/3rdparty/simdlib/Simd/SimdSet.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41.h b/3rdparty/simdlib/Simd/SimdSse41.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41BgrToBgra.cpp b/3rdparty/simdlib/Simd/SimdSse41BgrToBgra.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41BgrToGray.cpp b/3rdparty/simdlib/Simd/SimdSse41BgrToGray.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41BgrToRgb.cpp b/3rdparty/simdlib/Simd/SimdSse41BgrToRgb.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41BgraToBgr.cpp b/3rdparty/simdlib/Simd/SimdSse41BgraToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41Cpu.cpp b/3rdparty/simdlib/Simd/SimdSse41Cpu.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41GaussianBlur.cpp b/3rdparty/simdlib/Simd/SimdSse41GaussianBlur.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41GrayToBgr.cpp b/3rdparty/simdlib/Simd/SimdSse41GrayToBgr.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41Reduce.cpp b/3rdparty/simdlib/Simd/SimdSse41Reduce.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41ReduceGray2x2.cpp b/3rdparty/simdlib/Simd/SimdSse41ReduceGray2x2.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41ReduceGray4x4.cpp b/3rdparty/simdlib/Simd/SimdSse41ReduceGray4x4.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41ResizeBilinear.cpp b/3rdparty/simdlib/Simd/SimdSse41ResizeBilinear.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdSse41Resizer.cpp b/3rdparty/simdlib/Simd/SimdSse41Resizer.cpp old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdStore.h b/3rdparty/simdlib/Simd/SimdStore.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdStream.h b/3rdparty/simdlib/Simd/SimdStream.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdUpdate.h b/3rdparty/simdlib/Simd/SimdUpdate.h old mode 100755 new mode 100644 diff --git a/3rdparty/simdlib/Simd/SimdView.hpp b/3rdparty/simdlib/Simd/SimdView.hpp old mode 100755 new mode 100644 diff --git a/CMakeLists.txt b/CMakeLists.txt index 18f9b81221..c6219b9913 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -586,17 +586,7 @@ if(SOQT_FOUND) # SoQt < 1.6.0 that depends on Qt4 was found. We need an explicit VP_OPTION(USE_QT Qt "" "Include Coin/SoQt/Qt support" "" ON IF USE_SOQT AND NOT WINRT AND NOT IOS) endif() VP_OPTION(USE_SOXT SOXT "" "Include Coin/SoXt support" "" OFF IF USE_COIN3D AND NOT WINRT AND NOT IOS) -set(THREADS_PREFER_PTHREAD_FLAG ON) -VP_OPTION(USE_THREADS Threads "" "Include std::thread support" "" ON IF NOT (WIN32 OR MINGW)) - -# We need threads. To be changed to make threads optional -if(NOT USE_THREADS) - if(Threads_FOUND) - message(WARNING "We need std::thread. We turn USE_THREADS=ON.") - unset(USE_THREADS) - set(USE_THREADS ON CACHE BOOL "Include std::thread support" FORCE) - endif() -endif() +VP_OPTION(USE_THREADS Threads "" "Include std::thread support" "" ON) VP_OPTION(USE_XML2 XML2 "" "Include libxml2 support" "" ON IF NOT WINRT) if(CMAKE_TOOLCHAIN_FILE) @@ -613,7 +603,7 @@ VP_OPTION(USE_X11 X11 "" "Include X11 support" "${X1 VP_OPTION(USE_GTK2 MyGTK2 "" "Include gtk2 support" "" OFF IF NOT WINRT AND NOT IOS) VP_OPTION(USE_JPEG "JPEG;MyJPEG" "" "Include jpeg support" "" ON IF NOT IOS) VP_OPTION(USE_PNG "PNG;MyPNG" "" "Include png support" "" ON IF NOT IOS) -# To control Pioneer mobile robots, under UNIX we need Aria, pthread, rt and dl 3rd party libraries +# To control Pioneer mobile robots, under UNIX we need Aria and std::threads, rt and dl 3rd party libraries VP_OPTION(USE_ARIA ARIA "" "Include aria support" "" ON IF NOT WINRT AND NOT IOS) #VP_OPTION(USE_RT RT "" "Include rt support" "" ON) #VP_OPTION(USE_DL DL "" "Include dl support" "" ON) @@ -624,7 +614,6 @@ VP_OPTION(USE_PCL PCL QUIET "Include Point Cloud Library suppor VP_OPTION(USE_TENSORRT TensorRT "" "Include TensorRT support" "" ON IF NOT WINRT AND NOT IOS) VP_OPTION(USE_NLOHMANN_JSON nlohmann_json QUIET "Include nlohmann json support" "" ON) -# Upgrade c++ standard to 14 for pcl 1.9.1.99 that enables by default c++ 14 standard if(USE_PCL) # PCL is used in modules gui, sensor and mbt. # In these modules we cannot directly use PCL_INCLUDE_DIRS and PCL_LIBRARIES using: @@ -705,7 +694,7 @@ endif() # ---------------------------------------------------------------------------- # Build-in 3rd parties. Should be after c++ standard potential modification # ---------------------------------------------------------------------------- -VP_OPTION(WITH_PTHREAD "" "" "Build pthread as built-in library" "" ON IF (NOT USE_THREADS) AND (WIN32 OR MINGW) AND (NOT WINRT)) +VP_OPTION(WITH_PTHREAD "" "" "Build pthread as built-in library" "" ON IF (WIN32 OR MINGW) AND (NOT WINRT)) # Since C99 is not supported by MSVC 2010 or prior, we disable apriltag if MSVC < 2012 VP_OPTION(WITH_APRILTAG "" "" "Build AprilTag as built-in library" "" ON IF (USE_THREADS OR WITH_PTHREAD) AND (NOT WINRT) AND (NOT MSVC_VERSION LESS 1700)) VP_OPTION(WITH_APRILTAG_BIG_FAMILY "" "" "Build AprilTag big family (41h12, 48h12, 49h12, 52h13)" "" OFF IF WITH_APRILTAG) diff --git a/apps/calibration/hand_eye_calibration_show_extrinsics.py b/apps/calibration/hand_eye_calibration_show_extrinsics.py old mode 100755 new mode 100644 diff --git a/cmake/templates/visp-config.bat.in b/cmake/templates/visp-config.bat.in old mode 100755 new mode 100644 diff --git a/cmake/templates/visp-config.in b/cmake/templates/visp-config.in old mode 100755 new mode 100644 diff --git a/cmake/templates/visp-config.install.in b/cmake/templates/visp-config.install.in old mode 100755 new mode 100644 diff --git a/cmake/templates/vpConfig.h.in b/cmake/templates/vpConfig.h.in index 45d8918a21..807d5db374 100644 --- a/cmake/templates/vpConfig.h.in +++ b/cmake/templates/vpConfig.h.in @@ -146,7 +146,7 @@ // Defined if XML2 library available. #cmakedefine VISP_HAVE_XML2 -// Defined if pthread library available. +// Defined if pthread library available (deprecated). #cmakedefine VISP_HAVE_PTHREAD // Defined if std::thread available. diff --git a/doc/image/tutorial/started/img-monkey-win.jpg b/doc/image/tutorial/started/img-monkey-win.jpg old mode 100755 new mode 100644 diff --git a/doc/image/tutorial/visual-servo/img-bebop2-coord-system.png b/doc/image/tutorial/visual-servo/img-bebop2-coord-system.png old mode 100755 new mode 100644 diff --git a/example/calibration/camera_calibration_show_extrinsics.py b/example/calibration/camera_calibration_show_extrinsics.py old mode 100755 new mode 100644 diff --git a/example/device/framegrabber/CMakeLists.txt b/example/device/framegrabber/CMakeLists.txt index 4879b1fabf..535c4e9d80 100644 --- a/example/device/framegrabber/CMakeLists.txt +++ b/example/device/framegrabber/CMakeLists.txt @@ -48,7 +48,6 @@ set(example_cpp grabDirectShow.cpp grabDirectShowMulti.cpp grabFlyCapture.cpp - grabRealSense.cpp grabRealSense2.cpp grabRealSense2_T265.cpp grabV4l2MultiCpp11Thread.cpp @@ -83,7 +82,6 @@ if(VISP_HAVE_REALSENSE OR VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") visp_set_source_file_compile_flag(getRealSense2Info.cpp ${CXX_FLAGS_MUTE_WARNINGS}) - visp_set_source_file_compile_flag(grabRealSense.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(grabRealSense2.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(grabRealSense2_T265.cpp ${CXX_FLAGS_MUTE_WARNINGS}) visp_set_source_file_compile_flag(readRealSenseData.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/example/device/framegrabber/grabRealSense.cpp b/example/device/framegrabber/grabRealSense.cpp deleted file mode 100644 index 1c5a6bcc99..0000000000 --- a/example/device/framegrabber/grabRealSense.cpp +++ /dev/null @@ -1,259 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. - * - * This software is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * See the file LICENSE.txt at the root directory of this source - * distribution for additional information about the GNU GPL. - * - * For using ViSP with software that can not be combined with the GNU - * GPL, please contact Inria about acquiring a ViSP Professional - * Edition License. - * - * See https://visp.inria.fr for more information. - * - * This software was developed at: - * Inria Rennes - Bretagne Atlantique - * Campus Universitaire de Beaulieu - * 35042 Rennes Cedex - * France - * - * If you have questions regarding the use of this file, please contact - * Inria at visp@inria.fr - * - * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE - * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * - * Description: - * Test RealSense RGB-D sensor. - * -*****************************************************************************/ - -/*! - \example grabRealSense.cpp - This example shows how to retrieve data from a RealSense RGB-D sensor. - -*/ - -#include - -#include -#include -#include -#include -#include -#include - -#if defined(VISP_HAVE_REALSENSE) - -// Using a thread to display the pointcloud with PCL produces a segfault on -// OSX -#if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX -#if (defined(VISP_HAVE_PTHREAD) || defined(_WIN32)) // Threading available -#define USE_THREAD -#endif -#endif - -#ifdef VISP_HAVE_PCL -#include -#include -#endif - -#ifdef VISP_HAVE_PCL -#ifdef USE_THREAD -// Shared vars -typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; -t_CaptureState s_capture_state = capture_waiting; -vpMutex s_mutex_capture; - -vpThread::Return displayPointcloudFunction(vpThread::Args args) -{ - pcl::PointCloud::Ptr pointcloud_ = *((pcl::PointCloud::Ptr *)args); - - pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer")); - pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud_); - viewer->setBackgroundColor(0, 0, 0); - viewer->initCameraParameters(); - viewer->setPosition(640 + 80, 480 + 80); - viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0); - viewer->setSize(640, 480); - - t_CaptureState capture_state_; - - do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); - - if (capture_state_ == capture_started) { - static bool update = false; - if (!update) { - viewer->addPointCloud(pointcloud_, rgb, "sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); - update = true; - } - else { - viewer->updatePointCloud(pointcloud_, rgb, "sample cloud"); - } - - viewer->spinOnce(10); - } - } while (capture_state_ != capture_stopped); - - std::cout << "End of point cloud display thread" << std::endl; - return EXIT_SUCCESS; -} -#endif -#endif -#endif - -int main() -{ -#if defined(VISP_HAVE_REALSENSE) - try { - vpRealSense rs; - rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30)); - rs.open(); - - std::cout << rs.getCameraParameters(rs::stream::color, vpCameraParameters::perspectiveProjWithoutDistortion) - << std::endl; - std::cout << rs.getCameraParameters(rs::stream::color, vpCameraParameters::perspectiveProjWithDistortion) - << std::endl; - std::cout << "Extrinsics cMd: \n" << rs.getTransformation(rs::stream::color, rs::stream::depth) << std::endl; - std::cout << "Extrinsics dMc: \n" << rs.getTransformation(rs::stream::depth, rs::stream::color) << std::endl; - std::cout << "Extrinsics cMi: \n" << rs.getTransformation(rs::stream::color, rs::stream::infrared) << std::endl; - std::cout << "Extrinsics dMi: \n" << rs.getTransformation(rs::stream::depth, rs::stream::infrared) << std::endl; - - vpImage color((unsigned int)rs.getIntrinsics(rs::stream::color).height, - (unsigned int)rs.getIntrinsics(rs::stream::color).width); - - vpImage infrared_display((unsigned int)rs.getIntrinsics(rs::stream::infrared).height, - (unsigned int)rs.getIntrinsics(rs::stream::infrared).width); - vpImage infrared_y16; - rs::device *dev = rs.getHandler(); - bool use_infrared_y16 = dev->get_stream_format(rs::stream::infrared) == rs::format::y16; - - vpImage depth_display((unsigned int)rs.getIntrinsics(rs::stream::depth).height, - (unsigned int)rs.getIntrinsics(rs::stream::depth).width); - vpImage depth(depth_display.getHeight(), depth_display.getWidth()); - -#ifdef VISP_HAVE_PCL - pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud); - -#ifdef USE_THREAD - vpThread thread_display_pointcloud(displayPointcloudFunction, (vpThread::Args)&pointcloud); -#else - pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer")); - pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud); - viewer->setBackgroundColor(0, 0, 0); - viewer->addCoordinateSystem(1.0); - viewer->initCameraParameters(); - viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0); -#endif - -#else - std::vector pointcloud; -#endif - -#if defined(VISP_HAVE_X11) - vpDisplayX dc(color, 10, 10, "Color image"); - vpDisplayX di(infrared_display, (int)color.getWidth() + 80, 10, "Infrared image"); - vpDisplayX dd(depth_display, 10, (int)color.getHeight() + 80, "Depth image"); -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI dc(color, 10, 10, "Color image"); - vpDisplayGDI di(infrared_display, color.getWidth() + 80, 10, "Infrared image"); - vpDisplayGDI dd(depth_display, 10, color.getHeight() + 80, "Depth image"); -#else - std::cout << "No image viewer is available..." << std::endl; -#endif - - while (1) { - double t = vpTime::measureTimeMs(); - - if (use_infrared_y16) { - rs.acquire(color, infrared_y16, depth, pointcloud); - vpImageConvert::convert(infrared_y16, infrared_display); - } - else { -#ifdef VISP_HAVE_PCL - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)infrared_display.bitmap); -#else - rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)infrared_display.bitmap); -#endif - } - -#ifdef VISP_HAVE_PCL -#ifdef USE_THREAD - { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_started; - } -#else - static bool update = false; - if (!update) { - viewer->addPointCloud(pointcloud, rgb, "sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); - viewer->setPosition(color.getWidth() + 80, color.getHeight() + 80); - update = true; - } - else { - viewer->updatePointCloud(pointcloud, rgb, "sample cloud"); - } - - viewer->spinOnce(10); -#endif -#endif - - vpImageConvert::createDepthHistogram(depth, depth_display); - - vpDisplay::display(color); - vpDisplay::display(infrared_display); - vpDisplay::display(depth_display); - - vpDisplay::displayText(color, 15, 15, "Click to quit", vpColor::red); - if (vpDisplay::getClick(color, false) || vpDisplay::getClick(infrared_display, false) || - vpDisplay::getClick(depth_display, false)) { - break; - } - vpDisplay::flush(color); - vpDisplay::flush(infrared_display); - vpDisplay::flush(depth_display); - - std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl; - } - - std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; - -#ifdef VISP_HAVE_PCL -#ifdef USE_THREAD - { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; - } -#endif -#endif - - rs.close(); - } - catch (const vpException &e) { - std::cerr << "RealSense error " << e.what() << std::endl; - } - catch (const rs::error &e) { - std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() - << "): " << e.what() << std::endl; - } - catch (const std::exception &e) { - std::cerr << e.what() << std::endl; - } - -#elif !defined(VISP_HAVE_REALSENSE) - std::cout << "This deprecated example is only working with librealsense 1.x" << std::endl; -#endif - return EXIT_SUCCESS; -} diff --git a/example/device/framegrabber/grabRealSense2.cpp b/example/device/framegrabber/grabRealSense2.cpp index 6d2b7a4bdd..19f3f5bd15 100644 --- a/example/device/framegrabber/grabRealSense2.cpp +++ b/example/device/framegrabber/grabRealSense2.cpp @@ -44,10 +44,9 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ - && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) -#ifdef VISP_HAVE_PCL +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) #include #include @@ -180,7 +179,7 @@ int main() (unsigned int)rs.getIntrinsics(RS2_STREAM_DEPTH).width); vpImage depth(depth_display.getHeight(), depth_display.getWidth()); -#ifdef VISP_HAVE_PCL +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) std::mutex mutex; ViewerWorker viewer(true, mutex); std::thread viewer_thread(&ViewerWorker::run, &viewer); @@ -199,7 +198,7 @@ int main() while (true) { double t = vpTime::measureTimeMs(); -#ifdef VISP_HAVE_PCL +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) { std::lock_guard lock(mutex); rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, @@ -230,7 +229,7 @@ int main() std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; -#ifdef VISP_HAVE_PCL +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) { std::lock_guard lock(mutex); cancelled = true; @@ -253,7 +252,7 @@ int main() int main() { #if !defined(VISP_HAVE_REALSENSE2) - std::cout << "You do not realsense2 SDK functionality enabled..." << std::endl; + std::cout << "You do not have realsense2 SDK functionality enabled..." << std::endl; std::cout << "Tip:" << std::endl; std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl; return EXIT_SUCCESS; diff --git a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp index 32fc56ae73..2f4333cc31 100644 --- a/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp +++ b/example/device/framegrabber/grabV4l2MultiCpp11Thread.cpp @@ -45,7 +45,7 @@ #include -#if defined(VISP_HAVE_V4L2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_V4L2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) && defined(VISP_HAVE_THREADS) #include #include diff --git a/example/device/framegrabber/readRealSenseData.cpp b/example/device/framegrabber/readRealSenseData.cpp index d7ad1c9336..5fe2cda11e 100644 --- a/example/device/framegrabber/readRealSenseData.cpp +++ b/example/device/framegrabber/readRealSenseData.cpp @@ -40,7 +40,7 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #include #include #include @@ -71,27 +71,27 @@ namespace void usage(const char *name, const char *badparam) { fprintf(stdout, "\n\ - Read RealSense data.\n\ - \n\ - %s\ - OPTIONS: \n\ - -i \n\ - Input directory.\n\ - \n\ - -c \n\ - Click enable.\n\ - \n\ - -b \n\ - Pointcloud is in binary format.\n\ - \n\ - -o \n\ - Save color and depth side by side to image sequence.\n\ - \n\ - -d \n\ - Display depth in color.\n\ - \n\ - -h \n\ - Print the help.\n\n", + Read RealSense data.\n\ + \n\ + %s\ + OPTIONS: \n\ + -i \n\ + Input directory.\n\ + \n\ + -c \n\ + Click enable.\n\ + \n\ + -b \n\ + Pointcloud is in binary format.\n\ + \n\ + -o \n\ + Save color and depth side by side to image sequence.\n\ + \n\ + -d \n\ + Display depth in color.\n\ + \n\ + -h \n\ + Print the help.\n\n", name); if (badparam) diff --git a/example/device/framegrabber/saveRealSenseData.cpp b/example/device/framegrabber/saveRealSenseData.cpp index e22dbe4b08..35263c266b 100644 --- a/example/device/framegrabber/saveRealSenseData.cpp +++ b/example/device/framegrabber/saveRealSenseData.cpp @@ -39,8 +39,8 @@ #include #include -#if (defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2)) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PUGIXML) +#if (defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2)) && defined(VISP_HAVE_THREADS) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PUGIXML) #include #include @@ -75,42 +75,42 @@ namespace void usage(const char *name, const char *badparam) { fprintf(stdout, "\n\ - Save RealSense data.\n\ - \n\ - %s\ - OPTIONS: \n\ - -s \n\ - Save data.\n\ - \n\ - -o \n\ - Output directory.\n\ - \n\ - -a \n\ - Use aligned streams.\n\ - \n\ - -c \n\ - Save color stream.\n\ - \n\ - -d \n\ - Save depth stream.\n\ - \n\ - -p \n\ - Save pointcloud.\n\ - \n\ - -i \n\ - Save infrared stream.\n\ - \n\ - -C \n\ - Click to save.\n\ - \n\ - -f \n\ - Set FPS.\n\ - \n\ - -b \n\ - Save point cloud in binary format.\n\ - \n\ - -h \n\ - Print the help.\n\n", + Save RealSense data.\n\ + \n\ + %s\ + OPTIONS: \n\ + -s \n\ + Save data.\n\ + \n\ + -o \n\ + Output directory.\n\ + \n\ + -a \n\ + Use aligned streams.\n\ + \n\ + -c \n\ + Save color stream.\n\ + \n\ + -d \n\ + Save depth stream.\n\ + \n\ + -p \n\ + Save pointcloud.\n\ + \n\ + -i \n\ + Save infrared stream.\n\ + \n\ + -C \n\ + Click to save.\n\ + \n\ + -f \n\ + Set FPS.\n\ + \n\ + -b \n\ + Save point cloud in binary format.\n\ + \n\ + -h \n\ + Print the help.\n\n", name); if (badparam) diff --git a/example/device/laserscanner/SickLDMRS-Process.cpp b/example/device/laserscanner/SickLDMRS-Process.cpp index dc1dac47b3..67bd4974ec 100644 --- a/example/device/laserscanner/SickLDMRS-Process.cpp +++ b/example/device/laserscanner/SickLDMRS-Process.cpp @@ -68,23 +68,20 @@ #include #include -#if (!defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__)))) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) +#if (!defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__)))) && \ + (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GTK)) && defined(VISP_HAVE_THREADS) + +#include +#include static int save = 0; static int layerToDisplay = 0xF; // 0xF = 1111 => all the layers are selected static vpLaserScan shm_laserscan[4]; double time_offset = 0; -#ifdef VISP_HAVE_PTHREAD -pthread_mutex_t shm_mutex; -#endif +std::mutex shm_mutex; std::string output_path; -void *laser_display_and_save_loop(void *); -void *laser_acq_loop(void *); -void *camera_acq_and_display_loop(void *); - -void *laser_display_and_save_loop(void *) +void laser_display_and_save_loop() { vpImage map(700, 300); map = 0; @@ -133,14 +130,11 @@ void *laser_display_and_save_loop(void *) vpDisplay::display(map); #endif -#ifdef VISP_HAVE_PTHREAD - pthread_mutex_lock(&shm_mutex); -#endif - for (int layer = 0; layer < 4; layer++) + shm_mutex.lock(); + for (int layer = 0; layer < 4; layer++) { laserscan[layer] = shm_laserscan[layer]; -#ifdef VISP_HAVE_PTHREAD - pthread_mutex_unlock(&shm_mutex); -#endif + } + shm_mutex.unlock(); // Parse the four layers for (int layer = 0; layer < 4; layer++) { @@ -158,12 +152,12 @@ void *laser_display_and_save_loop(void *) // Write the file header fdscan << "# Scan layer [1 to 4] : " << layer + 1 << std::endl - << "# Start timestamp (s) : " << laserscan[layer].getStartTimestamp() - time_offset << std::endl - << "# End timestamp (s) : " << laserscan[layer].getEndTimestamp() - time_offset << std::endl - << "# Data : \"radial distance (m)\" \"horizontal angle " - "(rad)\" \"vertical angle (rad)\" \"X (m)\" \"Y (m)\" \"Z " - "(m)\"" - << std::endl; + << "# Start timestamp (s) : " << laserscan[layer].getStartTimestamp() - time_offset << std::endl + << "# End timestamp (s) : " << laserscan[layer].getEndTimestamp() - time_offset << std::endl + << "# Data : \"radial distance (m)\" \"horizontal angle " + "(rad)\" \"vertical angle (rad)\" \"X (m)\" \"Y (m)\" \"Z " + "(m)\"" + << std::endl; } vpImagePoint E; // Beam echo @@ -194,10 +188,9 @@ void *laser_display_and_save_loop(void *) // std::endl; } delete display; - return nullptr; } -void *laser_acq_loop(void *) +void laser_acq_loop() { std::string ip = "131.254.12.119"; @@ -211,22 +204,17 @@ void *laser_acq_loop(void *) if (laser.measure(laserscan) == false) continue; -#ifdef VISP_HAVE_PTHREAD - pthread_mutex_lock(&shm_mutex); -#endif - for (int layer = 0; layer < 4; layer++) + shm_mutex.lock(); + for (int layer = 0; layer < 4; layer++) { shm_laserscan[layer] = laserscan[layer]; -#ifdef VISP_HAVE_PTHREAD - pthread_mutex_unlock(&shm_mutex); -#endif + } + shm_mutex.unlock(); std::cout << "laser acq time: " << vpTime::measureTimeMs() - t1 << std::endl; } - - return nullptr; } -void *camera_acq_and_display_loop(void *) +void camera_acq_and_display_loop() { #ifdef VISP_HAVE_DC1394 try { @@ -234,8 +222,9 @@ void *camera_acq_and_display_loop(void *) vp1394TwoGrabber g; // Create a grabber based on libdc1394-2.x third party lib // If no camera found return - if (g.getNumCameras() == 0) - return nullptr; + if (g.getNumCameras() == 0) { + return; + } // g.setVideoMode(vp1394TwoGrabber::vpVIDEO_MODE_640x480_MONO8); // g.setFramerate(vp1394TwoGrabber::vpFRAMERATE_60); @@ -255,7 +244,7 @@ void *camera_acq_and_display_loop(void *) display->init(Q, 320, 10, "Camera"); #endif - // Create a file with cameraimage time stamps + // Create a file with image time stamps std::ofstream fdimage_ts; if (save) { std::string filename = output_path + "/image_timestamp.txt"; @@ -289,10 +278,10 @@ void *camera_acq_and_display_loop(void *) if (save) { fdimage_ts.close(); } - } catch (...) { + } + catch (...) { } #endif - return nullptr; } int main(int argc, const char **argv) @@ -304,7 +293,8 @@ int main(int argc, const char **argv) try { // Create a directory with name "username" vpIoTools::makeDirectory(output_path); - } catch (...) { + } + catch (...) { std::cout << "Cannot create " << output_path << " directory" << std::endl; return EXIT_FAILURE; } @@ -323,30 +313,27 @@ int main(int argc, const char **argv) {"-h", vpParseArgv::ARGV_HELP, (char *)nullptr, (char *)nullptr, "Display one or more measured layers form a Sick LD-MRS laser " "scanner."}, - {(char *)nullptr, vpParseArgv::ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr}}; + {(char *)nullptr, vpParseArgv::ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr} }; // Read the command line options if (vpParseArgv::parse(&argc, argv, argTable, vpParseArgv::ARGV_NO_LEFTOVERS | vpParseArgv::ARGV_NO_ABBREV | - vpParseArgv::ARGV_NO_DEFAULTS)) { + vpParseArgv::ARGV_NO_DEFAULTS)) { return (EXIT_FAILURE); } + VISP_HAVE_PTHREAD + time_offset = vpTime::measureTimeSecond(); - time_offset = vpTime::measureTimeSecond(); -#ifdef VISP_HAVE_PTHREAD - pthread_t thread_camera_acq; - pthread_t thread_laser_acq; - pthread_t thread_laser_display; - pthread_create(&thread_camera_acq, nullptr, &camera_acq_and_display_loop, nullptr); - pthread_create(&thread_laser_acq, nullptr, &laser_acq_loop, nullptr); - pthread_create(&thread_laser_display, nullptr, &laser_display_and_save_loop, nullptr); - pthread_join(thread_camera_acq, 0); - pthread_join(thread_laser_acq, 0); - pthread_join(thread_laser_display, 0); -#endif + std::thread thread_camera_acq(&camera_acq_and_display_loop); + std::thread thread_laser_acq(&laser_acq_loop); + std::thread thread_laser_display(&laser_display_and_save_loop); + thread_camera_acq.join(); + thread_laser_acq.join(); + thread_laser_display.join(); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } @@ -367,7 +354,7 @@ int main() int main() { std::cout << "This example is only working on unix-like platforms \n" - << "since the Sick LD-MRS driver was not ported to Windows." << std::endl; + << "since the Sick LD-MRS driver was not ported to Windows." << std::endl; return EXIT_SUCCESS; } diff --git a/example/moments/image/servoMomentImage.cpp b/example/moments/image/servoMomentImage.cpp index bd3c7045ae..1cfe5b9352 100644 --- a/example/moments/image/servoMomentImage.cpp +++ b/example/moments/image/servoMomentImage.cpp @@ -63,25 +63,12 @@ #include #include -#if !defined(_WIN32) && !defined(VISP_HAVE_PTHREAD) -// Robot simulator used in this example is not available -int main() -{ - std::cout << "Can't run this example since vpSimulatorAfma6 capability is " - "not available." - << std::endl; - std::cout << "You should install pthread third-party library." << std::endl; - return EXIT_SUCCESS; -} -// No display available -#elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ - !defined(VISP_HAVE_GTK) +#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ + !defined(VISP_HAVE_GTK) && !defined(VISP_HAVE_THREADS) int main() { std::cout << "Can't run this example since no display capability is available." << std::endl; - std::cout << "You should install one of the following third-party library: " - "X11, OpenCV, GDI, GTK." - << std::endl; + std::cout << "You should install one of the following third-party library: X11, OpenCV, GDI, GTK." << std::endl; return EXIT_SUCCESS; } #else diff --git a/example/moments/points/servoMomentPoints.cpp b/example/moments/points/servoMomentPoints.cpp index 53c0f5782c..4c3184a2ef 100644 --- a/example/moments/points/servoMomentPoints.cpp +++ b/example/moments/points/servoMomentPoints.cpp @@ -62,25 +62,12 @@ #include #include -#if !defined(_WIN32) && !defined(VISP_HAVE_PTHREAD) -// Robot simulator used in this example is not available -int main() -{ - std::cout << "Can't run this example since vpSimulatorAfma6 capability is " - "not available." - << std::endl; - std::cout << "You should install pthread third-party library." << std::endl; - return EXIT_SUCCESS; -} -// No display available -#elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ - !defined(VISP_HAVE_GTK) +#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ + !defined(VISP_HAVE_GTK) && !defined(VISP_HAVE_THREADS) int main() { std::cout << "Can't run this example since no display capability is available." << std::endl; - std::cout << "You should install one of the following third-party library: " - "X11, OpenCV, GDI, GTK." - << std::endl; + std::cout << "You should install one of the following third-party library: X11, OpenCV, GDI, GTK." << std::endl; return EXIT_SUCCESS; } #else diff --git a/example/moments/polygon/servoMomentPolygon.cpp b/example/moments/polygon/servoMomentPolygon.cpp index 4134c33caa..776c7528b2 100644 --- a/example/moments/polygon/servoMomentPolygon.cpp +++ b/example/moments/polygon/servoMomentPolygon.cpp @@ -61,25 +61,12 @@ #include #include -#if !defined(_WIN32) && !defined(VISP_HAVE_PTHREAD) -// Robot simulator used in this example is not available -int main() -{ - std::cout << "Can't run this example since vpSimulatorAfma6 capability is " - "not available." - << std::endl; - std::cout << "You should install pthread third-party library." << std::endl; - return EXIT_SUCCESS; -} -// No display available -#elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ - !defined(VISP_HAVE_GTK) +#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ + !defined(VISP_HAVE_GTK) && !defined(VISP_HAVE_THREADS) int main() { std::cout << "Can't run this example since no display capability is available." << std::endl; - std::cout << "You should install one of the following third-party library: " - "X11, OpenCV, GDI, GTK." - << std::endl; + std::cout << "You should install one of the following third-party library: X11, OpenCV, GDI, GTK." << std::endl; return EXIT_SUCCESS; } #else diff --git a/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp b/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp index 649961326d..cceca787e7 100644 --- a/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/afma6/servoSimuAfma6FourPoints2DCamVelocity.cpp @@ -53,9 +53,8 @@ #include #include -#if ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_GDI)) && \ - (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) +#if defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_GDI)) \ + && (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) // We need to use threading capabilities. Thus on Unix-like // platforms, the libpthread third-party library need to be diff --git a/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp b/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp index b99dc47015..64e82c5d71 100644 --- a/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/viper850/servoSimuViper850FourPoints2DCamVelocity.cpp @@ -53,9 +53,8 @@ #include #include -#if ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_GDI)) && \ - (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) +#if defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_GDI)) \ + && (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV)) // We need to use threading capabilities. Thus on Unix-like // platforms, the libpthread third-party library need to be @@ -348,7 +347,8 @@ int main(int argc, const char **argv) vpDisplay::getClick(Iint); } return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch a ViSP exception: " << e << std::endl; return EXIT_FAILURE; } @@ -357,7 +357,7 @@ int main(int argc, const char **argv) int main() { std::cout << "You do not have X11, or GDI (Graphical Device Interface) of OpenCV functionalities to display images..." - << std::endl; + << std::endl; std::cout << "Tip if you are on a unix-like system:" << std::endl; std::cout << "- Install X11, configure again ViSP using cmake and build again this example" << std::endl; std::cout << "Tip if you are on a windows-like system:" << std::endl; diff --git a/example/servo-pixhawk/sendMocapToPixhawk.cpp b/example/servo-pixhawk/sendMocapToPixhawk.cpp index 67cf9fdc32..e646a8599b 100644 --- a/example/servo-pixhawk/sendMocapToPixhawk.cpp +++ b/example/servo-pixhawk/sendMocapToPixhawk.cpp @@ -46,7 +46,7 @@ // Check if std:c++17 or higher #if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) && \ - (defined(VISP_HAVE_QUALISYS) || defined(VISP_HAVE_VICON)) + (defined(VISP_HAVE_QUALISYS) || defined(VISP_HAVE_VICON)) && defined(VISP_HAVE_THREADS) #include #include diff --git a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp index 8fa7735c17..50d495cc5e 100644 --- a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp +++ b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp @@ -59,7 +59,7 @@ #endif #include -#if defined(VISP_HAVE_PTU46) && defined(VISP_HAVE_DC1394) +#if defined(VISP_HAVE_PTU46) && defined(VISP_HAVE_DC1394) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/ar/src/coin-simulator/vpSimulator.cpp b/modules/ar/src/coin-simulator/vpSimulator.cpp index 16598e938f..8d154d9931 100644 --- a/modules/ar/src/coin-simulator/vpSimulator.cpp +++ b/modules/ar/src/coin-simulator/vpSimulator.cpp @@ -73,12 +73,12 @@ // Positions of all of the vertices: // -static float pyramidVertexes[5][3] = {{0.33f, 0.33f, 0.f}, +static float pyramidVertexes[5][3] = { {0.33f, 0.33f, 0.f}, {-0.33f, 0.33f, 0.f}, {-0.33f, -0.33f, 0.f}, {0.33f, -0.33f, 0.f}, - {0.f, 0.f, -1.0f}}; + {0.f, 0.f, -1.0f} }; static int32_t pyramidFaces[] = { 0, @@ -325,18 +325,18 @@ void vpSimulator::kill() vpSimulator::vpSimulator() : #if defined(VISP_HAVE_SOWIN) - mainWindow(), + mainWindow(), #elif defined(VISP_HAVE_SOQT) - mainWindow(nullptr), + mainWindow(nullptr), #elif defined(VISP_HAVE_SOXT) - mainWindow(), + mainWindow(), #endif - mainWindowInitialized(false), typeImage(vpSimulator::grayImage), image_background(nullptr), internalView(nullptr), - externalView(nullptr), mainThread(nullptr), internal_width(0), internal_height(0), external_width(0), external_height(0), - scene(nullptr), internalRoot(nullptr), externalRoot(nullptr), internalCamera(nullptr), externalCamera(nullptr), - internalCameraPosition(nullptr), extrenalCameraPosition(nullptr), internalCameraObject(nullptr), zoomFactor(0.), - cameraPositionInitialized(false), cMf(), internalCameraParameters(), externalCameraParameters(), realtime(nullptr), - offScreenRenderer(nullptr), bufferView(nullptr), get(0) + mainWindowInitialized(false), typeImage(vpSimulator::grayImage), image_background(nullptr), internalView(nullptr), + externalView(nullptr), mainThread(nullptr), internal_width(0), internal_height(0), external_width(0), external_height(0), + scene(nullptr), internalRoot(nullptr), externalRoot(nullptr), internalCamera(nullptr), externalCamera(nullptr), + internalCameraPosition(nullptr), extrenalCameraPosition(nullptr), internalCameraObject(nullptr), zoomFactor(0.), + cameraPositionInitialized(false), cMf(), internalCameraParameters(), externalCameraParameters(), realtime(nullptr), + offScreenRenderer(nullptr), bufferView(nullptr), get(0) { vpSimulator::init(); } @@ -415,7 +415,8 @@ void vpSimulator::setZoomFactor(float zoom) taille->scaleFactor.setValue(zoomFactor, zoomFactor, zoomFactor); this->scene->addChild(taille); firstTime = false; - } else { + } + else { SoScale *taille = (SoScale *)this->scene->getChild(0); taille->scaleFactor.setValue(zoomFactor, zoomFactor, zoomFactor); } @@ -750,7 +751,8 @@ void vpSimulator::load(const char *iv_filename, const vpHomogeneousMatrix &fMo) try { this->addObject(newObject, fMo); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error adding object from file <%s> ", iv_filename); throw; } @@ -765,7 +767,8 @@ void vpSimulator::addObject(SoSeparator *newObject, const vpHomogeneousMatrix &f { try { this->addObject(newObject, fMo, scene); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error adding object in scene graph "); throw; } @@ -787,7 +790,8 @@ void vpSimulator::addObject(SoSeparator *object, const vpHomogeneousMatrix &fMo, if (i == j) { if (fabs(fMo[i][j] - 1) > 1e-6) identity = false; - } else { + } + else { if (fabs(fMo[i][j]) > 1e-6) identity = false; } @@ -796,7 +800,8 @@ void vpSimulator::addObject(SoSeparator *object, const vpHomogeneousMatrix &fMo, if (identity == true) { root->addChild(object); - } else { + } + else { SbMatrix matrix; SbRotation rotation; for (unsigned int i = 0; i < 4; i++) @@ -875,7 +880,8 @@ void vpSimulator::offScreenRendering(vpSimulatorViewType view, int *width, int * if (view == vpSimulator::INTERNAL) { size = this->internalView->getViewportRegion().getWindowSize(); thisroot = this->internalView->getSceneManager()->getSceneGraph(); - } else { + } + else { size = this->externalView->getViewportRegion().getWindowSize(); thisroot = this->externalView->getSceneManager()->getSceneGraph(); } @@ -886,7 +892,8 @@ void vpSimulator::offScreenRendering(vpSimulatorViewType view, int *width, int * if (nullptr == this->offScreenRenderer) { // Init du SoOffscreenRenderer this->offScreenRenderer = new SoOffscreenRenderer(myViewPort); - } else { + } + else { // Redefini le view port this->offScreenRenderer->setViewportRegion(myViewPort); } @@ -896,20 +903,21 @@ void vpSimulator::offScreenRendering(vpSimulatorViewType view, int *width, int * vpERROR_TRACE("La scene n'a pas pu etre rendue offscreen."); delete this->offScreenRenderer; this->offScreenRenderer = nullptr; - } else { - - /* - if (view==vpSimulator::INTERNAL) - { - //Recopie du buffer contenant l'image, dans bufferView - int length = 3*size [0]*size[1]; - delete [] bufferView; - bufferView = new unsigned char [length]; - for(int i=0; ioffScreenRenderer->getBuffer()[i]; - } - }*/ + } + else { + + /* + if (view==vpSimulator::INTERNAL) + { + //Recopie du buffer contenant l'image, dans bufferView + int length = 3*size [0]*size[1]; + delete [] bufferView; + bufferView = new unsigned char [length]; + for(int i=0; ioffScreenRenderer->getBuffer()[i]; + } + }*/ } // exit(1) ; @@ -996,7 +1004,6 @@ void vpSimulator::getInternalImage(vpImage &I) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_ar.a(vpSimulator.cpp.o) has no -// symbols -void dummy_vpSimulator(){}; +// Work around to avoid warning: libvisp_ar.a(vpSimulator.cpp.o) has no symbols +void dummy_vpSimulator() { }; #endif diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 8dbaa41ec5..1184627d29 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -48,8 +48,8 @@ #include #include -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) -#include +#if defined(VISP_HAVE_THREADS) +#include #endif #include @@ -481,7 +481,7 @@ inline std::ostream &operator<<(std::ostream &s, const vpImage &I) return s; } -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_HAVE_THREADS) namespace { struct vpImageLut_Param_t @@ -499,9 +499,8 @@ struct vpImageLut_Param_t { } }; -vpThread::Return performLutThread(vpThread::Args args) +void performLutThread(vpImageLut_Param_t *imageLut_param) { - vpImageLut_Param_t *imageLut_param = static_cast(args); unsigned int start_index = imageLut_param->m_start_index; unsigned int end_index = imageLut_param->m_end_index; @@ -511,11 +510,6 @@ vpThread::Return performLutThread(vpThread::Args args) unsigned char *ptrEnd = bitmap + end_index; unsigned char *ptrCurrent = ptrStart; - // while(ptrCurrent != ptrEnd) { - // *ptrCurrent = imageLut_param->m_lut[*ptrCurrent]; - // ++ptrCurrent; - // } - if (end_index - start_index >= 8) { // Unroll loop version for (; ptrCurrent <= ptrEnd - 8;) { @@ -548,8 +542,6 @@ vpThread::Return performLutThread(vpThread::Args args) for (; ptrCurrent != ptrEnd; ++ptrCurrent) { *ptrCurrent = imageLut_param->m_lut[*ptrCurrent]; } - - return 0; } struct vpImageLutRGBa_Param_t @@ -567,9 +559,8 @@ struct vpImageLutRGBa_Param_t { } }; -vpThread::Return performLutRGBaThread(vpThread::Args args) +void performLutRGBaThread(vpImageLutRGBa_Param_t *imageLut_param) { - vpImageLutRGBa_Param_t *imageLut_param = static_cast(args); unsigned int start_index = imageLut_param->m_start_index; unsigned int end_index = imageLut_param->m_end_index; @@ -615,8 +606,6 @@ vpThread::Return performLutRGBaThread(vpThread::Args args) *ptrCurrent = imageLut_param->m_lut[*ptrCurrent].A; ptrCurrent++; } - - return 0; } } // namespace #endif @@ -2023,7 +2012,7 @@ template <> inline void vpImage::performLut(const unsigned char(& unsigned char *ptrCurrent = ptrStart; bool use_single_thread = (nbThreads == 0 || nbThreads == 1); -#if !defined(VISP_HAVE_PTHREAD) && !defined(_WIN32) +#if !defined(VISP_HAVE_THREADS) use_single_thread = true; #endif @@ -2040,10 +2029,9 @@ template <> inline void vpImage::performLut(const unsigned char(& } } else { -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_HAVE_THREADS) // Multi-threads - - std::vector threadpool; + std::vector threadpool; std::vector imageLutParams; unsigned int image_size = getSize(); @@ -2064,7 +2052,7 @@ template <> inline void vpImage::performLut(const unsigned char(& imageLutParams.push_back(imageLut_param); // Start the threads - vpThread *imageLut_thread = new vpThread((vpThread::Fn)performLutThread, (vpThread::Args)imageLut_param); + std::thread *imageLut_thread = new std::thread(&performLutThread, imageLut_param); threadpool.push_back(imageLut_thread); } @@ -2103,7 +2091,7 @@ template <> inline void vpImage::performLut(const vpRGBa(&lut)[256], uns unsigned char *ptrCurrent = ptrStart; bool use_single_thread = (nbThreads == 0 || nbThreads == 1); -#if !defined(VISP_HAVE_PTHREAD) && !defined(_WIN32) +#if !defined(VISP_HAVE_THREADS) use_single_thread = true; #endif @@ -2128,9 +2116,9 @@ template <> inline void vpImage::performLut(const vpRGBa(&lut)[256], uns } } else { -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_HAVE_THREADS) // Multi-threads - std::vector threadpool; + std::vector threadpool; std::vector imageLutParams; unsigned int image_size = getSize(); @@ -2151,7 +2139,7 @@ template <> inline void vpImage::performLut(const vpRGBa(&lut)[256], uns imageLutParams.push_back(imageLut_param); // Start the threads - vpThread *imageLut_thread = new vpThread((vpThread::Fn)performLutRGBaThread, (vpThread::Args)imageLut_param); + std::thread *imageLut_thread = new std::thread(&performLutRGBaThread, imageLut_param); threadpool.push_back(imageLut_thread); } diff --git a/modules/core/include/visp3/core/vpImageTools.h b/modules/core/include/visp3/core/vpImageTools.h index 55d3c002ea..6c8fa38269 100644 --- a/modules/core/include/visp3/core/vpImageTools.h +++ b/modules/core/include/visp3/core/vpImageTools.h @@ -43,8 +43,8 @@ #include -#ifdef VISP_HAVE_PTHREAD -#include +#ifdef VISP_HAVE_THREADS +#include #endif #include @@ -518,7 +518,7 @@ inline void vpImageTools::binarise(vpImage &I, unsigned char thre } } -#ifdef VISP_HAVE_PTHREAD +#ifdef VISP_HAVE_THREADS #ifndef DOXYGEN_SHOULD_SKIP_THIS template class vpUndistortInternalType @@ -549,22 +549,21 @@ template class vpUndistortInternalType return *this; } - static void *vpUndistort_threaded(void *arg); + static void vpUndistort_threaded(vpUndistortInternalType &undistortSharedData); }; -template void *vpUndistortInternalType::vpUndistort_threaded(void *arg) +template void vpUndistortInternalType::vpUndistort_threaded(vpUndistortInternalType &undistortSharedData) { - vpUndistortInternalType *undistortSharedData = static_cast *>(arg); - int offset = (int)undistortSharedData->threadid; - int width = (int)undistortSharedData->width; - int height = (int)undistortSharedData->height; - int nthreads = (int)undistortSharedData->nthreads; - - double u0 = undistortSharedData->cam.get_u0(); - double v0 = undistortSharedData->cam.get_v0(); - double px = undistortSharedData->cam.get_px(); - double py = undistortSharedData->cam.get_py(); - double kud = undistortSharedData->cam.get_kud(); + int offset = (int)undistortSharedData.threadid; + int width = (int)undistortSharedData.width; + int height = (int)undistortSharedData.height; + int nthreads = (int)undistortSharedData.nthreads; + + double u0 = undistortSharedData.cam.get_u0(); + double v0 = undistortSharedData.cam.get_v0(); + double px = undistortSharedData.cam.get_px(); + double py = undistortSharedData.cam.get_py(); + double kud = undistortSharedData.cam.get_kud(); double invpx = 1.0 / px; double invpy = 1.0 / py; @@ -572,8 +571,8 @@ template void *vpUndistortInternalType::vpUndistort_threaded( double kud_px2 = kud * invpx * invpx; double kud_py2 = kud * invpy * invpy; - Type *dst = undistortSharedData->dst + (height / nthreads * offset) * width; - Type *src = undistortSharedData->src; + Type *dst = undistortSharedData.dst + (height / nthreads * offset) * width; + Type *src = undistortSharedData.src; for (double v = height / nthreads * offset; v < height / nthreads * (offset + 1); v++) { double deltav = v - v0; @@ -616,12 +615,9 @@ template void *vpUndistortInternalType::vpUndistort_threaded( dst++; } } - - pthread_exit((void *)0); - return nullptr; } #endif // DOXYGEN_SHOULD_SKIP_THIS -#endif // VISP_HAVE_PTHREAD +#endif // VISP_HAVE_THREADS /*! Undistort an image @@ -650,7 +646,7 @@ template void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &cam, vpImage &undistI, unsigned int nThreads) { -#ifdef VISP_HAVE_PTHREAD +#if defined(VISP_HAVE_THREADS) // // Optimized version using pthreads // @@ -669,13 +665,9 @@ void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &c } unsigned int nthreads = nThreads; - pthread_attr_t attr; - pthread_t *callThd = new pthread_t[nthreads]; - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); + std::vector threadpool; - vpUndistortInternalType *undistortSharedData; - undistortSharedData = new vpUndistortInternalType[nthreads]; + vpUndistortInternalType *undistortSharedData = new vpUndistortInternalType[nthreads]; for (unsigned int i = 0; i < nthreads; i++) { // Each thread works on a different set of data. @@ -687,19 +679,22 @@ void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &c undistortSharedData[i].cam = cam; undistortSharedData[i].nthreads = nthreads; undistortSharedData[i].threadid = i; - pthread_create(&callThd[i], &attr, &vpUndistortInternalType::vpUndistort_threaded, &undistortSharedData[i]); + std::thread *undistort_thread = new std::thread(&vpUndistortInternalType::vpUndistort_threaded, std::ref(undistortSharedData[i])); + threadpool.push_back(undistort_thread); } - pthread_attr_destroy(&attr); /* Wait on the other threads */ for (unsigned int i = 0; i < nthreads; i++) { // vpTRACE("join thread %d", i); - pthread_join(callThd[i], nullptr); + threadpool[i]->join(); + } + + for (unsigned int i = 0; i < nthreads; i++) { + delete threadpool[i]; } - delete[] callThd; delete[] undistortSharedData; -#else // VISP_HAVE_PTHREAD +#else // VISP_HAVE_THREADS (void)nThreads; // // optimized version without pthreads @@ -773,7 +768,7 @@ void vpImageTools::undistort(const vpImage &I, const vpCameraParameters &c dst++; } } -#endif // VISP_HAVE_PTHREAD +#endif // VISP_HAVE_THREADS #if 0 // non optimized version @@ -1137,7 +1132,7 @@ void vpImageTools::resize(const vpImage &I, vpImage &Ires, const vpI } } } -} + } #if defined(VISP_HAVE_SIMDLIB) template <> diff --git a/modules/core/include/visp3/core/vpMutex.h b/modules/core/include/visp3/core/vpMutex.h index a9aaf12e1e..f61ab41063 100644 --- a/modules/core/include/visp3/core/vpMutex.h +++ b/modules/core/include/visp3/core/vpMutex.h @@ -37,7 +37,7 @@ #include #include -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) && (defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0))) #if defined(VISP_HAVE_PTHREAD) #include @@ -53,6 +53,7 @@ \class vpMutex \ingroup group_core_threading + \deprecated Use rather std::mutex. Class that allows protection by mutex. @@ -66,7 +67,7 @@ \sa vpScopedLock */ -class vpMutex +class vp_deprecated vpMutex { public: vpMutex() : m_mutex() diff --git a/modules/core/include/visp3/core/vpThread.h b/modules/core/include/visp3/core/vpThread.h index 8420656b82..672ba84ffb 100644 --- a/modules/core/include/visp3/core/vpThread.h +++ b/modules/core/include/visp3/core/vpThread.h @@ -36,7 +36,7 @@ #include #include -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) && (defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0))) #if defined(VISP_HAVE_PTHREAD) #include @@ -53,6 +53,8 @@ \ingroup group_core_threading + \deprecated Use rather std::thread. + Class to represent individual threads of execution. This class implements native pthread functionalities if available, or native Windows threading capabilities if pthread is not available under @@ -65,7 +67,7 @@ More examples are provided in \ref tutorial-multi-threading. */ -class vpThread +class vp_deprecated vpThread { public: #if defined(VISP_HAVE_PTHREAD) diff --git a/modules/core/src/tools/convert/vpConvert.cpp b/modules/core/src/tools/convert/vpConvert.cpp index 9e38c3def8..6ba42f78c6 100644 --- a/modules/core/src/tools/convert/vpConvert.cpp +++ b/modules/core/src/tools/convert/vpConvert.cpp @@ -185,7 +185,7 @@ cv::Point3d vpConvert::vpCamPointToPoint3d(const vpPoint &point) } /*! - Unary function to convert the 3D coordinates in the object frame to a cv::Point3f. + Unary function to convert the 3D coordinates in the object frame to a cv::Point3f. \param point : Point to convert. \return A cv::Point3f with the 3D coordinates stored in vpPoint in the @@ -248,7 +248,8 @@ void vpConvert::convertFromOpenCV(const cv::Point3f &from, vpPoint &to, bool cam { if (cameraFrame) { to = point3fToVpCamPoint(from); - } else { + } + else { to = point3fToVpObjectPoint(from); } } @@ -264,7 +265,8 @@ void vpConvert::convertFromOpenCV(const cv::Point3d &from, vpPoint &to, bool cam { if (cameraFrame) { to = point3dToVpCamPoint(from); - } else { + } + else { to = point3dToVpObjectPoint(from); } } @@ -314,7 +316,8 @@ void vpConvert::convertFromOpenCV(const std::vector &from, std::vec to.resize(from.size()); if (cameraFrame) { std::transform(from.begin(), from.end(), to.begin(), point3fToVpCamPoint); - } else { + } + else { std::transform(from.begin(), from.end(), to.begin(), point3fToVpObjectPoint); } } @@ -331,7 +334,8 @@ void vpConvert::convertFromOpenCV(const std::vector &from, std::vec to.resize(from.size()); if (cameraFrame) { std::transform(from.begin(), from.end(), to.begin(), point3dToVpCamPoint); - } else { + } + else { std::transform(from.begin(), from.end(), to.begin(), point3dToVpObjectPoint); } } @@ -377,7 +381,8 @@ void vpConvert::convertToOpenCV(const vpPoint &from, cv::Point3f &to, bool camer { if (cameraFrame) { to = vpCamPointToPoint3f(from); - } else { + } + else { to = vpObjectPointToPoint3f(from); } } @@ -393,7 +398,8 @@ void vpConvert::convertToOpenCV(const vpPoint &from, cv::Point3d &to, bool camer { if (cameraFrame) { to = vpCamPointToPoint3d(from); - } else { + } + else { to = vpObjectPointToPoint3d(from); } } @@ -432,7 +438,8 @@ void vpConvert::convertToOpenCV(const std::vector &from, std::vector &from, std::vector #include -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) -#include +#if defined(VISP_HAVE_THREADS) +#include namespace { @@ -76,9 +76,8 @@ struct vpHistogram_Param_t } }; -vpThread::Return computeHistogramThread(vpThread::Args args) +void computeHistogramThread(vpHistogram_Param_t *histogram_param) { - vpHistogram_Param_t *histogram_param = static_cast(args); unsigned int start_index = histogram_param->m_start_index; unsigned int end_index = histogram_param->m_end_index; @@ -171,7 +170,6 @@ vpThread::Return computeHistogramThread(vpThread::Args args) ++ptrMaskCurrent; } } - return 0; } } // namespace #endif @@ -188,7 +186,7 @@ bool compare_vpHistogramPeak(vpHistogramPeak first, vpHistogramPeak second) } /*! - Defaut constructor for a gray level histogram. + Default constructor for a gray level histogram. */ vpHistogram::vpHistogram() : m_histogram(nullptr), m_size(256), mp_mask(nullptr), m_total(0) { init(); } @@ -314,7 +312,7 @@ void vpHistogram::calculate(const vpImage &I, unsigned int nbins, memset(m_histogram, 0, m_size * sizeof(unsigned int)); bool use_single_thread; -#if !defined(VISP_HAVE_PTHREAD) && !defined(_WIN32) +#if !defined(VISP_HAVE_THREADS) use_single_thread = true; #else use_single_thread = (nbThreads == 0 || nbThreads == 1); @@ -355,9 +353,9 @@ void vpHistogram::calculate(const vpImage &I, unsigned int nbins, } } else { -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) +#if defined(VISP_HAVE_THREADS) // Multi-threads - std::vector threadpool; + std::vector threadpool; std::vector histogramParams; unsigned int image_size = I.getSize(); @@ -381,7 +379,7 @@ void vpHistogram::calculate(const vpImage &I, unsigned int nbins, histogramParams.push_back(histogram_param); // Start the threads - vpThread *histogram_thread = new vpThread((vpThread::Fn)computeHistogramThread, (vpThread::Args)histogram_param); + std::thread *histogram_thread = new std::thread(&computeHistogramThread, histogram_param); threadpool.push_back(histogram_thread); } diff --git a/modules/core/src/tools/histogram/vpHistogramPeak.cpp b/modules/core/src/tools/histogram/vpHistogramPeak.cpp index 63e476ad70..6b507e8490 100644 --- a/modules/core/src/tools/histogram/vpHistogramPeak.cpp +++ b/modules/core/src/tools/histogram/vpHistogramPeak.cpp @@ -44,12 +44,12 @@ #include /*! - Defaut constructor for a gray level histogram peak. + Default constructor for a gray level histogram peak. */ vpHistogramPeak::vpHistogramPeak() : level(0), value(0) {} /*! - Defaut constructor for a gray level histogram peak. + Default constructor for a gray level histogram peak. */ vpHistogramPeak::vpHistogramPeak(unsigned char lvl, unsigned val) : level(lvl), value(val) {} diff --git a/modules/core/src/tools/xml/vpXmlParser.cpp b/modules/core/src/tools/xml/vpXmlParser.cpp index 8c203293bb..56480aee98 100644 --- a/modules/core/src/tools/xml/vpXmlParser.cpp +++ b/modules/core/src/tools/xml/vpXmlParser.cpp @@ -52,7 +52,7 @@ Initialise the main tag with default value. */ -vpXmlParser::vpXmlParser() : nodeMap(), main_tag("config") {} +vpXmlParser::vpXmlParser() : nodeMap(), main_tag("config") { } /*! Basic destructor that does nothing. @@ -79,7 +79,7 @@ vpXmlParser::~vpXmlParser() \param _twin : The parser to copy. */ -vpXmlParser::vpXmlParser(const vpXmlParser &_twin) : nodeMap(_twin.nodeMap), main_tag(_twin.main_tag) {} +vpXmlParser::vpXmlParser(const vpXmlParser &_twin) : nodeMap(_twin.nodeMap), main_tag(_twin.main_tag) { } /* utilities functions to read/write data from an xml document */ @@ -457,7 +457,8 @@ void vpXmlParser::save(const std::string &filename, bool append) doc = xmlNewDoc((xmlChar *)"1.0"); root_node = xmlNewNode(nullptr, (xmlChar *)main_tag.c_str()); xmlDocSetRootElement(doc, root_node); - } else { + } + else { if (!append) { xmlFreeDoc(doc); if (remove(filename.c_str()) != 0) @@ -482,7 +483,6 @@ void vpXmlParser::save(const std::string &filename, bool append) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpXmlParser.cpp.o) has no -// symbols -void dummy_vpXmlParser(){}; +// Work around to avoid warning: libvisp_core.a(vpXmlParser.cpp.o) has no symbols +void dummy_vpXmlParser() { }; #endif diff --git a/modules/core/test/image-with-dataset/perfColorConversion.cpp b/modules/core/test/image-with-dataset/perfColorConversion.cpp index b8b26970cc..03d24abf5b 100644 --- a/modules/core/test/image-with-dataset/perfColorConversion.cpp +++ b/modules/core/test/image-with-dataset/perfColorConversion.cpp @@ -35,7 +35,7 @@ #include -#ifdef VISP_HAVE_CATCH2 +#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/core/test/image-with-dataset/perfImageResize.cpp b/modules/core/test/image-with-dataset/perfImageResize.cpp index 06e60928bb..69cd7d90ca 100644 --- a/modules/core/test/image-with-dataset/perfImageResize.cpp +++ b/modules/core/test/image-with-dataset/perfImageResize.cpp @@ -35,7 +35,7 @@ #include -#ifdef VISP_HAVE_CATCH2 +#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/core/test/image-with-dataset/testColorConversion.cpp b/modules/core/test/image-with-dataset/testColorConversion.cpp index f3d2e61ee8..b9b1a43d67 100644 --- a/modules/core/test/image-with-dataset/testColorConversion.cpp +++ b/modules/core/test/image-with-dataset/testColorConversion.cpp @@ -149,7 +149,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -164,7 +164,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -179,7 +179,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -194,7 +194,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -209,7 +209,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -224,7 +224,7 @@ TEST_CASE("RGBa to Gray conversion", "[image_conversion]") vpImageConvert::convert(rgba, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGBa to Gray conversion, mean error: " << error << std::endl; + std::cout << "RGBa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -243,12 +243,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -263,12 +263,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -283,11 +283,11 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -302,12 +302,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -322,12 +322,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -342,12 +342,12 @@ TEST_CASE("RGB to Gray conversion", "[image_conversion]") vpImageConvert::RGBToGrey(rgb.data(), gray.bitmap, w, h, false); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 1, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 1, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; vpImage gray2(h, w); vpImageConvert::RGBToGrey(rgb.data(), gray2.bitmap, w * h); CHECK(common_tools::almostEqual(gray_ref, gray2, maxMeanPixelError, error)); - std::cout << "RGB to Gray conversion 2, mean error: " << error << std::endl; + std::cout << "RGB to Gray conversion 2, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -458,7 +458,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -477,7 +477,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -496,7 +496,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -515,7 +515,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -534,7 +534,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -553,7 +553,7 @@ TEST_CASE("BGR to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -576,7 +576,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -595,7 +595,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -614,7 +614,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -633,7 +633,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -652,7 +652,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -671,7 +671,7 @@ TEST_CASE("BGRa to Gray conversion", "[image_conversion]") double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGRa to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGRa to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -691,7 +691,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x17 (SSE41 aligned=false)") { @@ -707,7 +707,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x32 (AVX2 aligned=true)") { @@ -723,7 +723,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 1x33 (AVX2 aligned=false)") { @@ -739,7 +739,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 4x64 (general aligned = true") { @@ -755,7 +755,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("Image 5x65 (general aligned = false") { @@ -771,7 +771,7 @@ TEST_CASE("BGRa to RGBa conversion", "[image_conversion]") rgba.getHeight()); double error = 0; CHECK(common_tools::almostEqual(rgba_ref, rgba, maxMeanPixelError, error)); - std::cout << "BGRa to RGBa conversion, mean error: " << error << std::endl; + std::cout << "BGRa to RGBa conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } } @@ -830,7 +830,7 @@ TEST_CASE("OpenCV Mat <==> vpImage conversion", "[image_conversion]") vpImageConvert::convert(img, gray); double error = 0; CHECK(common_tools::almostEqual(gray_ref, gray, maxMeanPixelError, error)); - std::cout << "BGR to Gray conversion, mean error: " << error << std::endl; + std::cout << "BGR to Gray conversion, mean error: " << error << " max allowed: " << maxMeanPixelError << std::endl; } SECTION("CV_8UC1 to unsigned char") @@ -996,7 +996,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - BGGR - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - BGGR - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1007,7 +1007,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - BGGR - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - BGGR - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1027,7 +1027,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - GBRG - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - GBRG - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1038,7 +1038,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - GBRG - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - GBRG - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1058,7 +1058,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - GRBG - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - GRBG - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1069,7 +1069,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - GRBG - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - GRBG - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1089,7 +1089,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - RGGB - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - RGGB - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1100,7 +1100,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") convertTo(I_RGBA_16U, I_RGBA_8U); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "16-bit - RGGB - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "16-bit - RGGB - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1127,7 +1127,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - BGGR - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - BGGR - Bilinear - PSNR: " << PSNR <<" min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1137,7 +1137,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - BGGR - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - BGGR - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1157,7 +1157,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - GBRG - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - GBRG - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1167,7 +1167,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - GBRG - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - GBRG - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1187,7 +1187,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - GRBG - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - GRBG - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1197,7 +1197,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - GRBG - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - GRBG - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1217,7 +1217,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - RGGB - Bilinear - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - RGGB - Bilinear - PSNR: " << PSNR << " min required: " << min_PSNR_bilinear << std::endl; CHECK(PSNR >= min_PSNR_bilinear); } @@ -1227,7 +1227,7 @@ TEST_CASE("Bayer conversion", "[image_conversion]") I_Bayer_8U.getWidth(), I_Bayer_8U.getHeight()); double PSNR = computePSNR(I_RGBA_8U, I_RGBA_8U_ref); - std::cout << "8-bit - RGGB - Malvar - PSNR: " << PSNR << std::endl; + std::cout << "8-bit - RGGB - Malvar - PSNR: " << PSNR << " min required: " << min_PSNR_Malvar << std::endl; CHECK(PSNR >= min_PSNR_Malvar); } } @@ -1249,6 +1249,7 @@ int main(int argc, char *argv[]) // numFailed is clamped to 255 as some unices only use the lower 8 bits. // This clamping has already been applied, so just return it here // You can also do any post run clean-up here + std::cout << (numFailed ? "Test failed" : "Test succeed") << std::endl; return numFailed; } #else diff --git a/modules/core/test/image-with-dataset/testUndistortImage.cpp b/modules/core/test/image-with-dataset/testUndistortImage.cpp index cbe07c8476..3f871a0983 100644 --- a/modules/core/test/image-with-dataset/testUndistortImage.cpp +++ b/modules/core/test/image-with-dataset/testUndistortImage.cpp @@ -30,11 +30,7 @@ * * Description: * Test for image undistortion. - * - * Authors: - * Anthony Saunier - * -*****************************************************************************/ + */ #include #include @@ -45,15 +41,14 @@ #include #include #include + /*! \example testUndistortImage.cpp \brief Undistort an image. - Read an image from the disk, undistort it and save the - undistorted image on the disk. - - */ + Read an image from the disk, undistort it and save the undistorted image on the disk. +*/ // List of allowed command line options #define GETOPTARGS "cdi:o:t:s:h" @@ -200,7 +195,7 @@ int main(int argc, const char **argv) if (!env_ipath.empty()) ipath = env_ipath; -// Set the default output path + // Set the default output path #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX opt_opath = "/tmp"; #elif defined(_WIN32) @@ -229,7 +224,8 @@ int main(int argc, const char **argv) try { // Create the dirname vpIoTools::makeDirectory(opath); - } catch (...) { + } + catch (...) { usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; @@ -244,8 +240,8 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } @@ -254,9 +250,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; return EXIT_FAILURE; } @@ -279,7 +275,8 @@ int main(int argc, const char **argv) if (scale > 1) { std::cout << "Scale the image by a factor of " << scale << std::endl; vpImageTools::resize(I_, I, I_.getWidth() * scale, I_.getHeight() * scale); - } else { + } + else { I = I_; } std::cout << "Input image: " << I.getWidth() << "x" << I.getHeight() << std::endl; @@ -430,7 +427,8 @@ int main(int argc, const char **argv) vpImageIo::write(U_diff_gray, filename); return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp b/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp index 7974ed449e..1c818c46ea 100644 --- a/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp +++ b/modules/core/test/tools/histogram-with-dataset/testHistogram.cpp @@ -264,7 +264,7 @@ int main(int argc, const char **argv) int nbIterations = 100; unsigned int nbBins = 256; unsigned int sum_single_thread = 0; - unsigned int sum_single_multithread = 0; + unsigned int sum_multi_thread = 0; double t_single_thread = vpTime::measureTimeMs(); for (int iteration = 0; iteration < nbIterations; iteration++) { @@ -272,19 +272,19 @@ int main(int argc, const char **argv) } t_single_thread = vpTime::measureTimeMs() - t_single_thread; - double t_multithread = vpTime::measureTimeMs(); + double t_multi_thread = vpTime::measureTimeMs(); for (int iteration = 0; iteration < nbIterations; iteration++) { - sum_single_multithread = histogramSum(I, nbBins, nbThreads); + sum_multi_thread = histogramSum(I, nbBins, nbThreads); } - t_multithread = vpTime::measureTimeMs() - t_multithread; + t_multi_thread = vpTime::measureTimeMs() - t_multi_thread; std::cout << "sum_single_thread=" << sum_single_thread << " ; t_single_thread=" << t_single_thread << " ms ; mean=" << t_single_thread / (double)nbIterations << " ms" << std::endl; - std::cout << "sum_single_multithread=" << sum_single_multithread << " ; t_multithread=" << t_multithread - << " ms ; mean=" << t_multithread / (double)nbIterations << " ms" << std::endl; - std::cout << "Speed-up=" << t_single_thread / (double)t_multithread << "X" << std::endl; + std::cout << "sum_multi_thread (nbThreads=" << nbThreads << ")=" << sum_multi_thread << " ; t_multi_thread=" << t_multi_thread + << " ms ; mean=" << t_multi_thread / (double)nbIterations << " ms" << std::endl; + std::cout << "Speed-up=" << t_single_thread / (double)t_multi_thread << "X" << std::endl; - if (sum_single_thread != I.getSize() || sum_single_multithread != I.getSize()) { + if (sum_single_thread != I.getSize() || sum_multi_thread != I.getSize()) { std::cerr << "Problem with histogram!" << std::endl; return EXIT_FAILURE; } diff --git a/modules/core/test/tools/threading/testMutex.cpp b/modules/core/test/tools/threading/testMutex.cpp deleted file mode 100644 index 61e59352e7..0000000000 --- a/modules/core/test/tools/threading/testMutex.cpp +++ /dev/null @@ -1,98 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. - * - * This software is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * See the file LICENSE.txt at the root directory of this source - * distribution for additional information about the GNU GPL. - * - * For using ViSP with software that can not be combined with the GNU - * GPL, please contact Inria about acquiring a ViSP Professional - * Edition License. - * - * See https://visp.inria.fr for more information. - * - * This software was developed at: - * Inria Rennes - Bretagne Atlantique - * Campus Universitaire de Beaulieu - * 35042 Rennes Cedex - * France - * - * If you have questions regarding the use of this file, please contact - * Inria at visp@inria.fr - * - * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE - * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * - * Description: - * Test threading capabilities. - * -*****************************************************************************/ - -/*! - - \example testMutex.cpp - - \brief Test mutexes and threading capabilities. - -*/ - -#include - -#include -#include - -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) - -int thread_counter = 0; -vpMutex mutex; - -vpThread::Return doSomeThing(vpThread::Args args) -{ - mutex.lock(); - unsigned int thread_id = *((unsigned int *)args); - - std::cout << "Started job " << thread_counter << " with id " << thread_id << std::endl; - - for (unsigned long i = 0; i < (0xFFFF); i++) { - }; - - std::cout << "Ended job " << thread_counter << std::endl; - - thread_counter++; - mutex.unlock(); - - return 0; -} - -int main(void) -{ - unsigned int nthread = 10; - vpThread *thread = new vpThread[nthread]; - unsigned int *thread_id = new unsigned int[nthread]; - - for (unsigned int i = 0; i < nthread; i++) { - thread_id[i] = i; - thread[i].create((vpThread::Fn)&doSomeThing, (vpThread::Args)&thread_id[i]); - } - - delete[] thread; - delete[] thread_id; - - return EXIT_SUCCESS; -} - -#else -int main() -{ -#if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX - std::cout << "You should enable pthread usage and rebuild ViSP..." << std::endl; -#else - std::cout << "Multi-threading seems not supported on this platform" << std::endl; -#endif -} -#endif diff --git a/modules/core/test/tools/threading/testThread.cpp b/modules/core/test/tools/threading/testThread.cpp deleted file mode 100644 index f048d4b20b..0000000000 --- a/modules/core/test/tools/threading/testThread.cpp +++ /dev/null @@ -1,137 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. - * - * This software is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * See the file LICENSE.txt at the root directory of this source - * distribution for additional information about the GNU GPL. - * - * For using ViSP with software that can not be combined with the GNU - * GPL, please contact Inria about acquiring a ViSP Professional - * Edition License. - * - * See https://visp.inria.fr for more information. - * - * This software was developed at: - * Inria Rennes - Bretagne Atlantique - * Campus Universitaire de Beaulieu - * 35042 Rennes Cedex - * France - * - * If you have questions regarding the use of this file, please contact - * Inria at visp@inria.fr - * - * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE - * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * - * Description: - * Test threading capabilities. - * -*****************************************************************************/ - -/*! - - \example testThread.cpp - - \brief Test threading capabilities. - -*/ - -#include - -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) - -//! [Code] -#include - -#include -#include -#include - -vpMutex g_mutex_cout; - -vpThread::Return myFooFunction(vpThread::Args args) -{ - (void)(args); // Avoid warning: unused parameter args - // do stuff... - return 0; -} - -vpThread::Return myBarFunction(vpThread::Args args) -{ - (void)(args); // Avoid warning: unused parameter args - // do stuff... - return 0; -} - -vpThread::Return myQuxFunction(vpThread::Args args) -{ - unsigned int args_ = *((unsigned int *)args); - g_mutex_cout.lock(); - std::cout << "qux arg: " << args_ << std::endl; - g_mutex_cout.unlock(); - // do stuff... - return 0; -} - -int main() -{ - unsigned int qux_arg = 12; - vpThread foo; - vpThread bar((vpThread::Fn)myBarFunction); - vpThread qux((vpThread::Fn)myQuxFunction, - (vpThread::Args)&qux_arg); // Pass qux_arg to myQuxFunction() function - - vpTime::wait(1000); // Sleep 1s to ensure myQuxFunction() internal printings - g_mutex_cout.lock(); - std::cout << "Joinable after construction:" << std::endl; - std::cout << "foo: " << foo.joinable() << std::endl; - std::cout << "bar: " << bar.joinable() << std::endl; - std::cout << "qux: " << qux.joinable() << std::endl; - g_mutex_cout.unlock(); - - foo.create((vpThread::Fn)myFooFunction); - - g_mutex_cout.lock(); - std::cout << "Joinable after creation:" << std::endl; - std::cout << "foo: " << foo.joinable() << std::endl; - std::cout << "bar: " << bar.joinable() << std::endl; - std::cout << "qux: " << qux.joinable() << std::endl; - g_mutex_cout.unlock(); - - if (foo.joinable()) - foo.join(); - if (bar.joinable()) - bar.join(); - if (qux.joinable()) - qux.join(); - - g_mutex_cout.lock(); - std::cout << "Joinable after joining:" << std::endl; - std::cout << "foo: " << foo.joinable() << std::endl; - std::cout << "bar: " << bar.joinable() << std::endl; - std::cout << "qux: " << qux.joinable() << std::endl; - g_mutex_cout.unlock(); - - return EXIT_SUCCESS; -} -//! [Code] - -#else - -#include - -int main() -{ -#if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX - std::cout << "You should enable pthread usage and rebuild ViSP..." << std::endl; -#else - std::cout << "Multi-threading seems not supported on this platform" << std::endl; -#endif - return EXIT_SUCCESS; -} -#endif diff --git a/modules/core/test/tools/threading/testThread2.cpp b/modules/core/test/tools/threading/testThread2.cpp deleted file mode 100644 index 10ed60cfc5..0000000000 --- a/modules/core/test/tools/threading/testThread2.cpp +++ /dev/null @@ -1,205 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. - * - * This software is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * See the file LICENSE.txt at the root directory of this source - * distribution for additional information about the GNU GPL. - * - * For using ViSP with software that can not be combined with the GNU - * GPL, please contact Inria about acquiring a ViSP Professional - * Edition License. - * - * See https://visp.inria.fr for more information. - * - * This software was developed at: - * Inria Rennes - Bretagne Atlantique - * Campus Universitaire de Beaulieu - * 35042 Rennes Cedex - * France - * - * If you have questions regarding the use of this file, please contact - * Inria at visp@inria.fr - * - * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE - * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * - * Description: - * Test threading capabilities (extended). - * -*****************************************************************************/ - -/*! - \example testThread2.cpp - - \brief Test threading capabilities (extended). -*/ - -#include - -#if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) - -#include -#include -#include - -#include -#include -#include - -namespace -{ -//! [functor-thread-example declaration] -class vpArithmFunctor -{ -public: - vpArithmFunctor(const vpColVector &v1, const vpColVector &v2, unsigned int start, unsigned int end) - : m_add(), m_mul(), m_v1(v1), m_v2(v2), m_indexStart(start), m_indexEnd(end) - { } - - vpArithmFunctor() : m_add(), m_mul(), m_v1(), m_v2(), m_indexStart(0), m_indexEnd(0) { } - - void operator()() { computeImpl(); } - - vpColVector getVectorAdd() const { return m_add; } - - vpColVector getVectorMul() const { return m_mul; } - -private: - vpColVector m_add; - vpColVector m_mul; - vpColVector m_v1; - vpColVector m_v2; - unsigned int m_indexStart; - unsigned int m_indexEnd; - - void computeImpl() - { - m_add.resize(m_indexEnd - m_indexStart); - m_mul.resize(m_indexEnd - m_indexStart); - - // to simulate a long computation - for (int iter = 0; iter < 100; iter++) { - for (unsigned int i = m_indexStart, cpt = 0; i < m_indexEnd; i++, cpt++) { - m_add[cpt] = m_v1[i] + m_v2[i]; - m_mul[cpt] = m_v1[i] * m_v2[i]; - } - } - } -}; -//! [functor-thread-example declaration] - -//! [functor-thread-example threadFunction] -vpThread::Return arithmThread(vpThread::Args args) -{ - vpArithmFunctor *f = static_cast(args); - (*f)(); - return 0; -} -//! [functor-thread-example threadFunction] - -void insert(vpColVector &v1, const vpColVector &v2) -{ - unsigned int size = v1.size(); - v1.resize(size + v2.size(), false); - - for (unsigned int i = 0, cpt = size; i < v2.size(); i++, cpt++) { - v1[cpt] = v2[i]; - } -} - -bool check(const vpColVector &v1, const vpColVector &v2, const vpColVector &res_add, const vpColVector &res_mul) -{ - double add = 0.0, mul = 0.0; - for (unsigned int i = 0; i < v1.size(); i++) { - add += v1[i] + v2[i]; - mul += v1[i] * v2[i]; - } - - double add_th = res_add.sum(); - double mul_th = res_mul.sum(); - - std::cout << "add=" << add << " ; add_th=" << add_th << std::endl; - std::cout << "mul=" << mul << " ; mul_th=" << mul_th << std::endl; - - if (!vpMath::equal(add, add_th, std::numeric_limits::epsilon())) { - std::cerr << "Problem: add=" << add << " ; add_th=" << add_th << std::endl; - return false; - } - - if (!vpMath::equal(mul, mul_th, std::numeric_limits::epsilon())) { - std::cerr << "Problem: mul=" << mul << " ; mul_th=" << mul_th << std::endl; - return false; - } - - return true; -} -} // namespace - -int main() -{ - unsigned int nb_threads = 4; - unsigned int size = 1000007; - srand((unsigned int)time(nullptr)); - - vpColVector v1(size), v2(size); - for (unsigned int i = 0; i < size; i++) { - v1[i] = rand() % 101; - v2[i] = rand() % 101; - } - - //! [functor-thread-example threadCreation] - std::vector threads(nb_threads); - std::vector functors(nb_threads); - unsigned int split = size / nb_threads; - for (unsigned int i = 0; i < nb_threads; i++) { - if (i < nb_threads - 1) { - functors[i] = vpArithmFunctor(v1, v2, i * split, (i + 1) * split); - } - else { - functors[i] = vpArithmFunctor(v1, v2, i * split, size); - } - - std::cout << "Create thread: " << i << std::endl; - threads[i].create((vpThread::Fn)arithmThread, (vpThread::Args)&functors[i]); - } - //! [functor-thread-example threadCreation] - - //! [functor-thread-example getResults] - vpColVector res_add, res_mul; - for (size_t i = 0; i < nb_threads; i++) { - std::cout << "Join thread: " << i << std::endl; - threads[i].join(); - - insert(res_add, functors[i].getVectorAdd()); - insert(res_mul, functors[i].getVectorMul()); - } - //! [functor-thread-example getResults] - - if (!check(v1, v2, res_add, res_mul)) { - return EXIT_FAILURE; - } - - std::cout << "testThread2 is ok!" << std::endl; - return EXIT_SUCCESS; -} - -#else - -#include -#include - -int main() -{ -#if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX - std::cout << "You should enable pthread usage and rebuild ViSP..." << std::endl; -#else - std::cout << "Multi-threading seems not supported on this platform" << std::endl; -#endif - return EXIT_SUCCESS; -} -#endif diff --git a/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp b/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp index f8babbc1f4..bb17b37a4a 100644 --- a/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp +++ b/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp @@ -1179,7 +1179,6 @@ void vpDetectorDNNOpenCV::setParsingMethod(const DNNResultsParsingType &typePars } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDetectorDNNOpenCV.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDetectorDNNOpenCV.cpp.o) has no symbols void dummy_vpDetectorDNN() { }; #endif diff --git a/modules/detection/src/face/vpDetectorFace.cpp b/modules/detection/src/face/vpDetectorFace.cpp index ab62cdbcf3..be790f1cb7 100644 --- a/modules/detection/src/face/vpDetectorFace.cpp +++ b/modules/detection/src/face/vpDetectorFace.cpp @@ -46,7 +46,7 @@ bool vpSortLargestFace(cv::Rect rect1, cv::Rect rect2) { return (rect1.area() > /*! Default constructor. */ -vpDetectorFace::vpDetectorFace() : m_faces(), m_face_cascade(), m_frame_gray() {} +vpDetectorFace::vpDetectorFace() : m_faces(), m_face_cascade(), m_frame_gray() { } /*! Set the name of the OpenCV cascade classifier file used for face detection. @@ -141,7 +141,6 @@ bool vpDetectorFace::detect(const cv::Mat &frame_gray) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDetectorFace.cpp.o) has no -// symbols -void dummy_vpDetectorFace(){}; +// Work around to avoid warning: libvisp_core.a(vpDetectorFace.cpp.o) has no symbols +void dummy_vpDetectorFace() { }; #endif diff --git a/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h b/modules/gui/include/visp3/gui/vpColorBlindFriendlyPalette.h old mode 100755 new mode 100644 diff --git a/modules/gui/include/visp3/gui/vpPclViewer.h b/modules/gui/include/visp3/gui/vpPclViewer.h old mode 100755 new mode 100644 index ace4fb1363..28bc9ec785 --- a/modules/gui/include/visp3/gui/vpPclViewer.h +++ b/modules/gui/include/visp3/gui/vpPclViewer.h @@ -37,7 +37,7 @@ #include -#if defined(VISP_HAVE_PCL) +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) // System #include #include @@ -253,7 +253,7 @@ class VISP_EXPORT vpPclViewer std::thread m_threadDisplay; /*!< The non-blocking drawing thread.*/ bool m_hasToRun; /*!< If true, the drawing thread is running. Otherwise, it is stopped.*/ std::string m_title; /*!< The title of the viewer window.*/ - bool m_hasToSavePCDs; /*!< If true, thhe point clouds will be saved at each iteration of the drawing thread.*/ + bool m_hasToSavePCDs; /*!< If true, the point clouds will be saved at each iteration of the drawing thread.*/ std::string m_outFolder; /*!< If non empty, the path to the folders where the point clouds will be saved.*/ }; #endif // #if defined(VISP_HAVE_PCL) diff --git a/modules/gui/src/display/vpDisplayGTK.cpp b/modules/gui/src/display/vpDisplayGTK.cpp index b070bb9c85..6bb25f78f5 100644 --- a/modules/gui/src/display/vpDisplayGTK.cpp +++ b/modules/gui/src/display/vpDisplayGTK.cpp @@ -1589,7 +1589,6 @@ unsigned int vpDisplayGTK::getScreenHeight() } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayGTK.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayGTK.cpp.o) has no symbols void dummy_vpDisplayGTK() { }; #endif diff --git a/modules/gui/src/display/vpDisplayOpenCV.cpp b/modules/gui/src/display/vpDisplayOpenCV.cpp index d0b73d743d..a31918ab57 100644 --- a/modules/gui/src/display/vpDisplayOpenCV.cpp +++ b/modules/gui/src/display/vpDisplayOpenCV.cpp @@ -2174,7 +2174,6 @@ void vpDisplayOpenCV::overlay(std::function overlay_function, d } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayOpenCV.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayOpenCV.cpp.o) has no symbols void dummy_vpDisplayOpenCV() { }; #endif diff --git a/modules/gui/src/display/vpDisplayX.cpp b/modules/gui/src/display/vpDisplayX.cpp index bc9ec6d092..f2c42f3d1f 100644 --- a/modules/gui/src/display/vpDisplayX.cpp +++ b/modules/gui/src/display/vpDisplayX.cpp @@ -2661,7 +2661,6 @@ bool vpDisplayX::getPointerPosition(vpImagePoint &ip) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayX.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayX.cpp.o) has no symbols void dummy_vpDisplayX() { }; #endif diff --git a/modules/gui/src/display/windows/vpD3DRenderer.cpp b/modules/gui/src/display/windows/vpD3DRenderer.cpp index e2ce40fae9..caae08fa6e 100644 --- a/modules/gui/src/display/windows/vpD3DRenderer.cpp +++ b/modules/gui/src/display/windows/vpD3DRenderer.cpp @@ -1191,8 +1191,7 @@ void vpD3DRenderer::getImage(vpImage &I) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no symbols void dummy_vpD3DRenderer() { }; #endif #endif diff --git a/modules/gui/src/display/windows/vpDisplayD3D.cpp b/modules/gui/src/display/windows/vpDisplayD3D.cpp index a00ac23d59..ef67a63a1e 100644 --- a/modules/gui/src/display/windows/vpDisplayD3D.cpp +++ b/modules/gui/src/display/windows/vpDisplayD3D.cpp @@ -189,7 +189,6 @@ vpDisplayD3D::vpDisplayD3D(vpImage &I, int winx, int winy, const } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayD3D.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayD3D.cpp.o) has no symbols void dummy_vpDisplayD3D() { }; #endif diff --git a/modules/gui/src/display/windows/vpDisplayGDI.cpp b/modules/gui/src/display/windows/vpDisplayGDI.cpp index 5140f60cbc..37581e306a 100644 --- a/modules/gui/src/display/windows/vpDisplayGDI.cpp +++ b/modules/gui/src/display/windows/vpDisplayGDI.cpp @@ -189,7 +189,6 @@ vpDisplayGDI::vpDisplayGDI(vpImage &I, int winx, int winy, const } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayGDI.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayGDI.cpp.o) has no symbols void dummy_vpDisplayGDI() { }; #endif diff --git a/modules/gui/src/display/windows/vpDisplayWin32.cpp b/modules/gui/src/display/windows/vpDisplayWin32.cpp index 410db2674f..a8d5013761 100644 --- a/modules/gui/src/display/windows/vpDisplayWin32.cpp +++ b/modules/gui/src/display/windows/vpDisplayWin32.cpp @@ -906,7 +906,6 @@ unsigned int vpDisplayWin32::getScreenHeight() return height; } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayWin32.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpDisplayWin32.cpp.o) has no symbols void dummy_vpDisplayWin32() { }; #endif diff --git a/modules/gui/src/display/windows/vpGDIRenderer.cpp b/modules/gui/src/display/windows/vpGDIRenderer.cpp index eed3809185..7a8de6d807 100644 --- a/modules/gui/src/display/windows/vpGDIRenderer.cpp +++ b/modules/gui/src/display/windows/vpGDIRenderer.cpp @@ -1029,7 +1029,6 @@ void vpGDIRenderer::getImage(vpImage &I) } #endif #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpGDIRenderer.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpGDIRenderer.cpp.o) has no symbols void dummy_vpGDIRenderer() { }; #endif diff --git a/modules/gui/src/display/windows/vpWin32API.cpp b/modules/gui/src/display/windows/vpWin32API.cpp index 105853e7f4..ca65e445bd 100644 --- a/modules/gui/src/display/windows/vpWin32API.cpp +++ b/modules/gui/src/display/windows/vpWin32API.cpp @@ -50,7 +50,7 @@ DWORD vpProcessErrors(const std::string &api_name) FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM | FORMAT_MESSAGE_IGNORE_INSERTS, nullptr, err, MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (LPTSTR)&lpMsgBuf, 0, nullptr); std::cout << "call to " << api_name << " failed with the following error code: " << err << "(" << (LPTSTR)lpMsgBuf - << ")" << std::endl; + << ")" << std::endl; return err; } @@ -136,7 +136,6 @@ HBITMAP vpCreateBitmap(int nWidth, int nHeight, UINT cPlanes, UINT cBitsPerPel, } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpWin32API.cpp.o) has no -// symbols -void dummy_vpWin32API(){}; +// Work around to avoid warning: libvisp_core.a(vpWin32API.cpp.o) has no symbols +void dummy_vpWin32API() { }; #endif diff --git a/modules/gui/src/display/windows/vpWin32Window.cpp b/modules/gui/src/display/windows/vpWin32Window.cpp index 3b2a0962b6..2dd7d3c0d4 100644 --- a/modules/gui/src/display/windows/vpWin32Window.cpp +++ b/modules/gui/src/display/windows/vpWin32Window.cpp @@ -156,13 +156,13 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam) // case WM_SYSKEYUP: case WM_KEYDOWN: // case WM_KEYUP: - { - GetKeyNameText((LONG)lParam, window->lpString, - 10); // 10 is the size of lpString - // window->key = MapVirtualKey(wParam, MAPVK_VK_TO_CHAR); - vpReleaseSemaphore(window->semaKey, 1, nullptr); - break; - } + { + GetKeyNameText((LONG)lParam, window->lpString, + 10); // 10 is the size of lpString + // window->key = MapVirtualKey(wParam, MAPVK_VK_TO_CHAR); + vpReleaseSemaphore(window->semaKey, 1, nullptr); + break; + } case WM_COMMAND: @@ -298,9 +298,11 @@ void vpWin32Window::initWindow(const char *title, int posx, int posy, unsigned i if (val == -1) { std::cout << "GetMessage error:" << GetLastError() << std::endl; break; - } else if (val == 0) { + } + else if (val == 0) { break; - } else { + } + else { if (!TranslateAccelerator(msg.hwnd, nullptr, &msg)) { TranslateMessage(&msg); DispatchMessage(&msg); @@ -311,7 +313,6 @@ void vpWin32Window::initWindow(const char *title, int posx, int posy, unsigned i #endif #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpWin32Window.cpp.o) has no -// symbols -void dummy_vpWin32Window(){}; +// Work around to avoid warning: libvisp_core.a(vpWin32Window.cpp.o) has no symbols +void dummy_vpWin32Window() { }; #endif diff --git a/modules/gui/src/plot/vpPlotCurve.cpp b/modules/gui/src/plot/vpPlotCurve.cpp index c35ded35ee..ea4c221f73 100644 --- a/modules/gui/src/plot/vpPlotCurve.cpp +++ b/modules/gui/src/plot/vpPlotCurve.cpp @@ -46,9 +46,8 @@ #if defined(VISP_HAVE_DISPLAY) vpPlotCurve::vpPlotCurve() : color(vpColor::red), curveStyle(point), thickness(1), nbPoint(0), lastPoint(), pointListx(), pointListy(), - pointListz(), legend(), xmin(0), xmax(0), ymin(0), ymax(0) -{ -} + pointListz(), legend(), xmin(0), xmax(0), ymin(0), ymax(0) +{ } vpPlotCurve::~vpPlotCurve() { @@ -73,14 +72,16 @@ void vpPlotCurve::plotPoint(const vpImage &I, const vpImagePoint if (iP.get_i() <= lastPoint.get_i()) { top = iP.get_i() - 5; height = lastPoint.get_i() - top + 10; - } else { + } + else { top = lastPoint.get_i() - 5; height = iP.get_i() - top + 10; } if (iP.get_j() <= lastPoint.get_j()) { left = iP.get_j() - 5; width = lastPoint.get_j() - left + 10; - } else { + } + else { left = lastPoint.get_j() - 5; width = iP.get_j() - left + 10; } @@ -114,8 +115,7 @@ void vpPlotCurve::plotList(const vpImage &I, double xorg, double } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpPlotCurve.cpp.o) has no -// symbols -void dummy_vpPlotCurve(){}; +// Work around to avoid warning: libvisp_core.a(vpPlotCurve.cpp.o) has no symbols +void dummy_vpPlotCurve() { }; #endif #endif diff --git a/modules/gui/src/plot/vpPlotGraph.cpp b/modules/gui/src/plot/vpPlotGraph.cpp index 8ba2d3c383..d27f45d54a 100644 --- a/modules/gui/src/plot/vpPlotGraph.cpp +++ b/modules/gui/src/plot/vpPlotGraph.cpp @@ -1339,8 +1339,7 @@ vpHomogeneousMatrix vpPlotGraph::navigation(const vpImage &I, boo } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpPlotGraph.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpPlotGraph.cpp.o) has no symbols void dummy_vpPlotGraph() { }; #endif #endif diff --git a/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp b/modules/gui/src/pointcloud/vpColorBlindFriendlyPalette.cpp old mode 100755 new mode 100644 diff --git a/modules/gui/src/pointcloud/vpPclViewer.cpp b/modules/gui/src/pointcloud/vpPclViewer.cpp old mode 100755 new mode 100644 index 93e14b888d..efeda9ee89 --- a/modules/gui/src/pointcloud/vpPclViewer.cpp +++ b/modules/gui/src/pointcloud/vpPclViewer.cpp @@ -35,7 +35,7 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS #include -#if defined(VISP_HAVE_PCL) +#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_THREADS) // PCL #include @@ -487,8 +487,7 @@ void vpPclViewer::threadUpdateSurfaceOriginalColor(const pclPointCloudPointXYZRG } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no symbols void dummy_vpPCLPointCLoudVisualization() { }; #endif #endif diff --git a/modules/io/include/visp3/io/vpImageQueue.h b/modules/io/include/visp3/io/vpImageQueue.h index 75381cd77a..e7869d1036 100644 --- a/modules/io/include/visp3/io/vpImageQueue.h +++ b/modules/io/include/visp3/io/vpImageQueue.h @@ -36,7 +36,7 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/io/include/visp3/io/vpImageStorageWorker.h b/modules/io/include/visp3/io/vpImageStorageWorker.h index 9fc16fab51..1eb0e79b2b 100644 --- a/modules/io/include/visp3/io/vpImageStorageWorker.h +++ b/modules/io/include/visp3/io/vpImageStorageWorker.h @@ -36,7 +36,7 @@ #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/io/src/parallel-port/vpParallelPort.cpp b/modules/io/src/parallel-port/vpParallelPort.cpp index c8c0edd62e..26d39c4533 100644 --- a/modules/io/src/parallel-port/vpParallelPort.cpp +++ b/modules/io/src/parallel-port/vpParallelPort.cpp @@ -159,7 +159,6 @@ void vpParallelPort::close() } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpParallelPort.cpp.o) has no -// symbols -void dummy_vpParallelPort(){}; +// Work around to avoid warning: libvisp_core.a(vpParallelPort.cpp.o) has no symbols +void dummy_vpParallelPort() { }; #endif diff --git a/modules/io/test/image-with-dataset/perfImageLoadSave.cpp b/modules/io/test/image-with-dataset/perfImageLoadSave.cpp index 93d5d3dfd1..815525b09f 100644 --- a/modules/io/test/image-with-dataset/perfImageLoadSave.cpp +++ b/modules/io/test/image-with-dataset/perfImageLoadSave.cpp @@ -35,7 +35,7 @@ #include -#ifdef VISP_HAVE_CATCH2 +#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/io/test/image-with-dataset/testImageLoadSave.cpp b/modules/io/test/image-with-dataset/testImageLoadSave.cpp index a58ccb560a..3d3ae6d855 100644 --- a/modules/io/test/image-with-dataset/testImageLoadSave.cpp +++ b/modules/io/test/image-with-dataset/testImageLoadSave.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_CATCH2) && (VISP_HAVE_DATASET_VERSION >= 0x030500) +#if defined(VISP_HAVE_CATCH2) && (VISP_HAVE_DATASET_VERSION >= 0x030500) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/java/generator/gen2.py b/modules/java/generator/gen2.py old mode 100755 new mode 100644 diff --git a/modules/java/generator/gen_java.py b/modules/java/generator/gen_java.py old mode 100755 new mode 100644 diff --git a/modules/java/generator/hdr_parser.py b/modules/java/generator/hdr_parser.py old mode 100755 new mode 100644 diff --git a/modules/robot/include/visp3/robot/vpPololu.h b/modules/robot/include/visp3/robot/vpPololu.h index 372fa46cf1..a4c16e6bba 100644 --- a/modules/robot/include/visp3/robot/vpPololu.h +++ b/modules/robot/include/visp3/robot/vpPololu.h @@ -36,7 +36,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpQbDevice.h b/modules/robot/include/visp3/robot/vpQbDevice.h index 8d72d6cc34..034df6731e 100644 --- a/modules/robot/include/visp3/robot/vpQbDevice.h +++ b/modules/robot/include/visp3/robot/vpQbDevice.h @@ -37,7 +37,7 @@ #define _vpQbDevice_h_ #include -#ifdef VISP_HAVE_QBDEVICE +#if defined(VISP_HAVE_QBDEVICE) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpQbSoftHand.h b/modules/robot/include/visp3/robot/vpQbSoftHand.h index d4dbd9995a..3b26d947fc 100644 --- a/modules/robot/include/visp3/robot/vpQbSoftHand.h +++ b/modules/robot/include/visp3/robot/vpQbSoftHand.h @@ -35,7 +35,7 @@ #define _vpQbSoftHand_h_ #include -#ifdef VISP_HAVE_QBDEVICE +#if defined(VISP_HAVE_QBDEVICE) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpRobotBebop2.h b/modules/robot/include/visp3/robot/vpRobotBebop2.h index 5261436a0d..3c4576607b 100644 --- a/modules/robot/include/visp3/robot/vpRobotBebop2.h +++ b/modules/robot/include/visp3/robot/vpRobotBebop2.h @@ -41,7 +41,7 @@ #include -#ifdef VISP_HAVE_ARSDK +#if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/robot/include/visp3/robot/vpRobotBiclops.h b/modules/robot/include/visp3/robot/vpRobotBiclops.h index 0c6999c7e6..d4c0ac0416 100644 --- a/modules/robot/include/visp3/robot/vpRobotBiclops.h +++ b/modules/robot/include/visp3/robot/vpRobotBiclops.h @@ -36,7 +36,7 @@ #include -#ifdef VISP_HAVE_BICLOPS +#if defined(VISP_HAVE_BICLOPS) && defined(VISP_HAVE_THREADS) /* ------------------------------------------------------------------------ */ /* --- INCLUDES ----------------------------------------------------------- */ diff --git a/modules/robot/include/visp3/robot/vpRobotFranka.h b/modules/robot/include/visp3/robot/vpRobotFranka.h index c7d23ad620..f07ea3e808 100644 --- a/modules/robot/include/visp3/robot/vpRobotFranka.h +++ b/modules/robot/include/visp3/robot/vpRobotFranka.h @@ -36,7 +36,7 @@ #include -#ifdef VISP_HAVE_FRANKA +#if defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpRobotMavsdk.h b/modules/robot/include/visp3/robot/vpRobotMavsdk.h index 5b6bba8156..376fcd2025 100644 --- a/modules/robot/include/visp3/robot/vpRobotMavsdk.h +++ b/modules/robot/include/visp3/robot/vpRobotMavsdk.h @@ -40,7 +40,8 @@ // Check if std:c++17 or higher. // Here we cannot use (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) in the declaration of the class -#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) +#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \ + && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpRobotPololuPtu.h b/modules/robot/include/visp3/robot/vpRobotPololuPtu.h index aacac886f3..30031bba61 100644 --- a/modules/robot/include/visp3/robot/vpRobotPololuPtu.h +++ b/modules/robot/include/visp3/robot/vpRobotPololuPtu.h @@ -36,7 +36,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h b/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h index 3bb77f9b16..a84db8f60c 100644 --- a/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h +++ b/modules/robot/include/visp3/robot/vpRobotWireFrameSimulator.h @@ -41,20 +41,14 @@ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include // std::fabs #include // numeric_limits -#if defined(_WIN32) -// Include WinSock2.h before windows.h to ensure that winsock.h is not -// included by windows.h since winsock.h and winsock2.h are incompatible -#include -#include -#elif defined(VISP_HAVE_PTHREAD) -#include -#endif -#include +#include +#include + #include #include #include @@ -114,23 +108,18 @@ class VISP_EXPORT vpRobotWireFrameSimulator : protected vpWireFrameSimulator, pu /*! The velocity in the current frame (articular, camera or reference)*/ vpColVector velocity; -#if defined(_WIN32) - HANDLE hThread; -#elif defined(VISP_HAVE_PTHREAD) - pthread_t thread; - pthread_attr_t attr; -#endif + std::thread *m_thread; - vpMutex m_mutex_fMi; - vpMutex m_mutex_eMc; - vpMutex m_mutex_artVel; - vpMutex m_mutex_artCoord; - vpMutex m_mutex_velocity; - vpMutex m_mutex_display; - vpMutex m_mutex_robotStop; - vpMutex m_mutex_frame; - vpMutex m_mutex_setVelocityCalled; - vpMutex m_mutex_scene; + std::mutex m_mutex_fMi; + std::mutex m_mutex_eMc; + std::mutex m_mutex_artVel; + std::mutex m_mutex_artCoord; + std::mutex m_mutex_velocity; + std::mutex m_mutex_display; + std::mutex m_mutex_robotStop; + std::mutex m_mutex_frame; + std::mutex m_mutex_setVelocityCalled; + std::mutex m_mutex_scene; bool displayBusy; @@ -335,26 +324,18 @@ class VISP_EXPORT vpRobotWireFrameSimulator : protected vpWireFrameSimulator, pu /** @name Protected Member Functions Inherited from vpRobotWireFrameSimulator */ //@{ -/*! - * Function used to launch the thread which moves the robot. - */ -#if defined(_WIN32) - static DWORD WINAPI launcher(LPVOID lpParam) - { - (static_cast(lpParam))->updateArticularPosition(); - return 0; - } -#elif defined(VISP_HAVE_PTHREAD) - static void *launcher(void *arg) + /*! + * Function used to launch the thread which moves the robot. + */ + static void launcher(vpRobotWireFrameSimulator &simulator) { - (reinterpret_cast(arg))->updateArticularPosition(); - // pthread_exit((void*) 0); - return nullptr; + simulator.updateArticularPosition(); } -#endif - /*! Method lauched by the thread to compute the position of the robot in the - * articular frame. */ + /*! + * Method launched by the thread to compute the position of the robot in the + * articular frame. + */ virtual void updateArticularPosition() = 0; /*! Method used to check if the robot reached a joint limit. */ virtual int isInJointLimit() = 0; diff --git a/modules/robot/include/visp3/robot/vpSimulatorAfma6.h b/modules/robot/include/visp3/robot/vpSimulatorAfma6.h index bfbc62e863..b15ebe6bdf 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorAfma6.h +++ b/modules/robot/include/visp3/robot/vpSimulatorAfma6.h @@ -44,7 +44,7 @@ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) /*! * \class vpSimulatorAfma6 diff --git a/modules/robot/include/visp3/robot/vpSimulatorViper850.h b/modules/robot/include/visp3/robot/vpSimulatorViper850.h index fe39abee69..854f7646f9 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorViper850.h +++ b/modules/robot/include/visp3/robot/vpSimulatorViper850.h @@ -40,7 +40,7 @@ */ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp b/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp index 20792b37d3..7c022269f1 100644 --- a/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp +++ b/modules/robot/src/haptic-device/qbdevice/vpQbDevice.cpp @@ -34,7 +34,7 @@ *****************************************************************************/ #include -#ifdef VISP_HAVE_QBDEVICE +#if defined(VISP_HAVE_QBDEVICE) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp b/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp index 5c8aca7159..5f5e3c3322 100644 --- a/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp +++ b/modules/robot/src/haptic-device/qbdevice/vpQbSoftHand.cpp @@ -34,7 +34,7 @@ *****************************************************************************/ #include -#ifdef VISP_HAVE_QBDEVICE +#if defined(VISP_HAVE_QBDEVICE) && defined(VISP_HAVE_THREADS) #include diff --git a/modules/robot/src/light/vpRingLight.cpp b/modules/robot/src/light/vpRingLight.cpp index 193e882168..27f469e6ea 100644 --- a/modules/robot/src/light/vpRingLight.cpp +++ b/modules/robot/src/light/vpRingLight.cpp @@ -214,7 +214,6 @@ void vpRingLight::off() } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRingLight.cpp.o) has no -// symbols -void dummy_vpRingLight(){}; +// Work around to avoid warning: libvisp_robot.a(vpRingLight.cpp.o) has no symbols +void dummy_vpRingLight() { }; #endif diff --git a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp index c79d06eb55..f03344475b 100644 --- a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp +++ b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp @@ -1754,7 +1754,6 @@ void vpRobotAfma4::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotAfma4.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotAfma4.cpp.o) has no symbols void dummy_vpRobotAfma4() { }; #endif diff --git a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp index 80f1a4d1f9..73709afcb9 100644 --- a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp +++ b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp @@ -187,8 +187,9 @@ vpRobotAfma6::vpRobotAfma6(bool verbose) : vpAfma6(), vpRobot() try { this->init(); this->setRobotState(vpRobot::STATE_STOP); - } catch (...) { - // vpERROR_TRACE("Error caught") ; + } + catch (...) { + // vpERROR_TRACE("Error caught") ; throw; } positioningVelocity = defaultPositioningVelocity; @@ -602,9 +603,10 @@ vpRobot::vpRobotStateType vpRobotAfma6::setRobotState(vpRobot::vpRobotStateType if (vpRobot::STATE_VELOCITY_CONTROL == getRobotState()) { std::cout << "Change the control mode from velocity to position control.\n"; Try(PrimitiveSTOP_Afma6()); - } else { - // std::cout << "Change the control mode from stop to position - // control.\n"; + } + else { + // std::cout << "Change the control mode from stop to position + // control.\n"; } this->powerOn(); break; @@ -672,20 +674,23 @@ void vpRobotAfma6::powerOn(void) Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus)); if (EStopStatus == ESTOP_AUTO) { break; // exit for loop - } else if (EStopStatus == ESTOP_MANUAL) { + } + else if (EStopStatus == ESTOP_MANUAL) { break; // exit for loop - } else if (EStopStatus == ESTOP_ACTIVATED) { + } + else if (EStopStatus == ESTOP_ACTIVATED) { if (firsttime) { std::cout << "Emergency stop is activated! \n" - << "Check the emergency stop button and push the yellow " - "button before continuing." - << std::endl; + << "Check the emergency stop button and push the yellow " + "button before continuing." + << std::endl; firsttime = false; } fprintf(stdout, "Remaining time %us \r", nitermax - i); fflush(stdout); CAL_Wait(1); - } else { + } + else { std::cout << "Sorry there is an error on the emergency chain." << std::endl; std::cout << "You have to call Adept for maintenance..." << std::endl; // Free allocated resources @@ -835,7 +840,8 @@ void vpRobotAfma6::get_eJe(vpMatrix &eJe) try { vpAfma6::get_eJe(q, eJe); - } catch (...) { + } + catch (...) { vpERROR_TRACE("catch exception "); throw; } @@ -879,7 +885,8 @@ void vpRobotAfma6::get_fJe(vpMatrix &fJe) try { vpAfma6::get_fJe(q, fJe); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -1149,8 +1156,9 @@ void vpRobotAfma6::setPosition(const vpRobot::vpControlFrameType frame, const vp } Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity)); Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000)); - } else { - // Cartesian position is out of range + } + else { + // Cartesian position is out of range error = -1; } @@ -1186,8 +1194,9 @@ void vpRobotAfma6::setPosition(const vpRobot::vpControlFrameType frame, const vp } Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity)); Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000)); - } else { - // Cartesian position is out of range + } + else { + // Cartesian position is out of range error = -1; } @@ -1298,7 +1307,8 @@ void vpRobotAfma6::setPosition(const vpRobot::vpControlFrameType frame, double p position[5] = pos6; setPosition(frame, position); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -1674,12 +1684,14 @@ void vpRobotAfma6::setVelocity(const vpRobot::vpControlFrameType frame, const vp if (axisInJoint[i]) std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl; } - } else { + } + else { printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt); if (TryString != nullptr) { // The statement is in TryString, but we need to check the validity printf(" Error sentence %s\n", TryString); // Print the TryString - } else { + } + else { printf("\n"); } } @@ -1823,7 +1835,8 @@ void vpRobotAfma6::getVelocity(const vpRobot::vpControlFrameType frame, vpColVec "vpRobotAfma6::getVelocity() not implemented in end-effector")); } } - } else { + } + else { first_time_getvel = false; } @@ -2239,7 +2252,8 @@ void vpRobotAfma6::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto return; } } - } else { + } + else { first_time_getdis = false; } @@ -2279,7 +2293,8 @@ bool vpRobotAfma6::checkJointLimits(vpColVector &jointsStatus) std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl; jointsStatus[i] = axisInJoint[i]; status = false; - } else { + } + else { jointsStatus[i] = 0; } } @@ -2294,7 +2309,6 @@ bool vpRobotAfma6::checkJointLimits(vpColVector &jointsStatus) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotAfma6.cpp.o) has no -// symbols -void dummy_vpRobotAfma6(){}; +// Work around to avoid warning: libvisp_robot.a(vpRobotAfma6.cpp.o) has no symbols +void dummy_vpRobotAfma6() { }; #endif diff --git a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp index 893258a983..4744a3d099 100644 --- a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp +++ b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp @@ -33,7 +33,7 @@ #include -#ifdef VISP_HAVE_BICLOPS +#if defined(VISP_HAVE_BICLOPS) && defined(VISP_HAVE_THREADS) #include // std::fabs #include @@ -854,7 +854,6 @@ void vpRobotBiclops::getDisplacement(vpRobot::vpControlFrameType frame, vpColVec } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotBiclops.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotBiclops.cpp.o) has no symbols void dummy_vpRobotBiclops() { }; #endif diff --git a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp index 5a7015e323..5885ca333c 100644 --- a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp +++ b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp @@ -35,7 +35,7 @@ #include -#ifdef VISP_HAVE_FRANKA +#if defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp index 1aafc581e8..54792a5670 100644 --- a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp +++ b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp @@ -36,7 +36,8 @@ #include // Check if std:c++17 or higher -#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) +#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \ + && defined(VISP_HAVE_THREADS) #include #include @@ -1579,7 +1580,6 @@ void vpRobotMavsdk::setVerbose(bool verbose) { m_impl->setVerbose(verbose); } bool vpRobotMavsdk::hasFlyingCapability() { return m_impl->getFlyingCapability(); } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotMavsdk.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotMavsdk.cpp.o) has no symbols void dummy_vpRobotMavsdk() { }; #endif diff --git a/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp b/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp index 6c47d0bb0e..84658c4d3f 100644 --- a/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp +++ b/modules/robot/src/real-robot/pioneer/vpRobotPioneer.cpp @@ -124,7 +124,8 @@ void vpRobotPioneer::setVelocity(const vpRobot::vpControlFrameType frame, const this->setVel(vel_sat[0] * 1000.); // convert velocity in mm/s this->setRotVel(vpMath::deg(vel_sat[1])); // convert velocity in deg/s this->unlock(); - } else if (frame == vpRobot::ARTICULAR_FRAME) { + } + else if (frame == vpRobot::ARTICULAR_FRAME) { vel_max[0] = getMaxTranslationVelocity(); vel_max[1] = getMaxTranslationVelocity(); @@ -134,7 +135,8 @@ void vpRobotPioneer::setVelocity(const vpRobot::vpControlFrameType frame, const this->setVel2(vel_sat[0] * 1000., vel_sat[1] * 1000.); // convert velocity in mm/s this->unlock(); - } else { + } + else { throw vpRobotException(vpRobotException::wrongStateError, "Cannot send the robot velocity in the specified control frame"); } @@ -193,12 +195,14 @@ void vpRobotPioneer::getVelocity(const vpRobot::vpControlFrameType frame, vpColV velocity[0] = this->getLeftVel() / 1000.; velocity[1] = this->getRightVel() / 1000; this->unlock(); - } else if (frame == vpRobot::REFERENCE_FRAME) { + } + else if (frame == vpRobot::REFERENCE_FRAME) { this->lock(); velocity[0] = this->getVel() / 1000.; velocity[1] = vpMath::rad(this->getRotVel()); this->unlock(); - } else { + } + else { throw vpRobotException(vpRobotException::wrongStateError, "Cannot get the robot volocity in the specified control frame"); } @@ -232,7 +236,6 @@ vpColVector vpRobotPioneer::getVelocity(const vpRobot::vpControlFrameType frame) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotPioneer.cpp.o) has no -// symbols -void dummy_vpRobotPioneer(){}; +// Work around to avoid warning: libvisp_robot.a(vpRobotPioneer.cpp.o) has no symbols +void dummy_vpRobotPioneer() { }; #endif diff --git a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp index ad20ba4d31..43cc96719d 100644 --- a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp +++ b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp @@ -34,7 +34,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp b/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp index be3c57a42c..253dce7c61 100644 --- a/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp +++ b/modules/robot/src/real-robot/pololu-maestro/vpRobotPololuPtu.cpp @@ -33,8 +33,7 @@ #include - -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp b/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp index 4bbe8acef2..262dc2f5d7 100644 --- a/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp +++ b/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp @@ -770,7 +770,6 @@ void vpRobotPtu46::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotPtu46.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotPtu46.cpp.o) has no symbols void dummy_vpRobotPtu46() { }; #endif diff --git a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp index 64e5cd3b8f..daed273a17 100644 --- a/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp +++ b/modules/robot/src/real-robot/universal-robots/vpRobotUniversalRobots.cpp @@ -874,7 +874,6 @@ vpRobot::vpRobotStateType vpRobotUniversalRobots::setRobotState(vpRobot::vpRobot } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotUniversalRobots.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotUniversalRobots.cpp.o) has no symbols void dummy_vpRobotUniversalRobots() { }; #endif diff --git a/modules/robot/src/robot-simulator/vpRobotCamera.cpp b/modules/robot/src/robot-simulator/vpRobotCamera.cpp index d9eecf8d4a..5d632ece76 100644 --- a/modules/robot/src/robot-simulator/vpRobotCamera.cpp +++ b/modules/robot/src/robot-simulator/vpRobotCamera.cpp @@ -248,7 +248,6 @@ void vpRobotCamera::setPosition(const vpHomogeneousMatrix &cMw) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_robot.a(vpRobotCamera.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_robot.a(vpRobotCamera.cpp.o) has no symbols void dummy_vpRobotCamera() { }; #endif diff --git a/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp b/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp index f45e033005..9e5d3e32f9 100644 --- a/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp +++ b/modules/robot/src/robot-simulator/vpRobotWireFrameSimulator.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include #include @@ -48,14 +48,10 @@ */ vpRobotWireFrameSimulator::vpRobotWireFrameSimulator() : vpWireFrameSimulator(), vpRobotSimulator(), I(), tcur(0), tprev(0), robotArms(nullptr), size_fMi(8), fMi(nullptr), - artCoord(), artVel(), velocity(), -#if defined(_WIN32) -#elif defined(VISP_HAVE_PTHREAD) - thread(), attr(), -#endif - m_mutex_fMi(), m_mutex_eMc(), m_mutex_artVel(), m_mutex_artCoord(), m_mutex_velocity(), m_mutex_display(), m_mutex_robotStop(), m_mutex_frame(), m_mutex_setVelocityCalled(), m_mutex_scene(), - displayBusy(false), - robotStop(false), jointLimit(false), jointLimitArt(false), singularityManagement(true), cameraParam(), + artCoord(), artVel(), velocity(), m_thread(), m_mutex_fMi(), m_mutex_eMc(), m_mutex_artVel(), m_mutex_artCoord(), + m_mutex_velocity(), m_mutex_display(), m_mutex_robotStop(), m_mutex_frame(), m_mutex_setVelocityCalled(), + m_mutex_scene(), displayBusy(false), robotStop(false), jointLimit(false), jointLimitArt(false), + singularityManagement(true), cameraParam(), #if defined(VISP_HAVE_DISPLAY) display(), #endif @@ -77,12 +73,8 @@ vpRobotWireFrameSimulator::vpRobotWireFrameSimulator() */ vpRobotWireFrameSimulator::vpRobotWireFrameSimulator(bool do_display) : vpWireFrameSimulator(), vpRobotSimulator(), I(), tcur(0), tprev(0), robotArms(nullptr), size_fMi(8), fMi(nullptr), - artCoord(), artVel(), velocity(), -#if defined(_WIN32) -#elif defined(VISP_HAVE_PTHREAD) - thread(), attr(), -#endif - m_mutex_fMi(), m_mutex_eMc(), m_mutex_artVel(), m_mutex_artCoord(), m_mutex_velocity(), m_mutex_display(), m_mutex_robotStop(), m_mutex_frame(), m_mutex_setVelocityCalled(), m_mutex_scene(), + artCoord(), artVel(), velocity(), m_thread(), m_mutex_fMi(), m_mutex_eMc(), m_mutex_artVel(), m_mutex_artCoord(), + m_mutex_velocity(), m_mutex_display(), m_mutex_robotStop(), m_mutex_frame(), m_mutex_setVelocityCalled(), m_mutex_scene(), displayBusy(false), robotStop(false), jointLimit(false), jointLimitArt(false), singularityManagement(true), cameraParam(), #if defined(VISP_HAVE_DISPLAY) diff --git a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp index ae1d7c870d..0e589be88c 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp @@ -34,7 +34,7 @@ *****************************************************************************/ #include -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include // std::fabs #include // numeric_limits #include @@ -58,27 +58,14 @@ const double vpSimulatorAfma6::defaultPositioningVelocity = 25.0; */ vpSimulatorAfma6::vpSimulatorAfma6() : vpRobotWireFrameSimulator(), vpAfma6(), q_prev_getdis(), first_time_getdis(true), - positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() + positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() { init(); initDisplay(); tcur = vpTime::measureTimeMs(); -#if defined(_WIN32) - DWORD dwThreadIdArray; - hThread = CreateThread(nullptr, // default security attributes - 0, // use default stack size - launcher, // thread function name - this, // argument to thread function - 0, // use default creation flags - &dwThreadIdArray); // returns the thread identifier -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - - pthread_create(&thread, nullptr, launcher, (void *)this); -#endif + m_thread = new std::thread(&launcher, std::ref(*this)); compute_fMi(); } @@ -91,27 +78,14 @@ vpSimulatorAfma6::vpSimulatorAfma6() */ vpSimulatorAfma6::vpSimulatorAfma6(bool do_display) : vpRobotWireFrameSimulator(do_display), q_prev_getdis(), first_time_getdis(true), - positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() + positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() { init(); initDisplay(); tcur = vpTime::measureTimeMs(); -#if defined(_WIN32) - DWORD dwThreadIdArray; - hThread = CreateThread(nullptr, // default security attributes - 0, // use default stack size - launcher, // thread function name - this, // argument to thread function - 0, // use default creation flags - &dwThreadIdArray); // returns the thread identifier -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - - pthread_create(&thread, nullptr, launcher, (void *)this); -#endif + m_thread = new std::thread(&launcher, std::ref(*this)); compute_fMi(); } @@ -125,17 +99,7 @@ vpSimulatorAfma6::~vpSimulatorAfma6() robotStop = true; m_mutex_robotStop.unlock(); -#if defined(_WIN32) -#if defined(WINRT_8_1) - WaitForSingleObjectEx(hThread, INFINITE, FALSE); -#else // pure win32 - WaitForSingleObject(hThread, INFINITE); -#endif - CloseHandle(hThread); -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_destroy(&attr); - pthread_join(thread, nullptr); -#endif + m_thread->join(); if (robotArms != nullptr) { for (int i = 0; i < 6; i++) @@ -144,6 +108,7 @@ vpSimulatorAfma6::~vpSimulatorAfma6() delete[] robotArms; delete[] fMi; + delete m_thread; } /*! @@ -170,7 +135,8 @@ void vpSimulatorAfma6::init() try { arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR"); std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl; - } catch (...) { + } + catch (...) { std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl; } } @@ -383,9 +349,10 @@ void vpSimulatorAfma6::getCameraParameters(vpCameraParameters &cam, const unsign // Set default intrinsic camera parameters for 640x480 images if (image_width == 640 && image_height == 480) { std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" - << std::endl; + << std::endl; cam.initPersProjWithoutDistortion(1109.5735473989, 1112.1520168160, 320, 240); - } else { + } + else { vpTRACE("Cannot get default intrinsic camera parameters for this image " "resolution"); } @@ -395,9 +362,10 @@ void vpSimulatorAfma6::getCameraParameters(vpCameraParameters &cam, const unsign // Set default intrinsic camera parameters for 640x480 images if (image_width == 640 && image_height == 480) { std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" - << std::endl; + << std::endl; cam.initPersProjWithoutDistortion(852.6583228197, 854.8084224761, 320, 240); - } else { + } + else { vpTRACE("Cannot get default intrinsic camera parameters for this image " "resolution"); } @@ -505,12 +473,13 @@ void vpSimulatorAfma6::updateArticularPosition() if (art <= _joint_min[jointLimitArt - 1] || art >= _joint_max[jointLimitArt - 1]) { if (verbose_) { std::cout << "Joint " << jointLimitArt - 1 - << " reaches a limit: " << vpMath::deg(_joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art) - << " < " << vpMath::deg(_joint_max[jointLimitArt - 1]) << std::endl; + << " reaches a limit: " << vpMath::deg(_joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art) + << " < " << vpMath::deg(_joint_max[jointLimitArt - 1]) << std::endl; } articularVelocities = 0.0; - } else + } + else jointLimit = false; } @@ -526,10 +495,10 @@ void vpSimulatorAfma6::updateArticularPosition() if (jl != 0 && jointLimit == false) { if (jl < 0) ellapsedTime = (_joint_min[(unsigned int)(-jl - 1)] - articularCoordinates[(unsigned int)(-jl - 1)]) / - (articularVelocities[(unsigned int)(-jl - 1)]); + (articularVelocities[(unsigned int)(-jl - 1)]); else ellapsedTime = (_joint_max[(unsigned int)(jl - 1)] - articularCoordinates[(unsigned int)(jl - 1)]) / - (articularVelocities[(unsigned int)(jl - 1)]); + (articularVelocities[(unsigned int)(jl - 1)]); for (unsigned int i = 0; i < 6; i++) articularCoordinates[i] = articularCoordinates[i] + ellapsedTime * articularVelocities[i]; @@ -589,7 +558,8 @@ void vpSimulatorAfma6::updateArticularPosition() vpTime::wait(tcur, 1000 * getSamplingTime()); tcur_1 = tcur; - } else { + } + else { vpTime::wait(tcur, vpTime::getMinTimeForUsleepCall()); } @@ -759,9 +729,10 @@ vpRobot::vpRobotStateType vpSimulatorAfma6::setRobotState(vpRobot::vpRobotStateT if (vpRobot::STATE_VELOCITY_CONTROL == getRobotState()) { std::cout << "Change the control mode from velocity to position control.\n"; stopMotion(); - } else { - // std::cout << "Change the control mode from stop to position - // control.\n"; + } + else { + // std::cout << "Change the control mode from stop to position + // control.\n"; } break; } @@ -1352,7 +1323,8 @@ void vpSimulatorAfma6::setPosition(const vpRobot::vpControlFrameType frame, cons set_velocity(error); break; } - } else { + } + else { vpERROR_TRACE("Positioning error."); throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range."); } @@ -1415,7 +1387,8 @@ void vpSimulatorAfma6::setPosition(const vpRobot::vpControlFrameType frame, cons set_velocity(error); break; } - } else + } + else vpERROR_TRACE("Positioning error. Position unreachable"); } while (errsqr > 1e-8 && nbSol > 0); break; @@ -1508,7 +1481,8 @@ void vpSimulatorAfma6::setPosition(const vpRobot::vpControlFrameType frame, doub position[5] = pos6; setPosition(frame, position); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -1833,7 +1807,7 @@ int vpSimulatorAfma6::isInJointLimit() if (artNumb != 0) std::cout << "\nWarning: Velocity control stopped: axis " << fabs((float)artNumb) << " on joint limit!" - << std::endl; + << std::endl; return artNumb; } @@ -1886,7 +1860,8 @@ void vpSimulatorAfma6::getDisplacement(vpRobot::vpControlFrameType frame, vpColV return; } } - } else { + } + else { first_time_getdis = false; } @@ -2062,7 +2037,8 @@ void vpSimulatorAfma6::move(const char *filename) this->readPosFile(filename, q); this->setRobotState(vpRobot::STATE_POSITION_CONTROL); this->setPosition(vpRobot::ARTICULAR_FRAME, q); - } catch (...) { + } + catch (...) { throw; } } @@ -2106,7 +2082,8 @@ void vpSimulatorAfma6::get_eJe(vpMatrix &eJe_) { try { vpAfma6::get_eJe(get_artCoord(), eJe_); - } catch (...) { + } + catch (...) { vpERROR_TRACE("catch exception "); throw; } @@ -2127,7 +2104,8 @@ void vpSimulatorAfma6::get_fJe(vpMatrix &fJe_) try { vpColVector articularCoordinates = get_artCoord(); vpAfma6::get_fJe(articularCoordinates, fJe_); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -2178,7 +2156,8 @@ void vpSimulatorAfma6::initArms() try { scene_dir_ = vpIoTools::getenv("VISP_SCENES_DIR"); std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl; - } catch (...) { + } + catch (...) { std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl; } } @@ -2287,7 +2266,8 @@ void vpSimulatorAfma6::getExternalImage(vpImage &I_) (std::fabs(py_ext - 1) > vpMath::maximum(py_ext, 1.) * std::numeric_limits::epsilon())) { u = (double)I_.getWidth() / (2 * px_ext); v = (double)I_.getHeight() / (2 * py_ext); - } else { + } + else { u = (double)I_.getWidth() / (vpMath::minimum(I_.getWidth(), I_.getHeight())); v = (double)I_.getHeight() / (vpMath::minimum(I_.getWidth(), I_.getHeight())); } @@ -2491,5 +2471,5 @@ bool vpSimulatorAfma6::setPosition(const vpHomogeneousMatrix &cdMo_, vpImage -#if defined(VISP_HAVE_MODULE_GUI) && ((defined(_WIN32) && !defined(WINRT_8_0)) || defined(VISP_HAVE_PTHREAD)) +#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS) #include // std::fabs #include // numeric_limits @@ -58,28 +58,14 @@ const double vpSimulatorViper850::defaultPositioningVelocity = 25.0; */ vpSimulatorViper850::vpSimulatorViper850() : vpRobotWireFrameSimulator(), vpViper850(), q_prev_getdis(), first_time_getdis(true), - positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() + positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() { init(); initDisplay(); tcur = vpTime::measureTimeMs(); -#if defined(_WIN32) - - DWORD dwThreadIdArray; - hThread = CreateThread(nullptr, // default security attributes - 0, // use default stack size - launcher, // thread function name - this, // argument to thread function - 0, // use default creation flags - &dwThreadIdArray); // returns the thread identifier -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - - pthread_create(&thread, nullptr, launcher, (void *)this); -#endif + m_thread = new std::thread(&launcher, std::ref(*this)); compute_fMi(); } @@ -92,27 +78,14 @@ vpSimulatorViper850::vpSimulatorViper850() */ vpSimulatorViper850::vpSimulatorViper850(bool do_display) : vpRobotWireFrameSimulator(do_display), q_prev_getdis(), first_time_getdis(true), - positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() + positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir() { init(); initDisplay(); tcur = vpTime::measureTimeMs(); -#if defined(_WIN32) - DWORD dwThreadIdArray; - hThread = CreateThread(nullptr, // default security attributes - 0, // use default stack size - launcher, // thread function name - this, // argument to thread function - 0, // use default creation flags - &dwThreadIdArray); // returns the thread identifier -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_init(&attr); - pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE); - - pthread_create(&thread, nullptr, launcher, (void *)this); -#endif + m_thread = new std::thread(&launcher, std::ref(*this)); compute_fMi(); } @@ -126,17 +99,7 @@ vpSimulatorViper850::~vpSimulatorViper850() robotStop = true; m_mutex_robotStop.unlock(); -#if defined(_WIN32) -#if defined(WINRT_8_1) - WaitForSingleObjectEx(hThread, INFINITE, FALSE); -#else // pure win32 - WaitForSingleObject(hThread, INFINITE); -#endif - CloseHandle(hThread); -#elif defined(VISP_HAVE_PTHREAD) - pthread_attr_destroy(&attr); - pthread_join(thread, nullptr); -#endif + m_thread->join(); if (robotArms != nullptr) { // free_Bound_scene (&(camera)); @@ -146,6 +109,7 @@ vpSimulatorViper850::~vpSimulatorViper850() delete[] robotArms; delete[] fMi; + delete m_thread; } /*! @@ -172,7 +136,8 @@ void vpSimulatorViper850::init() try { arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR"); std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl; - } catch (...) { + } + catch (...) { std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl; } } @@ -325,9 +290,10 @@ void vpSimulatorViper850::getCameraParameters(vpCameraParameters &cam, const uns // Set default intrinsic camera parameters for 640x480 images if (image_width == 640 && image_height == 480) { std::cout << "Get default camera parameters for camera \"" << vpViper850::CONST_MARLIN_F033C_CAMERA_NAME << "\"" - << std::endl; + << std::endl; cam.initPersProjWithoutDistortion(1232.0, 1233.0, 320, 240); - } else { + } + else { vpTRACE("Cannot get default intrinsic camera parameters for this image " "resolution"); } @@ -337,9 +303,10 @@ void vpSimulatorViper850::getCameraParameters(vpCameraParameters &cam, const uns // Set default intrinsic camera parameters for 640x480 images if (image_width == 640 && image_height == 480) { std::cout << "Get default camera parameters for camera \"" << vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME << "\"" - << std::endl; + << std::endl; cam.initPersProjWithoutDistortion(868.0, 869.0, 320, 240); - } else { + } + else { vpTRACE("Cannot get default intrinsic camera parameters for this image " "resolution"); } @@ -434,11 +401,12 @@ void vpSimulatorViper850::updateArticularPosition() if (art <= joint_min[jointLimitArt - 1] || art >= joint_max[jointLimitArt - 1]) { if (verbose_) { std::cout << "Joint " << jointLimitArt - 1 - << " reaches a limit: " << vpMath::deg(joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art) - << " < " << vpMath::deg(joint_max[jointLimitArt - 1]) << std::endl; + << " reaches a limit: " << vpMath::deg(joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art) + << " < " << vpMath::deg(joint_max[jointLimitArt - 1]) << std::endl; } articularVelocities = 0.0; - } else + } + else jointLimit = false; } @@ -454,10 +422,10 @@ void vpSimulatorViper850::updateArticularPosition() if (jl != 0 && jointLimit == false) { if (jl < 0) ellapsedTime = (joint_min[(unsigned int)(-jl - 1)] - articularCoordinates[(unsigned int)(-jl - 1)]) / - (articularVelocities[(unsigned int)(-jl - 1)]); + (articularVelocities[(unsigned int)(-jl - 1)]); else ellapsedTime = (joint_max[(unsigned int)(jl - 1)] - articularCoordinates[(unsigned int)(jl - 1)]) / - (articularVelocities[(unsigned int)(jl - 1)]); + (articularVelocities[(unsigned int)(jl - 1)]); for (unsigned int i = 0; i < 6; i++) articularCoordinates[i] = articularCoordinates[i] + ellapsedTime * articularVelocities[i]; @@ -517,7 +485,8 @@ void vpSimulatorViper850::updateArticularPosition() vpTime::wait(tcur, 1000 * getSamplingTime()); tcur_1 = tcur; - } else { + } + else { vpTime::wait(tcur, vpTime::getMinTimeForUsleepCall()); } m_mutex_robotStop.lock(); @@ -696,9 +665,10 @@ vpRobot::vpRobotStateType vpSimulatorViper850::setRobotState(vpRobot::vpRobotSta if (vpRobot::STATE_VELOCITY_CONTROL == getRobotState()) { std::cout << "Change the control mode from velocity to position control.\n"; stopMotion(); - } else { - // std::cout << "Change the control mode from stop to position - // control.\n"; + } + else { + // std::cout << "Change the control mode from stop to position + // control.\n"; } break; } @@ -1284,7 +1254,8 @@ void vpSimulatorViper850::setPosition(const vpRobot::vpControlFrameType frame, c set_velocity(error); break; } - } else { + } + else { vpERROR_TRACE("Positioning error."); throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range."); } @@ -1347,7 +1318,8 @@ void vpSimulatorViper850::setPosition(const vpRobot::vpControlFrameType frame, c set_velocity(error); break; } - } else + } + else vpERROR_TRACE("Positioning error. Position unreachable"); } while (errsqr > 1e-8 && nbSol > 0); break; @@ -1438,7 +1410,8 @@ void vpSimulatorViper850::setPosition(const vpRobot::vpControlFrameType frame, d position[5] = pos6; setPosition(frame, position); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -1809,7 +1782,7 @@ int vpSimulatorViper850::isInJointLimit() if (artNumb != 0) std::cout << "\nWarning: Velocity control stopped: axis " << fabs((float)artNumb) << " on joint limit!" - << std::endl; + << std::endl; return artNumb; } @@ -1865,7 +1838,8 @@ void vpSimulatorViper850::getDisplacement(vpRobot::vpControlFrameType frame, vpC return; } } - } else { + } + else { first_time_getdis = false; } @@ -2052,7 +2026,8 @@ void vpSimulatorViper850::move(const char *filename) this->readPosFile(filename, q); this->setRobotState(vpRobot::STATE_POSITION_CONTROL); this->setPosition(vpRobot::ARTICULAR_FRAME, q); - } catch (...) { + } + catch (...) { throw; } } @@ -2096,7 +2071,8 @@ void vpSimulatorViper850::get_eJe(vpMatrix &eJe_) { try { vpViper850::get_eJe(get_artCoord(), eJe_); - } catch (...) { + } + catch (...) { vpERROR_TRACE("catch exception "); throw; } @@ -2117,7 +2093,8 @@ void vpSimulatorViper850::get_fJe(vpMatrix &fJe_) try { vpColVector articularCoordinates = get_artCoord(); vpViper850::get_fJe(articularCoordinates, fJe_); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -2168,7 +2145,8 @@ void vpSimulatorViper850::initArms() try { scene_dir_ = vpIoTools::getenv("VISP_SCENES_DIR"); std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl; - } catch (...) { + } + catch (...) { std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl; } } @@ -2255,7 +2233,8 @@ void vpSimulatorViper850::getExternalImage(vpImage &I_) (std::fabs(py_ext - 1) > vpMath::maximum(py_ext, 1.) * std::numeric_limits::epsilon())) { u = (double)I_.getWidth() / (2 * px_ext); v = (double)I_.getHeight() / (2 * py_ext); - } else { + } + else { u = (double)I_.getWidth() / (vpMath::minimum(I_.getWidth(), I_.getHeight())); v = (double)I_.getHeight() / (vpMath::minimum(I_.getWidth(), I_.getHeight())); } @@ -2383,5 +2362,5 @@ void vpSimulatorViper850::initialiseObjectRelativeToCamera(const vpHomogeneousMa #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_robot.a(vpSimulatorViper850.cpp.o) // has no symbols -void dummy_vpSimulatorViper850(){}; +void dummy_vpSimulatorViper850() { }; #endif diff --git a/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp b/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp index 6c330c7058..fca58e6ac2 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkDroneVelocityControl.cpp @@ -48,7 +48,8 @@ #include // Check if std:c++17 or higher -#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) +#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \ + && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp b/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp index dffd649c22..26dcd0cea0 100644 --- a/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp +++ b/modules/robot/test/servo-pixhawk/testPixhawkRoverVelocityControl.cpp @@ -48,7 +48,8 @@ #include // Check if std:c++17 or higher -#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) +#if defined(VISP_HAVE_MAVSDK) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) \ + && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/test/servo-pololu/testPololuPosition.cpp b/modules/robot/test/servo-pololu/testPololuPosition.cpp index 3b49043c98..deaf385e19 100644 --- a/modules/robot/test/servo-pololu/testPololuPosition.cpp +++ b/modules/robot/test/servo-pololu/testPololuPosition.cpp @@ -39,7 +39,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/robot/test/servo-pololu/testPololuVelocity.cpp b/modules/robot/test/servo-pololu/testPololuVelocity.cpp index 7d9610b4ad..97387918e0 100644 --- a/modules/robot/test/servo-pololu/testPololuVelocity.cpp +++ b/modules/robot/test/servo-pololu/testPololuVelocity.cpp @@ -38,7 +38,7 @@ #include -#ifdef VISP_HAVE_POLOLU +#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/CMakeLists.txt b/modules/sensor/CMakeLists.txt index be27453fca..8c32dc1e8c 100644 --- a/modules/sensor/CMakeLists.txt +++ b/modules/sensor/CMakeLists.txt @@ -234,8 +234,6 @@ if(CXX_FLAGS_MUTE_WARNINGS) vp_set_source_file_compile_flag(test/rgb-depth/testOccipitalStructure_Core_images.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testOccipitalStructure_Core_imu.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testOccipitalStructure_Core_pcl.cpp ${CXX_FLAGS_MUTE_WARNINGS}) - vp_set_source_file_compile_flag(test/rgb-depth/testRealSense_R200.cpp ${CXX_FLAGS_MUTE_WARNINGS}) - vp_set_source_file_compile_flag(test/rgb-depth/testRealSense_SR300.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testRealSense2_SR300.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testRealSense2_D435.cpp ${CXX_FLAGS_MUTE_WARNINGS}) vp_set_source_file_compile_flag(test/rgb-depth/testRealSense2_D435_align.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiNetFTSensor.h old mode 100755 new mode 100644 diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h index 198240c3b7..6923c6be71 100644 --- a/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h +++ b/modules/sensor/include/visp3/sensor/vpForceTorqueIitSensor.h @@ -46,7 +46,7 @@ #include -#ifdef VISP_HAVE_FT_IIT_SDK +#if defined(VISP_HAVE_FT_IIT_SDK) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/include/visp3/sensor/vpKinect.h b/modules/sensor/include/visp3/sensor/vpKinect.h index d66742af67..d5f73273e3 100644 --- a/modules/sensor/include/visp3/sensor/vpKinect.h +++ b/modules/sensor/include/visp3/sensor/vpKinect.h @@ -42,16 +42,16 @@ #include // Note that libfreenect needs libusb-1.0 and libpthread -#if defined(VISP_HAVE_LIBFREENECT_AND_DEPENDENCIES) +#if defined(VISP_HAVE_LIBFREENECT_AND_DEPENDENCIES) && defined(VISP_HAVE_THREADS) #include #include +#include #include #include #include #include -#include // need pthread #include /*! @@ -154,8 +154,8 @@ class VISP_EXPORT vpKinect : public Freenect::FreenectDevice void DepthCallback(void *depth, uint32_t timestamp); private: - vpMutex m_rgb_mutex; - vpMutex m_depth_mutex; + std::mutex m_rgb_mutex; + std::mutex m_depth_mutex; vpCameraParameters RGBcam, IRcam; // intrinsic parameters of the two cameras vpHomogeneousMatrix rgbMir; // Transformation from IRcam coordinate frame to diff --git a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h index e425b5a2c9..07b6c5a8e3 100644 --- a/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h +++ b/modules/sensor/include/visp3/sensor/vpOccipitalStructure.h @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/src/force-torque/vpComedi.cpp b/modules/sensor/src/force-torque/vpComedi.cpp index c4bee5e8a3..f02ed55a17 100644 --- a/modules/sensor/src/force-torque/vpComedi.cpp +++ b/modules/sensor/src/force-torque/vpComedi.cpp @@ -47,9 +47,8 @@ */ vpComedi::vpComedi() : m_device("/dev/comedi0"), m_handler(nullptr), m_subdevice(0), m_range(0), m_aref(AREF_DIFF), m_nchannel(6), - m_range_info(6), m_maxdata(6), m_chanlist(6) -{ -} + m_range_info(6), m_maxdata(6), m_chanlist(6) +{ } /*! Destructor that closes the connection to the device if it is not already @@ -173,7 +172,6 @@ std::string vpComedi::getPhyDataUnits() const } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpComedi.cpp.o) has no -// symbols -void dummy_vpComedi(){}; +// Work around to avoid warning: libvisp_sensor.a(vpComedi.cpp.o) has symbols +void dummy_vpComedi() { }; #endif diff --git a/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp b/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp index 58b4084eb2..d111f26664 100644 --- a/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp +++ b/modules/sensor/src/force-torque/vpForceTorqueIitSensor.cpp @@ -43,7 +43,7 @@ #include -#ifdef VISP_HAVE_FT_IIT_SDK +#if defined(VISP_HAVE_FT_IIT_SDK) && defined(VISP_HAVE_THREADS) /*! Default constructor. diff --git a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp index 543dd82d12..d4b8009686 100644 --- a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp +++ b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp @@ -447,7 +447,7 @@ void vpV4l2Grabber::open(vpImage &I) close(); throw(vpFrameGrabberException(vpFrameGrabberException::settingError, - "No pixel format compatible with the camera was found")); + "No pixel format compatible with the camera was found")); } } } @@ -854,27 +854,27 @@ void vpV4l2Grabber::close() } if (inp != nullptr) { - delete [] inp; + delete[] inp; inp = nullptr; } if (std != nullptr) { - delete [] std; + delete[] std; std = nullptr; } if (fmt != nullptr) { - delete [] fmt; + delete[] fmt; fmt = nullptr; } if (ctl != nullptr) { - delete [] ctl; + delete[] ctl; ctl = nullptr; } if (buf_v4l2 != nullptr) { - delete [] buf_v4l2; + delete[] buf_v4l2; buf_v4l2 = nullptr; } if (buf_me != nullptr) { - delete [] buf_me; + delete[] buf_me; buf_me = nullptr; } } @@ -913,27 +913,27 @@ void vpV4l2Grabber::open() } if (inp != nullptr) { - delete [] inp; + delete[] inp; inp = nullptr; } if (std != nullptr) { - delete [] std; + delete[] std; std = nullptr; } if (fmt != nullptr) { - delete [] fmt; + delete[] fmt; fmt = nullptr; } if (ctl != nullptr) { - delete [] ctl; + delete[] ctl; ctl = nullptr; } if (buf_v4l2 != nullptr) { - delete [] buf_v4l2; + delete[] buf_v4l2; buf_v4l2 = nullptr; } if (buf_me != nullptr) { - delete [] buf_me; + delete[] buf_me; buf_me = nullptr; } @@ -1468,7 +1468,6 @@ vpV4l2Grabber &vpV4l2Grabber::operator>>(vpImage &I) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpV4l2Grabber.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_sensor.a(vpV4l2Grabber.cpp.o) has no symbols void dummy_vpV4l2Grabber() { }; #endif diff --git a/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp b/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp index 6666baaa81..67b9ca60d8 100644 --- a/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp +++ b/modules/sensor/src/rgb-depth/kinect/vpKinect.cpp @@ -121,7 +121,7 @@ void vpKinect::stop() */ void vpKinect::VideoCallback(void *rgb, uint32_t /* timestamp */) { - vpMutex::vpScopedLock lock(m_rgb_mutex); + std::lock_guard lock(m_rgb_mutex); uint8_t *rgb_ = static_cast(rgb); for (unsigned i = 0; i < height; i++) { for (unsigned j = 0; j < width; j++) { @@ -146,7 +146,7 @@ void vpKinect::VideoCallback(void *rgb, uint32_t /* timestamp */) */ void vpKinect::DepthCallback(void *depth, uint32_t /* timestamp */) { - vpMutex::vpScopedLock lock(m_depth_mutex); + std::lock_guard lock(m_depth_mutex); uint16_t *depth_ = static_cast(depth); for (unsigned i = 0; i < height; i++) { for (unsigned j = 0; j < width; j++) { @@ -167,7 +167,7 @@ void vpKinect::DepthCallback(void *depth, uint32_t /* timestamp */) */ bool vpKinect::getDepthMap(vpImage &map) { - vpMutex::vpScopedLock lock(m_depth_mutex); + std::lock_guard lock(m_depth_mutex); if (!m_new_depth_map) return false; map = this->dmap; @@ -225,7 +225,7 @@ bool vpKinect::getDepthMap(vpImage &map, vpImage &Imap) */ bool vpKinect::getRGB(vpImage &I_RGB) { - vpMutex::vpScopedLock lock(m_rgb_mutex); + std::lock_guard lock(m_rgb_mutex); if (!m_new_rgb_frame) return false; I_RGB = this->IRGB; @@ -292,7 +292,6 @@ void vpKinect::warpRGBFrame(const vpImage &Irgb, const vpImage &I } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpKinect.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_sensor.a(vpKinect.cpp.o) has no symbols void dummy_vpKinect() { }; #endif // VISP_HAVE_LIBFREENECT diff --git a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp index e618733b24..daaeb32591 100644 --- a/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp +++ b/modules/sensor/src/rgb-depth/occipital_structure/vpOccipitalStructure.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && defined(VISP_HAVE_THREADS) #include #include #include diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp index 807e4e1c51..fd6ded07f0 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense.cpp @@ -1045,7 +1045,6 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense &rs) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpRealSense.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_sensor.a(vpRealSense.cpp.o) has symbols void dummy_vpRealSense() { }; #endif diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp b/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp index 15b9a43659..e4536ec3a3 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp @@ -1677,7 +1677,6 @@ std::ostream &operator<<(std::ostream &os, const vpRealSense2 &rs) } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_sensor.a(vpRealSense2.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_sensor.a(vpRealSense2.cpp.o) has symbols void dummy_vpRealSense2() { }; #endif diff --git a/modules/sensor/src/rgb-depth/realsense/vpRealSense_impl.h b/modules/sensor/src/rgb-depth/realsense/vpRealSense_impl.h index 5dd48aba48..d76ed2834d 100644 --- a/modules/sensor/src/rgb-depth/realsense/vpRealSense_impl.h +++ b/modules/sensor/src/rgb-depth/realsense/vpRealSense_impl.h @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_REALSENSE) +#if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_THREADS) #include #include #include diff --git a/modules/sensor/test/force-torque/testForceTorqueAti.cpp b/modules/sensor/test/force-torque/testForceTorqueAti.cpp index bb70db8786..065bde7d09 100644 --- a/modules/sensor/test/force-torque/testForceTorqueAti.cpp +++ b/modules/sensor/test/force-torque/testForceTorqueAti.cpp @@ -45,35 +45,28 @@ #include #include -#include -#include #include #include #include -#if defined(VISP_HAVE_PTHREAD) +#if defined(VISP_HAVE_THREADS) -typedef enum { BIAS_DONE, UNBIAS_DONE, TO_BIAS, TO_UNBIAS } BiasState; +#include +#include -vpMutex s_mutex_data; +typedef enum { BIAS_DONE, UNBIAS_DONE, TO_BIAS, TO_UNBIAS } BiasState; #ifndef DOXYGEN_SHOULD_SKIP_THIS -typedef struct { +typedef struct +{ vpColVector ft; double timestamp; BiasState bias_state; } t_shared_data; #endif -t_shared_data s_shared_data; - -vpMutex s_mutex_state; -bool s_state_stop = false; - -vpThread::Return scopeFunction(vpThread::Args args) +void scopeFunction(std::mutex &mutex_data, std::mutex &mutex_state, t_shared_data &s_shared_data, bool &s_state_stop) { - (void)args; // Avoid warning: unused parameter args - #ifdef VISP_HAVE_DISPLAY vpPlot scope(2, 700, 700, 100, 200, "ATI F/T sensor data"); scope.initGraph(0, 3); @@ -98,7 +91,7 @@ vpThread::Return scopeFunction(vpThread::Args args) do { #ifdef VISP_HAVE_DISPLAY { // Get new measures to plot - vpMutex::vpScopedLock lock(s_mutex_data); + std::lock_guard lock(mutex_data); shared_data.ft = s_shared_data.ft; shared_data.timestamp = s_shared_data.timestamp; shared_data.bias_state = s_shared_data.bias_state; @@ -127,7 +120,7 @@ vpThread::Return scopeFunction(vpThread::Args args) else if (shared_data.bias_state == UNBIAS_DONE) shared_data.bias_state = TO_BIAS; { // Set new bias state - vpMutex::vpScopedLock lock(s_mutex_data); + std::lock_guard lock(mutex_data); s_shared_data.bias_state = shared_data.bias_state; } } @@ -141,12 +134,11 @@ vpThread::Return scopeFunction(vpThread::Args args) #endif { // Update state to stop - vpMutex::vpScopedLock lock(s_mutex_state); + std::lock_guard lock(mutex_state); s_state_stop = true; } std::cout << "End of scope thread" << std::endl; - return 0; } int main(int argc, char **argv) @@ -177,13 +169,18 @@ int main(int argc, char **argv) ati.bias(); std::cout << "Data recording in progress..." << std::endl; + std::mutex mutex_data; + std::mutex mutex_state; + bool state_stop = false; + bool s_state_stop = false; + t_shared_data shared_data; + t_shared_data s_shared_data; + // Start scope thread - vpThread thread_scope(scopeFunction); + std::thread thread_scope(&scopeFunction, std::ref(mutex_data), std::ref(mutex_state), std::ref(s_shared_data), std::ref(s_state_stop)); std::string file("recorded-ft-sync.txt"); std::ofstream f(file.c_str()); - bool state_stop; - t_shared_data shared_data; double start_time = vpTime::measureTimeMs(); @@ -193,7 +190,7 @@ int main(int argc, char **argv) double timestamp = loop_time - start_time; { // Update shared F/T measure used by the scope to plot curves - vpMutex::vpScopedLock lock(s_mutex_data); + std::lock_guard lock(mutex_data); shared_data.bias_state = s_shared_data.bias_state; } if (shared_data.bias_state == TO_BIAS) { @@ -201,19 +198,20 @@ int main(int argc, char **argv) ati.bias(); std::cout << "Unbias sensor" << std::endl; shared_data.bias_state = BIAS_DONE; - } else if (shared_data.bias_state == TO_UNBIAS) { + } + else if (shared_data.bias_state == TO_UNBIAS) { ati.unbias(); shared_data.bias_state = UNBIAS_DONE; } { // Update shared F/T measure used by the scope to plot curves - vpMutex::vpScopedLock lock(s_mutex_data); + std::lock_guard lock(mutex_data); s_shared_data.ft = ft; s_shared_data.timestamp = timestamp; s_shared_data.bias_state = shared_data.bias_state; } { // Get state to stop - vpMutex::vpScopedLock lock(s_mutex_state); + std::lock_guard lock(mutex_state); state_stop = s_state_stop; } diff --git a/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp b/modules/sensor/test/force-torque/testForceTorqueAtiNetFTSensor.cpp old mode 100755 new mode 100644 diff --git a/modules/sensor/test/mocap/testMocapQualisys.cpp b/modules/sensor/test/mocap/testMocapQualisys.cpp index ec1a79255b..4df6172314 100644 --- a/modules/sensor/test/mocap/testMocapQualisys.cpp +++ b/modules/sensor/test/mocap/testMocapQualisys.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_QUALISYS) +#if defined(VISP_HAVE_QUALISYS) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/test/mocap/testMocapVicon.cpp b/modules/sensor/test/mocap/testMocapVicon.cpp index 10c1f4c274..0c8c3a8830 100644 --- a/modules/sensor/test/mocap/testMocapVicon.cpp +++ b/modules/sensor/test/mocap/testMocapVicon.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_VICON) +#if defined(VISP_HAVE_VICON) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp index 325347c53d..cde2c5abc2 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_D435_pcl.cpp @@ -41,7 +41,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) \ && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PCL) #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp index ea1024dbee..350d9c1013 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_SR300.cpp @@ -42,8 +42,7 @@ #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \ - && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) #ifdef VISP_HAVE_PCL #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp index a76074c0f6..ab7ec4d130 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry.cpp @@ -47,8 +47,8 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) #include diff --git a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry_async.cpp b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry_async.cpp index 94581a572e..33d272a879 100644 --- a/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry_async.cpp +++ b/modules/sensor/test/rgb-depth/testRealSense2_T265_images_odometry_async.cpp @@ -47,8 +47,8 @@ #include #include -#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ - (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) +#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) \ + && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) #include #include diff --git a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp b/modules/sensor/test/rgb-depth/testRealSense_R200.cpp deleted file mode 100644 index f7447fa48d..0000000000 --- a/modules/sensor/test/rgb-depth/testRealSense_R200.cpp +++ /dev/null @@ -1,592 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. - * - * This software is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * See the file LICENSE.txt at the root directory of this source - * distribution for additional information about the GNU GPL. - * - * For using ViSP with software that can not be combined with the GNU - * GPL, please contact Inria about acquiring a ViSP Professional - * Edition License. - * - * See https://visp.inria.fr for more information. - * - * This software was developed at: - * Inria Rennes - Bretagne Atlantique - * Campus Universitaire de Beaulieu - * 35042 Rennes Cedex - * France - * - * If you have questions regarding the use of this file, please contact - * Inria at visp@inria.fr - * - * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE - * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * - * Description: - * Test Intel RealSense acquisition. - * -*****************************************************************************/ - -/*! - \example testRealSense_R200.cpp - Test Intel RealSense R200 acquisition. -*/ - -#include - -#include -#include -#include -#include -#include - -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) -#include -#include - -#ifdef VISP_HAVE_PCL -#include -#include -#endif - -namespace -{ - -#ifdef VISP_HAVE_PCL -// Global variables -pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud()); -pcl::PointCloud::Ptr pointcloud_color(new pcl::PointCloud()); -bool cancelled = false, update_pointcloud = false; - -class ViewerWorker -{ -public: - explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { } - - void run() - { - std::string date = vpTime::getDateTime(); - pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date)); - pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud_color); - pcl::PointCloud::Ptr local_pointcloud(new pcl::PointCloud()); - pcl::PointCloud::Ptr local_pointcloud_color(new pcl::PointCloud()); - - viewer->setBackgroundColor(0, 0, 0); - viewer->initCameraParameters(); - viewer->setPosition(640 + 80, 480 + 80); - viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0); - viewer->setSize(640, 480); - - bool init = true; - bool local_update = false, local_cancelled = false; - while (!local_cancelled) { - { - std::unique_lock lock(m_mutex, std::try_to_lock); - - if (lock.owns_lock()) { - local_update = update_pointcloud; - update_pointcloud = false; - local_cancelled = cancelled; - - if (local_update) { - if (m_colorMode) { - local_pointcloud_color = pointcloud_color->makeShared(); - } - else { - local_pointcloud = pointcloud->makeShared(); - } - } - } - } - - if (local_update && !local_cancelled) { - local_update = false; - - if (init) { - if (m_colorMode) { - viewer->addPointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, - "RGB sample cloud"); - } - else { - viewer->addPointCloud(local_pointcloud, "sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); - } - init = false; - } - else { - if (m_colorMode) { - viewer->updatePointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - } - else { - viewer->updatePointCloud(local_pointcloud, "sample cloud"); - } - } - } - - viewer->spinOnce(5); - } - - std::cout << "End of point cloud display thread" << std::endl; - } - -private: - bool m_colorMode; - std::mutex &m_mutex; -}; -#endif //#ifdef VISP_HAVE_PCL - -void test_R200(vpRealSense &rs, const std::map &enables, - const std::map ¶ms, - const std::map &options, const std::string &title, - bool depth_color_visualization = false, const rs::stream &color_stream = rs::stream::color, - const rs::stream &depth_stream = rs::stream::depth, - const rs::stream &infrared2_stream = rs::stream::infrared2, bool display_pcl = false, - bool pcl_color = false) -{ - std::cout << std::endl; - - std::map::const_iterator it_enable; - std::map::const_iterator it_param; - - for (it_enable = enables.begin(), it_param = params.begin(); it_enable != enables.end(); ++it_enable) { - rs.setEnableStream(it_enable->first, it_enable->second); - - if (it_enable->second) { - it_param = params.find(it_enable->first); - - if (it_param != params.end()) { - rs.setStreamSettings(it_param->first, it_param->second); - } - } - } - - rs.open(); - - vpImage depth; - vpImage I_depth; - vpImage I_depth_color; - - vpImage I_color; - vpImage infrared, infrared2; - vpImage I_infrared, I_infrared2; - - bool direct_infrared_conversion = false; - for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) { - if (it_enable->second) { - switch (it_enable->first) { - case rs::stream::color: - I_color.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - break; - - case rs::stream::depth: - depth.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_depth.init(depth.getHeight(), depth.getWidth()); - I_depth_color.init(depth.getHeight(), depth.getWidth()); - break; - - case rs::stream::infrared: - infrared.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_infrared.init(infrared.getHeight(), infrared.getWidth()); - - it_param = params.find(it_enable->first); - if (it_param != params.end()) { - direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8; - } - break; - - case rs::stream::infrared2: - infrared2.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_infrared2.init(infrared.getHeight(), infrared.getWidth()); - - it_param = params.find(it_enable->first); - if (it_param != params.end()) { - direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8; - } - break; - - default: - break; - } - } - } - -#if defined(VISP_HAVE_X11) - vpDisplayX dc, dd, di, di2; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI dc, dd, di, di2; -#endif - - for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) { - if (it_enable->second) { - switch (it_enable->first) { - case rs::stream::color: - dc.init(I_color, 0, 0, "Color frame"); - break; - - case rs::stream::depth: - if (depth_color_visualization) { - dd.init(I_depth_color, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } - else { - dd.init(I_depth, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } - break; - - case rs::stream::infrared: - di.init(I_infrared, 0, (int)(std::max(I_color.getHeight(), I_depth.getHeight())) + 30, "Infrared frame"); - break; - - case rs::stream::infrared2: - di2.init(I_infrared2, (int)I_infrared.getWidth(), - (int)(std::max(I_color.getHeight(), I_depth.getHeight())) + 30, "Infrared2 frame"); - break; - - default: - break; - } - } - } - - std::cout << "direct_infrared_conversion=" << direct_infrared_conversion << std::endl; - -#ifdef VISP_HAVE_PCL - std::mutex mutex; - ViewerWorker viewer(pcl_color, mutex); - std::thread viewer_thread; - - if (display_pcl) { - viewer_thread = std::thread(&ViewerWorker::run, &viewer); - } -#else - display_pcl = false; -#endif - - rs::device *dev = rs.getHandler(); - - // Test stream acquisition during 10 s - std::vector time_vector; - double t_begin = vpTime::measureTimeMs(); - while (true) { - double t = vpTime::measureTimeMs(); - - for (std::map::const_iterator it = options.begin(); it != options.end(); ++it) { - dev->set_option(it->first, it->second); - } - - if (display_pcl) { -#ifdef VISP_HAVE_PCL - std::lock_guard lock(mutex); - - if (direct_infrared_conversion) { - if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, - (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, - depth_stream, rs::stream::infrared, infrared2_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, - depth_stream, rs::stream::infrared, infrared2_stream); - } - } - else { - if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, - (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, - rs::stream::infrared, infrared2_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, - rs::stream::infrared, infrared2_stream); - } - - vpImageConvert::convert(infrared, I_infrared); - vpImageConvert::convert(infrared2, I_infrared2); - } - - update_pointcloud = true; -#endif - } - else { - if (direct_infrared_conversion) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, depth_stream, - rs::stream::infrared, infrared2_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream, - rs::stream::infrared, infrared2_stream); - vpImageConvert::convert(infrared, I_infrared); - vpImageConvert::convert(infrared2, I_infrared2); - } - } - - if (depth_color_visualization) { - vpImageConvert::createDepthHistogram(depth, I_depth_color); - } - else { - vpImageConvert::createDepthHistogram(depth, I_depth); - } - - vpDisplay::display(I_color); - if (depth_color_visualization) { - vpDisplay::display(I_depth_color); - } - else { - vpDisplay::display(I_depth); - } - vpDisplay::display(I_infrared); - vpDisplay::display(I_infrared2); - - vpDisplay::flush(I_color); - if (depth_color_visualization) { - vpDisplay::flush(I_depth_color); - } - else { - vpDisplay::flush(I_depth); - } - vpDisplay::flush(I_infrared); - vpDisplay::flush(I_infrared2); - - if (vpDisplay::getClick(I_color, false) || - (depth_color_visualization ? vpDisplay::getClick(I_depth_color, false) : vpDisplay::getClick(I_depth, false)) || - vpDisplay::getClick(I_infrared, false) || vpDisplay::getClick(I_infrared2, false)) { - break; - } - - time_vector.push_back(vpTime::measureTimeMs() - t); - if (vpTime::measureTimeMs() - t_begin >= 10000) { - break; - } - } - - if (display_pcl) { -#ifdef VISP_HAVE_PCL - { - std::lock_guard lock(mutex); - cancelled = true; - } - - viewer_thread.join(); -#endif - } - - std::cout << title << " - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; - - rs.close(); -} - -} // namespace - -int main(int argc, char *argv[]) -{ - try { - vpRealSense rs; - - rs.setEnableStream(rs::stream::color, false); - rs.open(); - if (rs_get_device_name((const rs_device *)rs.getHandler(), nullptr) != std::string("Intel RealSense R200")) { - std::cout << "This test file is used to test the Intel RealSense R200 only." << std::endl; - return EXIT_SUCCESS; - } - - std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl; - std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *)rs.getHandler(), nullptr) - << std::endl; - std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; - - rs.close(); - - std::map enables; - std::map params; - std::map options; - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = false; - enables[rs::stream::infrared2] = false; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 90); - - options[rs::option::r200_lr_auto_exposure_enabled] = 1; - - test_R200(rs, enables, params, options, "R200_DEPTH_Z16_640x480_90FPS + r200_lr_auto_exposure_enabled", true); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 90); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - - options[rs::option::r200_lr_auto_exposure_enabled] = 0; - options[rs::option::r200_emitter_enabled] = 0; - - test_R200(rs, enables, params, options, - "R200_DEPTH_Z16_640x480_90FPS + R200_INFRARED_Y8_640x480_90FPS " - "+ R200_INFRARED2_Y8_640x480_90FPS + " - "!r200_lr_auto_exposure_enabled + !r200_emitter_enabled", - true); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(628, 468, rs::format::z16, 90); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 90); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 90); - - options[rs::option::r200_lr_auto_exposure_enabled] = 1; - options[rs::option::r200_emitter_enabled] = 1; - - test_R200(rs, enables, params, options, - "R200_DEPTH_Z16_628x468_90FPS + " - "R200_INFRARED_Y16_640x480_90FPS + " - "R200_INFRARED2_Y16_640x480_90FPS"); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(628, 468, rs::format::z16, 90); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - - options.clear(); - - test_R200(rs, enables, params, options, - "R200_DEPTH_Z16_628x468_90FPS + R200_INFRARED_Y8_640x480_90FPS " - "+ R200_INFRARED2_Y8_640x480_90FPS"); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 90); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90); - - test_R200(rs, enables, params, options, - "R200_COLOR_RGBA8_640x480_30FPS + R200_DEPTH_Z16_628x468_90FPS " - "+ R200_INFRARED_Y8_640x480_90FPS + " - "R200_INFRARED2_Y8_640x480_90FPS", - true); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = false; - enables[rs::stream::infrared] = false; - enables[rs::stream::infrared2] = false; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30); - - test_R200(rs, enables, params, options, "R200_COLOR_RGBA8_1920x1080_30FPS"); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = false; - enables[rs::stream::infrared] = false; - enables[rs::stream::infrared2] = false; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60); - test_R200(rs, enables, params, options, "R200_COLOR_RGBA8_640x480_60FPS"); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - - // depth == 0 ; color == 1 ; infrared2 == 3 ; rectified_color == 6 ; - // color_aligned_to_depth == 7 ; infrared2_aligned_to_depth == 8 ; - // depth_aligned_to_color == 9 ; depth_aligned_to_rectified_color == 10 ; - // depth_aligned_to_infrared2 == 11 argv[2] <==> color stream - rs::stream color_stream = argc > 2 ? (rs::stream)atoi(argv[2]) : rs::stream::color_aligned_to_depth; - std::cout << "\ncolor_stream: " << color_stream << std::endl; - // argv[3] <==> depth stream - rs::stream depth_stream = argc > 3 ? (rs::stream)atoi(argv[3]) : rs::stream::depth_aligned_to_rectified_color; - std::cout << "depth_stream: " << depth_stream << std::endl; - // argv[4] <==> depth stream - rs::stream infrared2_stream = argc > 4 ? (rs::stream)atoi(argv[4]) : rs::stream::infrared2_aligned_to_depth; - std::cout << "infrared2_stream: " << infrared2_stream << std::endl; - - test_R200(rs, enables, params, options, - "R200_COLOR_ALIGNED_TO_DEPTH_RGBA8_640x480_60FPS + " - "R200_DEPTH_ALIGNED_TO_RECTIFIED_COLOR_Z16_640x480_60FPS + " - "R200_INFRARED_Y8_640x480_60FPS + " - "R200_INFRARED2_ALIGNED_TO_DEPTH_Y8_640x480_60FPS", - true, color_stream, depth_stream, infrared2_stream); - -#if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX, since viewer->spinOnce (10); produces a - // segfault on OSX - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - enables[rs::stream::infrared2] = true; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - - // Cannot render two pcl::visualization::PCLVisualizer so use an arg - // option to switch between B&W and color point cloud rendering until a - // solution is found - test_R200(rs, enables, params, options, - "R200_COLOR_RGBA8_640x480_60FPS + R200_DEPTH_Z16_640x480_60FPS + " - "R200_INFRARED_Y8_640x480_60FPS + R200_INFRARED2_Y8_640x480_60FPS", - false, rs::stream::color, rs::stream::depth, rs::stream::infrared2, true, - (argc > 1 ? (bool)(atoi(argv[1]) > 0) : false)); -#endif - } - catch (const vpException &e) { - std::cerr << "RealSense error " << e.what() << std::endl; - } - catch (const rs::error &e) { - std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() - << "): " << e.what() << std::endl; - } - catch (const std::exception &e) { - std::cerr << e.what() << std::endl; - } - - return EXIT_SUCCESS; -} - -#else -int main() -{ -#if !defined(VISP_HAVE_REALSENSE) - std::cout << "This deprecated example is only working with librealsense 1.x " << std::endl; -#elif !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) to make this test working" - << std::endl; -#elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) - std::cout << "X11 or GDI are needed!" << std::endl; -#endif - return EXIT_SUCCESS; -} -#endif diff --git a/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp b/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp deleted file mode 100644 index d37e15e113..0000000000 --- a/modules/sensor/test/rgb-depth/testRealSense_SR300.cpp +++ /dev/null @@ -1,526 +0,0 @@ -/**************************************************************************** - * - * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. - * - * This software is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * See the file LICENSE.txt at the root directory of this source - * distribution for additional information about the GNU GPL. - * - * For using ViSP with software that can not be combined with the GNU - * GPL, please contact Inria about acquiring a ViSP Professional - * Edition License. - * - * See https://visp.inria.fr for more information. - * - * This software was developed at: - * Inria Rennes - Bretagne Atlantique - * Campus Universitaire de Beaulieu - * 35042 Rennes Cedex - * France - * - * If you have questions regarding the use of this file, please contact - * Inria at visp@inria.fr - * - * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE - * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * - * Description: - * Test Intel RealSense acquisition. - * -*****************************************************************************/ - -/*! - \example testRealSense_SR300.cpp - Test Intel RealSense SR300 acquisition. -*/ - -#include - -#include -#include -#include -#include -#include - -#if defined(VISP_HAVE_REALSENSE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) -#include -#include - -#ifdef VISP_HAVE_PCL -#include -#include -#endif - -namespace -{ - -#ifdef VISP_HAVE_PCL -// Global variables -pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud()); -pcl::PointCloud::Ptr pointcloud_color(new pcl::PointCloud()); -bool cancelled = false, update_pointcloud = false; - -class ViewerWorker -{ -public: - explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { } - - void run() - { - std::string date = vpTime::getDateTime(); - pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date)); - pcl::visualization::PointCloudColorHandlerRGBField rgb(pointcloud_color); - pcl::PointCloud::Ptr local_pointcloud(new pcl::PointCloud()); - pcl::PointCloud::Ptr local_pointcloud_color(new pcl::PointCloud()); - - viewer->setBackgroundColor(0, 0, 0); - viewer->initCameraParameters(); - viewer->setPosition(640 + 80, 480 + 80); - viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0); - viewer->setSize(640, 480); - - bool init = true; - bool local_update = false, local_cancelled = false; - while (!local_cancelled) { - { - std::unique_lock lock(m_mutex, std::try_to_lock); - - if (lock.owns_lock()) { - local_update = update_pointcloud; - update_pointcloud = false; - local_cancelled = cancelled; - - if (local_update) { - if (m_colorMode) { - local_pointcloud_color = pointcloud_color->makeShared(); - } - else { - local_pointcloud = pointcloud->makeShared(); - } - } - } - } - - if (local_update && !local_cancelled) { - local_update = false; - - if (init) { - if (m_colorMode) { - viewer->addPointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, - "RGB sample cloud"); - } - else { - viewer->addPointCloud(local_pointcloud, "sample cloud"); - viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud"); - } - init = false; - } - else { - if (m_colorMode) { - viewer->updatePointCloud(local_pointcloud_color, rgb, "RGB sample cloud"); - } - else { - viewer->updatePointCloud(local_pointcloud, "sample cloud"); - } - } - } - - viewer->spinOnce(5); - } - - std::cout << "End of point cloud display thread" << std::endl; - } - -private: - bool m_colorMode; - std::mutex &m_mutex; -}; -#endif //#ifdef VISP_HAVE_PCL - -void test_SR300(vpRealSense &rs, const std::map &enables, - const std::map ¶ms, const std::string &title, - bool depth_color_visualization = false, const rs::stream &color_stream = rs::stream::color, - const rs::stream &depth_stream = rs::stream::depth, bool display_pcl = false, bool pcl_color = false) -{ - std::cout << std::endl; - - std::map::const_iterator it_enable; - std::map::const_iterator it_param; - - for (it_enable = enables.begin(), it_param = params.begin(); it_enable != enables.end(); ++it_enable) { - rs.setEnableStream(it_enable->first, it_enable->second); - - if (it_enable->second) { - it_param = params.find(it_enable->first); - - if (it_param != params.end()) { - rs.setStreamSettings(it_param->first, it_param->second); - } - } - } - - rs.open(); - - vpImage depth; - vpImage I_depth; - vpImage I_depth_color; - - vpImage I_color; - vpImage infrared; - vpImage I_infrared; - - bool direct_infrared_conversion = false; - for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) { - if (it_enable->second) { - switch (it_enable->first) { - case rs::stream::color: - I_color.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - break; - - case rs::stream::depth: - depth.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_depth.init(depth.getHeight(), depth.getWidth()); - I_depth_color.init(depth.getHeight(), depth.getWidth()); - break; - - case rs::stream::infrared: - infrared.init((unsigned int)rs.getIntrinsics(it_enable->first).height, - (unsigned int)rs.getIntrinsics(it_enable->first).width); - I_infrared.init(infrared.getHeight(), infrared.getWidth()); - - it_param = params.find(it_enable->first); - if (it_param != params.end()) { - direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8; - } - break; - - default: - break; - } - } - } - -#if defined(VISP_HAVE_X11) - vpDisplayX dc, dd, di; -#elif defined(VISP_HAVE_GDI) - vpDisplayGDI dc, dd, di; -#endif - - for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) { - if (it_enable->second) { - switch (it_enable->first) { - case rs::stream::color: - dc.init(I_color, 0, 0, "Color frame"); - break; - - case rs::stream::depth: - if (depth_color_visualization) { - dd.init(I_depth_color, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } - else { - dd.init(I_depth, (int)I_color.getWidth() + 80, 0, "Depth frame"); - } - break; - - case rs::stream::infrared: - di.init(I_infrared, 0, (int)(std::max(I_color.getHeight(), I_depth.getHeight())) + 30, "Infrared frame"); - break; - - default: - break; - } - } - } - - if (rs.getHandler()->is_stream_enabled(rs::stream::infrared)) { - std::cout << "direct_infrared_conversion=" << direct_infrared_conversion << std::endl; - } - -#ifdef VISP_HAVE_PCL - std::mutex mutex; - ViewerWorker viewer(pcl_color, mutex); - std::thread viewer_thread; - - if (display_pcl) { - viewer_thread = std::thread(&ViewerWorker::run, &viewer); - } -#else - display_pcl = false; -#endif - - // Test stream acquisition during 10 s - std::vector time_vector; - double t_begin = vpTime::measureTimeMs(); - while (true) { - double t = vpTime::measureTimeMs(); - - if (display_pcl) { -#ifdef VISP_HAVE_PCL - std::lock_guard lock(mutex); - - if (direct_infrared_conversion) { - if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, - (unsigned char *)I_infrared.bitmap, nullptr, color_stream, depth_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)I_infrared.bitmap, nullptr, color_stream, depth_stream); - } - } - else { - if (pcl_color) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud_color, - (unsigned char *)infrared.bitmap, nullptr, color_stream, depth_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, pointcloud, - (unsigned char *)infrared.bitmap, nullptr, color_stream, depth_stream); - } - - vpImageConvert::convert(infrared, I_infrared); - } - - update_pointcloud = true; -#endif - } - else { - if (direct_infrared_conversion) { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)I_infrared.bitmap, nullptr, color_stream, depth_stream); - } - else { - rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, nullptr, - (unsigned char *)infrared.bitmap, nullptr, color_stream, depth_stream); - vpImageConvert::convert(infrared, I_infrared); - } - } - - if (depth_color_visualization) { - vpImageConvert::createDepthHistogram(depth, I_depth_color); - } - else { - vpImageConvert::createDepthHistogram(depth, I_depth); - } - - vpDisplay::display(I_color); - if (depth_color_visualization) { - vpDisplay::display(I_depth_color); - } - else { - vpDisplay::display(I_depth); - } - vpDisplay::display(I_infrared); - - vpDisplay::flush(I_color); - if (depth_color_visualization) { - vpDisplay::flush(I_depth_color); - } - else { - vpDisplay::flush(I_depth); - } - vpDisplay::flush(I_infrared); - - if (vpDisplay::getClick(I_color, false) || - (depth_color_visualization ? vpDisplay::getClick(I_depth_color, false) : vpDisplay::getClick(I_depth, false)) || - vpDisplay::getClick(I_infrared, false)) { - break; - } - - time_vector.push_back(vpTime::measureTimeMs() - t); - if (vpTime::measureTimeMs() - t_begin >= 10000) { - break; - } - } - - if (display_pcl) { -#ifdef VISP_HAVE_PCL - { - std::lock_guard lock(mutex); - cancelled = true; - } - - viewer_thread.join(); -#endif - } - - std::cout << title << " - Mean time: " << vpMath::getMean(time_vector) - << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl; - - rs.close(); -} - -} // namespace - -int main(int argc, char *argv[]) -{ - try { - vpRealSense rs; - - rs.setEnableStream(rs::stream::color, false); - rs.open(); - if (rs_get_device_name((const rs_device *)rs.getHandler(), nullptr) != std::string("Intel RealSense SR300")) { - std::cout << "This test file is used to test the Intel RealSense SR300 only." << std::endl; - return EXIT_SUCCESS; - } - - std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl; - std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *)rs.getHandler(), nullptr) - << std::endl; - std::cout << "RealSense sensor characteristics: \n" << rs << std::endl; - - rs.close(); - - std::map enables; - std::map params; - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = false; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 240, rs::format::z16, 110); - - test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x240_110FPS"); - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = false; - enables[rs::stream::infrared] = false; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30); - - test_SR300(rs, enables, params, "SR300_COLOR_RGBA8_1920x1080_30FPS"); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = false; - enables[rs::stream::infrared] = true; - - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 200); - - test_SR300(rs, enables, params, "SR300_INFRARED_Y16_640x480_200FPS"); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = false; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - - test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x480_60FPS", true); - - enables[rs::stream::color] = false; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - - test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x480_60FPS + SR300_INFRARED_Y8_640x480_60FPS", true); - -#if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX, since viewer->spinOnce (10); produces a - // segfault on OSX - - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = true; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60); - params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60); - - // depth == 0 ; color == 1 ; rectified_color == 6 ; color_aligned_to_depth - // == 7 ; depth_aligned_to_color == 9 ; depth_aligned_to_rectified_color - // == 10 argv[1] <==> color stream - rs::stream color_stream = argc > 1 ? (rs::stream)atoi(argv[1]) : rs::stream::color; - std::cout << "\ncolor_stream: " << color_stream << std::endl; - // argv[2] <==> depth stream - rs::stream depth_stream = argc > 2 ? (rs::stream)atoi(argv[2]) : rs::stream::depth; - std::cout << "depth_stream: " << depth_stream << std::endl; - - test_SR300(rs, enables, params, - "SR300_COLOR_RGBA8_640x480_60FPS + " - "SR300_DEPTH_Z16_640x480_60FPS + " - "SR300_INFRARED_Y8_640x480_60FPS", - true, color_stream, depth_stream, true, true); -#endif - - // Color stream aligned to depth - enables[rs::stream::color] = true; - enables[rs::stream::depth] = true; - enables[rs::stream::infrared] = false; - - params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30); - params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 30); - - test_SR300(rs, enables, params, - "SR300_COLOR_ALIGNED_TO_DEPTH_RGBA8_640x480_30FPS + " - "SR300_DEPTH_Z16_640x480_30FPS", - true, rs::stream::color_aligned_to_depth); - - // Depth stream aligned to color - test_SR300(rs, enables, params, - "SR300_COLOR_RGBA8_640x480_30FPS + " - "SR300_DEPTH_ALIGNED_TO_COLOR_Z16_640x480_30FPS", - true, rs::stream::color, rs::stream::depth_aligned_to_color); - - rs.setEnableStream(rs::stream::color, true); - rs.setEnableStream(rs::stream::depth, false); - rs.setEnableStream(rs::stream::infrared, true); - rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::bgr8, 60)); - rs.setStreamSettings(rs::stream::infrared, vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 200)); - rs.open(); - - cv::Mat color_mat(480, 640, CV_8UC3); - cv::Mat infrared_mat(480, 640, CV_8U); - - double t_begin = vpTime::measureTimeMs(); - while (true) { - rs.acquire(color_mat.data, nullptr, nullptr, infrared_mat.data); - - cv::imshow("Color mat", color_mat); - cv::imshow("Infrared mat", infrared_mat); - char c = cv::waitKey(1); - if (c == 27) { - break; - } - - if (vpTime::measureTimeMs() - t_begin >= 10000) { - break; - } - } - } - catch (const vpException &e) { - std::cerr << "RealSense error " << e.what() << std::endl; - } - catch (const rs::error &e) { - std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() - << "): " << e.what() << std::endl; - } - catch (const std::exception &e) { - std::cerr << e.what() << std::endl; - } - - return EXIT_SUCCESS; -} - -#else -int main() -{ -#if !defined(VISP_HAVE_REALSENSE) - std::cout << "Install librealsense to make this test work." << std::endl; -#endif -#if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) to make this test work." - << std::endl; -#endif -#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI) - std::cout << "X11 or GDI are needed." << std::endl; -#endif - return EXIT_SUCCESS; -} -#endif diff --git a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h index eb63fa007e..7f1d4f9a33 100644 --- a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h +++ b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPose.h @@ -36,7 +36,7 @@ #define _vpMegaPose_h_ #include -#if defined(VISP_HAVE_NLOHMANN_JSON) +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS) #include #include diff --git a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h index a806e2ce8e..5dc6026b89 100644 --- a/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h +++ b/modules/tracker/dnn/include/visp3/dnn_tracker/vpMegaPoseTracker.h @@ -37,10 +37,10 @@ #define _vpMegaPoseTracker_h_ #include -#if defined(VISP_HAVE_NLOHMANN_JSON) +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS) #include -#include +#include #include /** diff --git a/modules/tracker/dnn/src/vpMegaPose.cpp b/modules/tracker/dnn/src/vpMegaPose.cpp index e54af3f485..beb4685fdc 100644 --- a/modules/tracker/dnn/src/vpMegaPose.cpp +++ b/modules/tracker/dnn/src/vpMegaPose.cpp @@ -33,9 +33,12 @@ * *****************************************************************************/ -#include #include +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS) + +#include + #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX #include #include @@ -230,8 +233,8 @@ void decode(const std::vector &buffer, unsigned int &index, vpHomogeneo } /* -Decode multiple objects from a byte array. -These objects can have different types. They are read from the buffer in the order that they are given to the function. + Decode multiple objects from a byte array. + These objects can have different types. They are read from the buffer in the order that they are given to the function. */ template void decode(const std::vector &buffer, unsigned int &index, T &object, Rest& ...rest) @@ -276,20 +279,19 @@ void handleWrongReturnMessage(const vpMegaPose::ServerMessage code, std::vector< const std::unordered_map vpMegaPose::m_codeMap = { - {ServerMessage::ERR, "RERR"}, - {ServerMessage::OK, "OKOK"}, - {ServerMessage::GET_POSE, "GETP"}, - {ServerMessage::RET_POSE, "RETP"}, - {ServerMessage::SET_INTR, "INTR"}, - {ServerMessage::GET_VIZ, "GETV"}, - {ServerMessage::RET_VIZ, "RETV"}, - {ServerMessage::GET_SCORE, "GSCO"}, - {ServerMessage::RET_SCORE, "RSCO"}, - {ServerMessage::SET_SO3_GRID_SIZE, "SO3G"}, - {ServerMessage::GET_LIST_OBJECTS, "GLSO"}, - {ServerMessage::RET_LIST_OBJECTS, "RLSO"}, - {ServerMessage::EXIT, "EXIT"}, - + {ServerMessage::ERR, "RERR"}, + {ServerMessage::OK, "OKOK"}, + {ServerMessage::GET_POSE, "GETP"}, + {ServerMessage::RET_POSE, "RETP"}, + {ServerMessage::SET_INTR, "INTR"}, + {ServerMessage::GET_VIZ, "GETV"}, + {ServerMessage::RET_VIZ, "RETV"}, + {ServerMessage::GET_SCORE, "GSCO"}, + {ServerMessage::RET_SCORE, "RSCO"}, + {ServerMessage::SET_SO3_GRID_SIZE, "SO3G"}, + {ServerMessage::GET_LIST_OBJECTS, "GLSO"}, + {ServerMessage::RET_LIST_OBJECTS, "RLSO"}, + {ServerMessage::EXIT, "EXIT"}, }; std::string vpMegaPose::messageToString(const vpMegaPose::ServerMessage messageType) @@ -326,7 +328,7 @@ std::pair> vpMegaPose::readMessa #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX size_t readCount = read(m_serverSocket, &size, sizeof(uint32_t)); #else - size_t readCount = recv(m_serverSocket, reinterpret_cast(&size), sizeof(uint32_t), 0); + size_t readCount = recv(m_serverSocket, reinterpret_cast(&size), sizeof(uint32_t), 0); #endif if (readCount != sizeof(uint32_t)) { throw vpException(vpException::ioError, "MegaPose: Error while reading data from socket"); @@ -337,7 +339,7 @@ std::pair> vpMegaPose::readMessa #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX readCount = read(m_serverSocket, code, MEGAPOSE_CODE_SIZE); #else - readCount = recv(m_serverSocket, reinterpret_cast(code), MEGAPOSE_CODE_SIZE, 0); + readCount = recv(m_serverSocket, reinterpret_cast(code), MEGAPOSE_CODE_SIZE, 0); #endif if (readCount != MEGAPOSE_CODE_SIZE) { throw vpException(vpException::ioError, "MegaPose: Error while reading data from socket"); @@ -351,7 +353,7 @@ std::pair> vpMegaPose::readMessa #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX int actually_read = read(m_serverSocket, &data[read_total], read_size); #else - int actually_read = recv(m_serverSocket, reinterpret_cast(&data[read_total]), read_size, 0); + int actually_read = recv(m_serverSocket, reinterpret_cast(&data[read_total]), read_size, 0); #endif if (actually_read <= 0) { throw vpException(vpException::ioError, "MegaPose: Error while reading data from socket"); @@ -613,3 +615,19 @@ std::vector vpMegaPose::getObjectNames() std::vector result = jsonValue; return result; } + +#else + +// Work around to avoid libvisp_dnn_tracker library empty when threads are not used +class VISP_EXPORT dummy_vpMegaPose +{ +public: + dummy_vpMegaPose() { }; +}; + +#if !defined(VISP_BUILD_SHARED_LIBS) +// Work around to avoid warning: libvisp_dnn_tracker.a(vpMegaPose.cpp.o) has no symbols +void dummy_vpMegaPose_fct() { }; +#endif + +#endif diff --git a/modules/tracker/dnn/src/vpMegaPoseTracker.cpp b/modules/tracker/dnn/src/vpMegaPoseTracker.cpp index af443d3462..2edca7407d 100644 --- a/modules/tracker/dnn/src/vpMegaPoseTracker.cpp +++ b/modules/tracker/dnn/src/vpMegaPoseTracker.cpp @@ -33,6 +33,10 @@ * *****************************************************************************/ +#include + +#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS) + #include #include @@ -72,3 +76,8 @@ void vpMegaPoseTracker::updatePose(const vpHomogeneousMatrix &cTo) m_poseEstimate.cTo = cTo; } +#elif !defined(VISP_BUILD_SHARED_LIBS) +// Work around to avoid warning: libvisp_dnn_tracker.a(vpMegaPoseTracker.cpp.o) has no symbols +void dummy_vpMegaPoseTracker(){}; + +#endif diff --git a/modules/tracker/klt/src/vpKltOpencv.cpp b/modules/tracker/klt/src/vpKltOpencv.cpp index ffd237b816..6f74012751 100644 --- a/modules/tracker/klt/src/vpKltOpencv.cpp +++ b/modules/tracker/klt/src/vpKltOpencv.cpp @@ -51,16 +51,16 @@ vpKltOpencv::vpKltOpencv() : m_gray(), m_prevGray(), m_points_id(), m_maxCount(500), m_termcrit(), m_winSize(10), m_qualityLevel(0.01), - m_minDistance(15), m_minEigThreshold(1e-4), m_harris_k(0.04), m_blockSize(3), m_useHarrisDetector(1), - m_pyrMaxLevel(3), m_next_points_id(0), m_initial_guess(false) + m_minDistance(15), m_minEigThreshold(1e-4), m_harris_k(0.04), m_blockSize(3), m_useHarrisDetector(1), + m_pyrMaxLevel(3), m_next_points_id(0), m_initial_guess(false) { m_termcrit = cv::TermCriteria(cv::TermCriteria::COUNT | cv::TermCriteria::EPS, 20, 0.03); } vpKltOpencv::vpKltOpencv(const vpKltOpencv ©) : m_gray(), m_prevGray(), m_points_id(), m_maxCount(500), m_termcrit(), m_winSize(10), m_qualityLevel(0.01), - m_minDistance(15), m_minEigThreshold(1e-4), m_harris_k(0.04), m_blockSize(3), m_useHarrisDetector(1), - m_pyrMaxLevel(3), m_next_points_id(0), m_initial_guess(false) + m_minDistance(15), m_minEigThreshold(1e-4), m_harris_k(0.04), m_blockSize(3), m_useHarrisDetector(1), + m_pyrMaxLevel(3), m_next_points_id(0), m_initial_guess(false) { *this = copy; } @@ -88,7 +88,7 @@ vpKltOpencv &vpKltOpencv::operator=(const vpKltOpencv ©) return *this; } -vpKltOpencv::~vpKltOpencv() {} +vpKltOpencv::~vpKltOpencv() { } void vpKltOpencv::initTracking(const cv::Mat &I, const cv::Mat &mask) { @@ -127,7 +127,8 @@ void vpKltOpencv::track(const cv::Mat &I) if (m_initial_guess) { flags |= cv::OPTFLOW_USE_INITIAL_FLOW; m_initial_guess = false; - } else { + } + else { std::swap(m_points[1], m_points[0]); } @@ -275,7 +276,8 @@ void vpKltOpencv::initTracking(const cv::Mat &I, const std::vector m_next_points_id = 0; for (size_t i = 0; i < m_points[1].size(); i++) m_points_id.push_back(m_next_points_id++); - } else { + } + else { long max = 0; for (size_t i = 0; i < m_points[1].size(); i++) { m_points_id.push_back(ids[i]); @@ -326,13 +328,12 @@ void vpKltOpencv::suppressFeature(const int &index) class VISP_EXPORT dummy_vpKltOpencv { public: - dummy_vpKltOpencv(){}; + dummy_vpKltOpencv() { }; }; #if !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_klt.a(vpKltOpenCV.cpp.o) has no -// symbols -void dummy_vpKltOpenCV_fct(){}; +// Work around to avoid warning: libvisp_klt.a(vpKltOpenCV.cpp.o) has no symbols +void dummy_vpKltOpenCV_fct() { }; #endif #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtTukeyEstimator.h old mode 100755 new mode 100644 diff --git a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp index eb5b1b9a2c..21a7475d42 100644 --- a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp +++ b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp @@ -1461,7 +1461,6 @@ void vpMbKltTracker::setUseKltTracking(const std::string &name, const bool &useK } #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_mbt.a(vpMbKltTracker.cpp.o) has no -// symbols +// Work around to avoid warning: libvisp_mbt.a(vpMbKltTracker.cpp.o) has no symbols void dummy_vpMbKltTracker() { }; #endif // VISP_HAVE_OPENCV diff --git a/modules/tracker/mbt/src/vpMbTracker.cpp b/modules/tracker/mbt/src/vpMbTracker.cpp index 4f973fe94e..686c7a830e 100644 --- a/modules/tracker/mbt/src/vpMbTracker.cpp +++ b/modules/tracker/mbt/src/vpMbTracker.cpp @@ -93,7 +93,7 @@ #include #endif -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) #include #endif @@ -101,7 +101,7 @@ namespace { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::mutex g_mutex_cout; #endif /*! @@ -1838,7 +1838,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbrPoint << " points" << std::endl; @@ -1887,7 +1887,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbrLine << " lines" << std::endl; @@ -1969,7 +1969,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbrPolygonLine << " polygon lines" << std::endl; @@ -2058,7 +2058,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbrPolygonPoint << " polygon points" << std::endl; @@ -2131,7 +2131,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbCylinder << " cylinders" << std::endl; @@ -2213,7 +2213,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << caoNbCircle << " circles" << std::endl; @@ -2278,7 +2278,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "Global information for " << vpIoTools::getName(modelFile) << " :" << std::endl; @@ -2290,7 +2290,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::lock_guard lock(g_mutex_cout); #endif std::cout << "> " << nbPoints << " points" << std::endl; diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp index 3e23e77981..95334199c3 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTrackerDeterminist.cpp @@ -35,7 +35,7 @@ #include -#if defined(VISP_HAVE_CATCH2) +#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_THREADS) #define CATCH_CONFIG_ENABLE_BENCHMARKING #define CATCH_CONFIG_RUNNER #include diff --git a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp index a66ea1eb23..634b7a300f 100644 --- a/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp +++ b/modules/tracker/tt_mi/src/mi/vpTemplateTrackerMI.cpp @@ -78,9 +78,9 @@ void vpTemplateTrackerMI::setBspline(const vpBsplineType &newbs) vpTemplateTrackerMI::vpTemplateTrackerMI(vpTemplateTrackerWarp *_warp) : vpTemplateTracker(_warp), hessianComputation(USE_HESSIEN_NORMAL), ApproxHessian(HESSIAN_NEW), lambda(0), temp(nullptr), - Prt(nullptr), dPrt(nullptr), Pt(nullptr), Pr(nullptr), d2Prt(nullptr), PrtTout(nullptr), dprtemp(nullptr), PrtD(nullptr), dPrtD(nullptr), - influBspline(0), bspline(3), Nc(8), Ncb(0), d2Ix(), d2Iy(), d2Ixy(), MI_preEstimation(0), MI_postEstimation(0), - NMI_preEstimation(0), NMI_postEstimation(0), covarianceMatrix(), computeCovariance(false) + Prt(nullptr), dPrt(nullptr), Pt(nullptr), Pr(nullptr), d2Prt(nullptr), PrtTout(nullptr), dprtemp(nullptr), PrtD(nullptr), dPrtD(nullptr), + influBspline(0), bspline(3), Nc(8), Ncb(0), d2Ix(), d2Iy(), d2Ixy(), MI_preEstimation(0), MI_postEstimation(0), + NMI_preEstimation(0), NMI_postEstimation(0), covarianceMatrix(), computeCovariance(false) { Ncb = Nc + bspline; influBspline = bspline * bspline; @@ -272,7 +272,8 @@ double vpTemplateTrackerMI::getNormalizedCost(const vpImage &I, c int Tij_ = static_cast(Tij); if (!blur) { IW = I[(int)i2][(int)j2]; - } else { + } + else { IW = BI.getValue(i2, j2); } int IW_ = static_cast(IW); @@ -438,7 +439,7 @@ void vpTemplateTrackerMI::computeHessien(vpMatrix &Hessian) for (unsigned int jt = 0; jt < nbParam; jt++) { if (ApproxHessian != HESSIAN_NONSECOND && ApproxHessian != HESSIAN_NEW) Hessian[it][jt] += - dprtemp[it] * dprtemp[jt] * Prt_Pt_ + d2Prt[r_Ncb_t_nbParam2_it_nbParam_ + jt] * dtemp; + dprtemp[it] * dprtemp[jt] * Prt_Pt_ + d2Prt[r_Ncb_t_nbParam2_it_nbParam_ + jt] * dtemp; else if (ApproxHessian == HESSIAN_NEW) Hessian[it][jt] += d2Prt[r_Ncb_t_nbParam2_it_nbParam_ + jt] * dtemp; else @@ -656,7 +657,8 @@ double vpTemplateTrackerMI::getMI(const vpImage &I, int &nc, cons delete[] tPt; return 0; - } else { + } + else { for (unsigned int r = 0; r < tNcb; r++) for (unsigned int t = 0; t < tNcb; t++) tPrt[r * tNcb + t] = tPrt[r * tNcb + t] / Nbpoint; diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index 5eaef2c574..e476fb83be 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -49,7 +49,7 @@ #include #include -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) #include #endif @@ -355,7 +355,7 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo throw(vpPoseException(vpPoseException::notInitializedError, "Not enough point to compute the pose")); } -#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) +#if defined(VISP_HAVE_THREADS) unsigned int nbThreads = 1; bool executeParallelVersion = useParallelRansac; #else @@ -363,7 +363,7 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo #endif if (executeParallelVersion) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) if (nbParallelRansacThreads <= 0) { // Get number of CPU threads nbThreads = std::thread::hardware_concurrency(); @@ -381,7 +381,7 @@ bool vpPose::poseRansac(vpHomogeneousMatrix &cMo, bool (*func)(const vpHomogeneo bool foundSolution = false; if (executeParallelVersion) { -#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_THREADS) std::vector threadpool; std::vector ransacWorkers; diff --git a/platforms/android/build_sdk.py b/platforms/android/build_sdk.py old mode 100755 new mode 100644 diff --git a/script/make-coverage-report.sh b/script/make-coverage-report.sh old mode 100755 new mode 100644 diff --git a/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp b/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp index 4e682c121e..46c45a5922 100644 --- a/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp +++ b/tutorial/detection/face/tutorial-face-detector-live-threaded.cpp @@ -2,39 +2,29 @@ #include #include -#include -#include #include #include #include #include #include -#if defined(HAVE_OPENCV_OBJDETECT) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEOIO) && (defined(VISP_HAVE_PTHREAD) || defined(_WIN32)) +#if defined(HAVE_OPENCV_OBJDETECT) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC) \ + && defined(HAVE_OPENCV_VIDEOIO) && defined(VISP_HAVE_THREADS) + +#include +#include #include // Shared vars typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; -t_CaptureState s_capture_state = capture_waiting; -bool s_face_available = false; -#if defined(VISP_HAVE_V4L2) -vpImage s_frame; -#elif defined(VISP_HAVE_OPENCV) -cv::Mat s_frame; -#endif -vpMutex s_mutex_capture; -vpMutex s_mutex_face; -vpRect s_face_bbox; -vpThread::Return captureFunction(vpThread::Args args) -{ #if defined(VISP_HAVE_V4L2) - vpV4l2Grabber cap = *(static_cast(args)); +void captureFunction(vpV4l2Grabber &cap, std::mutex &mutex_capture, vpImage &frame, t_CaptureState &capture_state) #elif defined(HAVE_OPENCV_VIDEOIO) - cv::VideoCapture cap = *((cv::VideoCapture *)args); +void captureFunction(cv::VideoCapture &cap, std::mutex &mutex_capture, cv::Mat &frame, t_CaptureState &capture_state) #endif - +{ // If the image is larger than 640 by 480, we subsample #if defined(VISP_HAVE_V4L2) vpImage frame_; @@ -50,26 +40,28 @@ vpThread::Return captureFunction(vpThread::Args args) // Update shared data { - vpMutex::vpScopedLock lock(s_mutex_capture); - if (s_capture_state == capture_stopped) + std::lock_guard lock(mutex_capture); + if (capture_state == capture_stopped) stop_capture_ = true; else - s_capture_state = capture_started; - s_frame = frame_; + capture_state = capture_started; + frame = frame_; } } { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } std::cout << "End of capture thread" << std::endl; - return 0; } -vpThread::Return displayFunction(vpThread::Args args) +#if defined(VISP_HAVE_V4L2) +void displayFunction(std::mutex &mutex_capture, std::mutex &mutex_face, vpImage &frame, t_CaptureState &capture_state, vpRect &face_bbox, bool &face_available) +#elif defined(HAVE_OPENCV_VIDEOIO) +void displayFunction(std::mutex &mutex_capture, std::mutex &mutex_face, cv::Mat &frame, t_CaptureState &capture_state, vpRect &face_bbox, bool &face_available) +#endif { - (void)args; // Avoid warning: unused parameter args vpImage I_; t_CaptureState capture_state_; @@ -83,20 +75,20 @@ vpThread::Return displayFunction(vpThread::Args args) #endif do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); + mutex_capture.lock(); + capture_state_ = capture_state; + mutex_capture.unlock(); // Check if a frame is available if (capture_state_ == capture_started) { // Get the frame and convert it to a ViSP image used by the display // class { - vpMutex::vpScopedLock lock(s_mutex_capture); + std::lock_guard lock(mutex_capture); #if defined(VISP_HAVE_V4L2) - I_ = s_frame; + I_ = frame; #elif defined(VISP_HAVE_OPENCV) - vpImageConvert::convert(s_frame, I_); + vpImageConvert::convert(frame, I_); #endif } @@ -117,9 +109,10 @@ vpThread::Return displayFunction(vpThread::Args args) // Check if a face was detected { - vpMutex::vpScopedLock lock(s_mutex_face); - face_available_ = s_face_available; - face_bbox_ = s_face_bbox; + + std::lock_guard lock(mutex_face); + face_available_ = face_available; + face_bbox_ = face_bbox; } if (face_available_) { // Access to the face bounding box to display it @@ -130,8 +123,8 @@ vpThread::Return displayFunction(vpThread::Args args) // Trigger end of acquisition with a mouse click vpDisplay::displayText(I_, 10, 10, "Click to exit...", vpColor::red); if (vpDisplay::getClick(I_, false)) { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } // Update the display @@ -147,16 +140,17 @@ vpThread::Return displayFunction(vpThread::Args args) #endif std::cout << "End of display thread" << std::endl; - return 0; } //! [face-detection-threaded detectionFunction] -vpThread::Return detectionFunction(vpThread::Args args) +#if defined(VISP_HAVE_V4L2) +void detectionFunction(std::mutex &mutex_capture, std::mutex &mutex_face, vpImage &frame, t_CaptureState &capture_state, vpRect &face_bbox, std::string &face_cascade_name, bool &face_available) +#elif defined(HAVE_OPENCV_VIDEOIO) +void detectionFunction(std::mutex &mutex_capture, std::mutex &mutex_face, cv::Mat &frame, t_CaptureState &capture_state, vpRect &face_bbox, std::string &face_cascade_name, bool &face_available) +#endif { - std::string opt_face_cascade_name = *((std::string *)args); - vpDetectorFace face_detector_; - face_detector_.setCascadeClassifierFile(opt_face_cascade_name); + face_detector_.setCascadeClassifierFile(face_cascade_name); t_CaptureState capture_state_; #if defined(VISP_HAVE_V4L2) @@ -165,24 +159,24 @@ vpThread::Return detectionFunction(vpThread::Args args) cv::Mat frame_; #endif do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); + mutex_capture.lock(); + capture_state_ = capture_state; + mutex_capture.unlock(); // Check if a frame is available if (capture_state_ == capture_started) { // Backup the frame { - vpMutex::vpScopedLock lock(s_mutex_capture); - frame_ = s_frame; + std::lock_guard lock(mutex_capture); + frame_ = frame; } // Detect faces bool face_found_ = face_detector_.detect(frame_); if (face_found_) { - vpMutex::vpScopedLock lock(s_mutex_face); - s_face_available = true; - s_face_bbox = face_detector_.getBBox(0); // Get largest face bounding box + std::lock_guard lock(mutex_face); + face_available = true; + face_bbox = face_detector_.getBBox(0); // Get largest face bounding box } } else { @@ -190,13 +184,11 @@ vpThread::Return detectionFunction(vpThread::Args args) } } while (capture_state_ != capture_stopped); std::cout << "End of face detection thread" << std::endl; - - return 0; } //! [face-detection-threaded detectionFunction] //! [face-detection-threaded mainFunction] -int main(int argc, const char *argv []) +int main(int argc, const char *argv[]) { std::string opt_face_cascade_name = "./haarcascade_frontalface_alt.xml"; unsigned int opt_device = 0; @@ -221,12 +213,14 @@ int main(int argc, const char *argv []) // Instantiate the capture #if defined(VISP_HAVE_V4L2) + vpImage frame; vpV4l2Grabber cap; std::ostringstream device; device << "/dev/video" << opt_device; cap.setDevice(device.str()); cap.setScale(opt_scale); #elif defined(HAVE_OPENCV_VIDEOIO) + cv::Mat frame; cv::VideoCapture cap; cap.open(opt_device); #if (VISP_HAVE_OPENCV_VERSION >= 0x030000) @@ -242,10 +236,18 @@ int main(int argc, const char *argv []) #endif #endif + std::mutex mutex_capture; + std::mutex mutex_face; + vpRect face_bbox; + t_CaptureState capture_state = capture_waiting; + bool face_available = false; + // Start the threads - vpThread thread_capture((vpThread::Fn)captureFunction, (vpThread::Args)&cap); - vpThread thread_display((vpThread::Fn)displayFunction); - vpThread thread_detection((vpThread::Fn)detectionFunction, (vpThread::Args)&opt_face_cascade_name); + std::thread thread_capture(&captureFunction, std::ref(cap), std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); + std::thread thread_display(&displayFunction, std::ref(mutex_capture), std::ref(mutex_face), std::ref(frame), + std::ref(capture_state), std::ref(face_bbox), std::ref(face_available)); + std::thread thread_detection(&detectionFunction, std::ref(mutex_capture), std::ref(mutex_face), std::ref(frame), + std::ref(capture_state), std::ref(face_bbox), std::ref(opt_face_cascade_name), std::ref(face_available)); // Wait until thread ends up thread_capture.join(); diff --git a/tutorial/grabber/tutorial-grabber-1394.cpp b/tutorial/grabber/tutorial-grabber-1394.cpp index 8593aeca02..d495fccb1e 100644 --- a/tutorial/grabber/tutorial-grabber-1394.cpp +++ b/tutorial/grabber/tutorial-grabber-1394.cpp @@ -58,7 +58,7 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_DC1394) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_DC1394) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp index 244e93e047..dc08bb5b45 100644 --- a/tutorial/grabber/tutorial-grabber-basler-pylon.cpp +++ b/tutorial/grabber/tutorial-grabber-basler-pylon.cpp @@ -73,7 +73,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_PYLON) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_PYLON) && defined(VISP_HAVE_THREADS) try { unsigned int opt_device = 0; std::string opt_type("GigE"); diff --git a/tutorial/grabber/tutorial-grabber-bebop2.cpp b/tutorial/grabber/tutorial-grabber-bebop2.cpp index e7c14dbb53..ab2c985e3a 100644 --- a/tutorial/grabber/tutorial-grabber-bebop2.cpp +++ b/tutorial/grabber/tutorial-grabber-bebop2.cpp @@ -72,7 +72,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char **argv) { -#if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_FFMPEG) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_ARSDK) && defined(VISP_HAVE_FFMPEG) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-flycapture.cpp b/tutorial/grabber/tutorial-grabber-flycapture.cpp index d3251c0480..feb532ddc6 100644 --- a/tutorial/grabber/tutorial-grabber-flycapture.cpp +++ b/tutorial/grabber/tutorial-grabber-flycapture.cpp @@ -60,7 +60,7 @@ void usage(const char *argv[], int error) int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_FLYCAPTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_FLYCAPTURE) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-ids-ueye.cpp b/tutorial/grabber/tutorial-grabber-ids-ueye.cpp index 635fa29fa2..fe6886eec0 100644 --- a/tutorial/grabber/tutorial-grabber-ids-ueye.cpp +++ b/tutorial/grabber/tutorial-grabber-ids-ueye.cpp @@ -107,7 +107,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_UEYE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_UEYE) && defined(VISP_HAVE_THREADS) try { unsigned int opt_device = 0; std::string opt_seqname; @@ -217,7 +217,7 @@ int main(int argc, const char *argv[]) std::cout << "Active camera is Model " << g.getActiveCameraModel() << " with S/N: " << g.getActiveCameraSerialNumber() << std::endl; -//! [Open connection] + //! [Open connection] g.open(I); //! [Open connection] diff --git a/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp b/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp index b42cc9f944..78bb337b40 100644 --- a/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp +++ b/tutorial/grabber/tutorial-grabber-opencv-threaded.cpp @@ -3,38 +3,34 @@ #include #include -#include -#include #include #include #include -#if defined(HAVE_OPENCV_VIDEOIO) && (defined(VISP_HAVE_PTHREAD) || defined(_WIN32)) +#if defined(HAVE_OPENCV_VIDEOIO) && defined(VISP_HAVE_THREADS) + +#include +#include #include #include -// Shared vars +// Possible capture states typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; -t_CaptureState s_capture_state = capture_waiting; -cv::Mat s_frame; -vpMutex s_mutex_capture; //! [capture-multi-threaded declaration] //! [capture-multi-threaded captureFunction] -vpThread::Return captureFunction(vpThread::Args args) +void captureFunction(cv::VideoCapture &cap, std::mutex &mutex_capture, cv::Mat &frame, t_CaptureState &capture_state) { - cv::VideoCapture cap = *((cv::VideoCapture *)args); - if (!cap.isOpened()) { // check if we succeeded std::cout << "Unable to start capture" << std::endl; - return 0; + return; } cv::Mat frame_; int i = 0; while ((i++ < 100) && !cap.read(frame_)) { - }; // warm up camera by skiping unread frames + }; // warm up camera by skipping unread frames bool stop_capture_ = false; @@ -45,29 +41,27 @@ vpThread::Return captureFunction(vpThread::Args args) // Update shared data { - vpMutex::vpScopedLock lock(s_mutex_capture); - if (s_capture_state == capture_stopped) + std::lock_guard lock(mutex_capture); + if (capture_state == capture_stopped) stop_capture_ = true; else - s_capture_state = capture_started; - s_frame = frame_; + capture_state = capture_started; + frame = frame_; } } { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } std::cout << "End of capture thread" << std::endl; - return 0; } //! [capture-multi-threaded captureFunction] //! [capture-multi-threaded displayFunction] -vpThread::Return displayFunction(vpThread::Args args) +void displayFunction(std::mutex &mutex_capture, cv::Mat &frame, t_CaptureState &capture_state) { - (void)args; // Avoid warning: unused parameter args vpImage I_; t_CaptureState capture_state_; @@ -79,17 +73,17 @@ vpThread::Return displayFunction(vpThread::Args args) #endif do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); + mutex_capture.lock(); + capture_state_ = capture_state; + mutex_capture.unlock(); // Check if a frame is available if (capture_state_ == capture_started) { // Get the frame and convert it to a ViSP image used by the display // class { - vpMutex::vpScopedLock lock(s_mutex_capture); - vpImageConvert::convert(s_frame, I_); + std::lock_guard lock(mutex_capture); + vpImageConvert::convert(frame, I_); } // Check if we need to initialize the display with the first frame @@ -110,8 +104,8 @@ vpThread::Return displayFunction(vpThread::Args args) // Trigger end of acquisition with a mouse click vpDisplay::displayText(I_, 10, 10, "Click to exit...", vpColor::red); if (vpDisplay::getClick(I_, false)) { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } // Update the display @@ -127,12 +121,11 @@ vpThread::Return displayFunction(vpThread::Args args) #endif std::cout << "End of display thread" << std::endl; - return 0; } //! [capture-multi-threaded displayFunction] //! [capture-multi-threaded mainFunction] -int main(int argc, const char *argv []) +int main(int argc, const char *argv[]) { int opt_device = 0; @@ -150,9 +143,13 @@ int main(int argc, const char *argv []) cv::VideoCapture cap; cap.open(opt_device); + cv::Mat frame; + t_CaptureState capture_state = capture_waiting; + // Create a mutex for capture + std::mutex mutex_capture; // Start the threads - vpThread thread_capture((vpThread::Fn)captureFunction, (vpThread::Args)&cap); - vpThread thread_display((vpThread::Fn)displayFunction); + std::thread thread_capture(&captureFunction, std::ref(cap), std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); + std::thread thread_display(&displayFunction, std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); // Wait until thread ends up thread_capture.join(); diff --git a/tutorial/grabber/tutorial-grabber-opencv.cpp b/tutorial/grabber/tutorial-grabber-opencv.cpp index 0a0d14133a..c41aab74b1 100644 --- a/tutorial/grabber/tutorial-grabber-opencv.cpp +++ b/tutorial/grabber/tutorial-grabber-opencv.cpp @@ -118,7 +118,7 @@ int main(int argc, const char *argv[]) std::cout << "Record name: " << opt_seqname << std::endl; } -#if defined(HAVE_OPENCV_VIDEOIO) && defined(HAVE_OPENCV_HIGHGUI) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(HAVE_OPENCV_VIDEOIO) && defined(HAVE_OPENCV_HIGHGUI) && defined(VISP_HAVE_THREADS) try { cv::VideoCapture cap(opt_device); // open the default camera if (!cap.isOpened()) { // check if we succeeded diff --git a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp index 6b0b06c2e3..2fab7ac820 100644 --- a/tutorial/grabber/tutorial-grabber-realsense-T265.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense-T265.cpp @@ -56,8 +56,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) \ - && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE2) && (RS2_API_VERSION > ((2 * 10000) + (31 * 100) + 0)) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname_left = "left-%04d.png", opt_seqname_right = "right-%04d.png"; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-realsense.cpp b/tutorial/grabber/tutorial-grabber-realsense.cpp index 424c1f23bf..f038a51c09 100644 --- a/tutorial/grabber/tutorial-grabber-realsense.cpp +++ b/tutorial/grabber/tutorial-grabber-realsense.cpp @@ -75,7 +75,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-structure-core.cpp b/tutorial/grabber/tutorial-grabber-structure-core.cpp index 25799e790f..f3e9417d62 100644 --- a/tutorial/grabber/tutorial-grabber-structure-core.cpp +++ b/tutorial/grabber/tutorial-grabber-structure-core.cpp @@ -72,7 +72,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_OCCIPITAL_STRUCTURE) && defined(VISP_HAVE_THREADS) try { std::string opt_seqname_visible = "visible-%04d.png", opt_seqname_depth = "depth-%04d.png"; int opt_record_mode = 0; diff --git a/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp b/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp index 5a0c538a0a..89ce052f69 100644 --- a/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp +++ b/tutorial/grabber/tutorial-grabber-v4l2-threaded.cpp @@ -1,27 +1,23 @@ //! \example tutorial-grabber-v4l2-threaded.cpp //! [capture-multi-threaded declaration] #include - #include -#include -#include #include #include #include -#if defined(VISP_HAVE_V4L2) && defined(VISP_HAVE_PTHREAD) +#if defined(VISP_HAVE_V4L2) && defined(VISP_HAVE_THREADS) + +#include +#include // Shared vars typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState; -t_CaptureState s_capture_state = capture_waiting; -vpImage s_frame; -vpMutex s_mutex_capture; //! [capture-multi-threaded declaration] //! [capture-multi-threaded captureFunction] -vpThread::Return captureFunction(vpThread::Args args) +void captureFunction(vpV4l2Grabber &cap, std::mutex &mutex_capture, vpImage &frame, t_CaptureState &capture_state) { - vpV4l2Grabber cap = *(static_cast(args)); vpImage frame_; bool stop_capture_ = false; @@ -34,28 +30,26 @@ vpThread::Return captureFunction(vpThread::Args args) // Update shared data { - vpMutex::vpScopedLock lock(s_mutex_capture); - if (s_capture_state == capture_stopped) + std::lock_guard lock(mutex_capture); + if (capture_state == capture_stopped) stop_capture_ = true; else - s_capture_state = capture_started; - s_frame = frame_; + capture_state = capture_started; + frame = frame_; } } { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } std::cout << "End of capture thread" << std::endl; - return 0; } //! [capture-multi-threaded captureFunction] //! [capture-multi-threaded displayFunction] -vpThread::Return displayFunction(vpThread::Args args) +void displayFunction(std::mutex &mutex_capture, vpImage &frame, t_CaptureState &capture_state) { - (void)args; // Avoid warning: unused parameter args vpImage I_; t_CaptureState capture_state_; @@ -65,16 +59,16 @@ vpThread::Return displayFunction(vpThread::Args args) #endif do { - s_mutex_capture.lock(); - capture_state_ = s_capture_state; - s_mutex_capture.unlock(); + mutex_capture.lock(); + capture_state_ = capture_state; + mutex_capture.unlock(); // Check if a frame is available if (capture_state_ == capture_started) { // Create a copy of the captured frame { - vpMutex::vpScopedLock lock(s_mutex_capture); - I_ = s_frame; + std::lock_guard lock(mutex_capture); + I_ = frame; } // Check if we need to initialize the display with the first frame @@ -92,13 +86,14 @@ vpThread::Return displayFunction(vpThread::Args args) // Trigger end of acquisition with a mouse click vpDisplay::displayText(I_, 10, 10, "Click to exit...", vpColor::red); if (vpDisplay::getClick(I_, false)) { - vpMutex::vpScopedLock lock(s_mutex_capture); - s_capture_state = capture_stopped; + std::lock_guard lock(mutex_capture); + capture_state = capture_stopped; } // Update the display vpDisplay::flush(I_); - } else { + } + else { vpTime::wait(2); // Sleep 2ms } } while (capture_state_ != capture_stopped); @@ -108,7 +103,6 @@ vpThread::Return displayFunction(vpThread::Args args) #endif std::cout << "End of display thread" << std::endl; - return 0; } //! [capture-multi-threaded displayFunction] @@ -127,8 +121,8 @@ int main(int argc, const char *argv[]) opt_scale = (unsigned int)atoi(argv[i + 1]); else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "--h") { std::cout << "Usage: " << argv[0] - << " [--camera_device ] [--scale ]" - << " [--help] [-h]" << std::endl; + << " [--camera_device ] [--scale ]" + << " [--help] [-h]" << std::endl; return EXIT_SUCCESS; } } @@ -140,9 +134,13 @@ int main(int argc, const char *argv[]) g.setDevice(device.str()); g.setScale(opt_scale); + vpImage frame; + std::mutex mutex_capture; + t_CaptureState capture_state = capture_waiting; + // Start the threads - vpThread thread_capture((vpThread::Fn)captureFunction, (vpThread::Args)&g); - vpThread thread_display((vpThread::Fn)displayFunction); + std::thread thread_capture(&captureFunction, std::ref(g), std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); + std::thread thread_display(&displayFunction, std::ref(mutex_capture), std::ref(frame), std::ref(capture_state)); // Wait until thread ends up thread_capture.join(); diff --git a/tutorial/grabber/tutorial-grabber-v4l2.cpp b/tutorial/grabber/tutorial-grabber-v4l2.cpp index 36fba4330e..a65213fd7a 100644 --- a/tutorial/grabber/tutorial-grabber-v4l2.cpp +++ b/tutorial/grabber/tutorial-grabber-v4l2.cpp @@ -76,7 +76,7 @@ void usage(const char *argv[], int error) */ int main(int argc, const char *argv[]) { -#if defined(VISP_HAVE_V4L2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) +#if defined(VISP_HAVE_V4L2) && defined(VISP_HAVE_THREADS) try { int opt_device = 0; unsigned int opt_scale = 1; // Default value is 2 in the constructor. Turn diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.h b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.h old mode 100755 new mode 100644 diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.mm b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageConversion.mm old mode 100755 new mode 100644 diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.h b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.h old mode 100755 new mode 100644 diff --git a/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.mm b/tutorial/ios/AprilTagLiveCamera/VispHelper/ImageDisplay.mm old mode 100755 new mode 100644 diff --git a/tutorial/robot/mbot/raspberry/daemon/visual-servo b/tutorial/robot/mbot/raspberry/daemon/visual-servo old mode 100755 new mode 100644 diff --git a/tutorial/tracking/dnn/tutorial-megapose-live-single-object-tracking.cpp b/tutorial/tracking/dnn/tutorial-megapose-live-single-object-tracking.cpp index 14ba48ae7f..3aa239b2c9 100644 --- a/tutorial/tracking/dnn/tutorial-megapose-live-single-object-tracking.cpp +++ b/tutorial/tracking/dnn/tutorial-megapose-live-single-object-tracking.cpp @@ -6,7 +6,8 @@ // Check if std:c++17 or higher #if ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) && \ defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_VIDEOIO) && \ - defined(HAVE_OPENCV_DNN) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(HAVE_OPENCV_HIGHGUI)) + defined(HAVE_OPENCV_DNN) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(HAVE_OPENCV_HIGHGUI)) && \ + defined(VISP_HAVE_THREADS) #include diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp old mode 100755 new mode 100644 diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp old mode 100755 new mode 100644 diff --git a/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-afma6.cpp b/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-afma6.cpp index 143b585f04..603fe9dcfc 100644 --- a/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-afma6.cpp +++ b/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-afma6.cpp @@ -30,7 +30,7 @@ void display_trajectory(const vpImage &I, std::vector &p int main() { -#if defined(VISP_HAVE_PTHREAD) +#if defined(VISP_HAVE_THREADS) try { vpHomogeneousMatrix cdMo(0, 0, 0.75, 0, 0, 0); vpHomogeneousMatrix cMo(-0.15, 0.1, 1., vpMath::rad(-10), vpMath::rad(10), vpMath::rad(50)); diff --git a/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-viper.cpp b/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-viper.cpp index 68b20c377b..00bbc20c4e 100644 --- a/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-viper.cpp +++ b/tutorial/visual-servo/ibvs/tutorial-ibvs-4pts-wireframe-robot-viper.cpp @@ -30,7 +30,7 @@ void display_trajectory(const vpImage &I, std::vector &p int main() { -#if defined(VISP_HAVE_PTHREAD) +#if defined(VISP_HAVE_THREADS) try { vpHomogeneousMatrix cdMo(0, 0, 0.75, 0, 0, 0); vpHomogeneousMatrix cMo(0.15, -0.1, 1., vpMath::rad(10), vpMath::rad(-10), vpMath::rad(50)); From 1ca7cc0c107562db41263c903c1eb69485643b4c Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 7 Feb 2024 14:28:56 +0100 Subject: [PATCH 026/164] Use friend inline (instead of inline friend) required by the python bindings --- .../include/visp3/imgproc/vpCircleHoughTransform.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h index 5580948782..42ecd57ffb 100644 --- a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h +++ b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h @@ -541,7 +541,7 @@ class VISP_EXPORT vpCircleHoughTransform * \param[in] j : The JSON object, resulting from the parsing of a JSON file. * \param[out] params : The circle Hough transform parameters that will be initialized from the JSON data. */ - inline friend void from_json(const json &j, vpCircleHoughTransformParameters ¶ms) + friend inline void from_json(const json &j, vpCircleHoughTransformParameters ¶ms) { std::string filteringAndGradientName = vpImageFilter::vpCannyFilteringAndGradientTypeToString(params.m_filteringAndGradientType); filteringAndGradientName = j.value("filteringAndGradientType", filteringAndGradientName); @@ -619,7 +619,7 @@ class VISP_EXPORT vpCircleHoughTransform * \param[out] j : A JSON parser object. * \param[in] params : The circle Hough transform parameters that will be serialized in the json object. */ - inline friend void to_json(json &j, const vpCircleHoughTransformParameters ¶ms) + friend inline void to_json(json &j, const vpCircleHoughTransformParameters ¶ms) { std::pair radiusLimits = { params.m_minRadius, params.m_maxRadius }; @@ -760,7 +760,7 @@ class VISP_EXPORT vpCircleHoughTransform * \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. */ - inline friend void from_json(const json &j, vpCircleHoughTransform &detector) + friend inline void from_json(const json &j, vpCircleHoughTransform &detector) { detector.m_algoParams = j; } @@ -771,7 +771,7 @@ class VISP_EXPORT vpCircleHoughTransform * \param[out] j A JSON parser object. * \param[in] detector The vpCircleHoughTransform that must be parsed into JSON format. */ - inline friend void to_json(json &j, const vpCircleHoughTransform &detector) + friend inline void to_json(json &j, const vpCircleHoughTransform &detector) { j = detector.m_algoParams; } From a68f1d5e2e3363f87f26d9c2d333f800ae9cc288 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 7 Feb 2024 14:35:16 +0100 Subject: [PATCH 027/164] Fix typo --- doc/tutorial/python/tutorial-install-python-bindings.dox | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 6bb6dd204f..680b125af1 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -302,7 +302,7 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: - These commands create a `venv/` directory in your project where all dependencies are installed. You need to activate it first though (in every `cmd` Command Prompt terminal instance where you are working on your project): - C:\> venv\Script\activate + C:\> venv\Scripts\activate (venv) C:\> mkdir visp-build-vc17-bindings (venv) C:\> cd visp-build-vc17-bindings (venv) C:\> cmake -G "Visual Studio 17 2022" -A "x64" -Dpybind11_DIR=C:\Users\User\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 ..\visp From 760d7e0ce9fe1f5d03ea5daeab815c17eb0a7092 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 7 Feb 2024 14:48:54 +0100 Subject: [PATCH 028/164] automatically replace inline friend with friend inline when parsing headers in Python bindings --- modules/python/generator/visp_python_bindgen/header.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/modules/python/generator/visp_python_bindgen/header.py b/modules/python/generator/visp_python_bindgen/header.py index faa19986aa..2075e9b304 100644 --- a/modules/python/generator/visp_python_bindgen/header.py +++ b/modules/python/generator/visp_python_bindgen/header.py @@ -162,7 +162,9 @@ def run_preprocessor(self): if not line.startswith('#define'): preprocessed_header_lines.append(line) preprocessed_header_content = ''.join(preprocessed_header_lines) + # Further refine header content: fix some simple parsing bugs preprocessed_header_content = preprocessed_header_content.replace('#include<', '#include <') # Bug in cpp header parser + preprocessed_header_content = preprocessed_header_content.replace('inline friend', 'friend inline') # Bug in cpp header parser return preprocessed_header_content From f75c627c40fac1c970eb5d5a6877fd97985e3008 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 7 Feb 2024 15:48:57 +0100 Subject: [PATCH 029/164] fix partial name resolution only having one iteration --- .../visp_python_bindgen/generator.py | 1 + .../visp_python_bindgen/header_utils.py | 42 +++++++------------ 2 files changed, 17 insertions(+), 26 deletions(-) diff --git a/modules/python/generator/visp_python_bindgen/generator.py b/modules/python/generator/visp_python_bindgen/generator.py index 51216b27eb..27bb5bb41c 100644 --- a/modules/python/generator/visp_python_bindgen/generator.py +++ b/modules/python/generator/visp_python_bindgen/generator.py @@ -101,6 +101,7 @@ def generate_module(generate_path: Path, config_path: Path) -> None: # This parallel implementation is disabled, # since the behaviour on Mac is different and leads to preprocessing not finding vpConfig.h and others # Reverting to a single process version fixes the issue + # with Pool() as pool: # new_all_headers = [] # for result in list(tqdm(pool.imap(header_preprocess, all_headers), total=len(all_headers), file=sys.stderr)): diff --git a/modules/python/generator/visp_python_bindgen/header_utils.py b/modules/python/generator/visp_python_bindgen/header_utils.py index 51ce4778d5..7ee2c26ef6 100644 --- a/modules/python/generator/visp_python_bindgen/header_utils.py +++ b/modules/python/generator/visp_python_bindgen/header_utils.py @@ -92,7 +92,7 @@ def add_level(result: List['HeaderFile'], remainder: List['HeaderFile'], depende class HeaderEnvironment(): def __init__(self, data: ParsedData): self.mapping: Dict[str, str] = self.build_naive_mapping(data.namespace, {}) - + logging.debug('Mapping = ', self.mapping) # Step 2: resolve enumeration names that are possibly hidden behind typedefs from visp_python_bindgen.enum_binding import resolve_enums_and_typedefs enum_reprs, _ = resolve_enums_and_typedefs(data.namespace, self.mapping) @@ -101,43 +101,33 @@ def __init__(self, data: ParsedData): self.mapping[value.name] = enum_repr.name + '::' + value.name def build_naive_mapping(self, data: Union[NamespaceScope, ClassScope], mapping, scope: str = ''): - if isinstance(data, NamespaceScope): - for alias in data.using_alias: - mapping[alias.alias] = get_type(alias.type, {}, mapping) - - for typedef in data.typedefs: - mapping[typedef.name] = scope + typedef.name - - for enum in data.enums: - if not name_is_anonymous(enum.typename): - enum_name = '::'.join([seg.name for seg in enum.typename.segments]) - mapping[enum_name] = scope + enum_name - - for cls in data.classes: - cls_name = '::'.join([seg.name for seg in cls.class_decl.typename.segments]) - mapping[cls_name] = scope + cls_name - mapping.update(self.build_naive_mapping(cls, mapping=mapping, scope=f'{scope}{cls_name}::')) + current_mapping = mapping.copy() + previous_mapping = None - for namespace in data.namespaces: - mapping.update(self.build_naive_mapping(data.namespaces[namespace], mapping=mapping, scope=f'{scope}{namespace}::')) + while current_mapping != previous_mapping: + previous_mapping = current_mapping.copy() - elif isinstance(data, ClassScope): for alias in data.using_alias: - mapping[alias.alias] = get_type(alias.type, {}, mapping) + current_mapping[alias.alias] = get_type(alias.type, {}, current_mapping) for typedef in data.typedefs: - mapping[typedef.name] = scope + typedef.name + current_mapping[typedef.name] = scope + typedef.name for enum in data.enums: if not name_is_anonymous(enum.typename): enum_name = '::'.join([seg.name for seg in enum.typename.segments]) - mapping[enum_name] = scope + enum_name + current_mapping[enum_name] = scope + enum_name for cls in data.classes: cls_name = '::'.join([seg.name for seg in cls.class_decl.typename.segments if not isinstance(seg, types.AnonymousName)]) - mapping[cls_name] = scope + cls_name - mapping.update(self.build_naive_mapping(cls, mapping=mapping, scope=f'{scope}{cls_name}::')) - return mapping + current_mapping[cls_name] = scope + cls_name + current_mapping.update(self.build_naive_mapping(cls, mapping=current_mapping, scope=f'{scope}{cls_name}::')) + + if isinstance(data, NamespaceScope): + for namespace in data.namespaces: + current_mapping.update(self.build_naive_mapping(data.namespaces[namespace], mapping=current_mapping, scope=f'{scope}{namespace}::')) + + return current_mapping def update_with_dependencies(self, other_envs: List['HeaderEnvironment']) -> None: for env in other_envs: From 476ee4c5be603fcb1310f364a8addf1673b738d7 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 7 Feb 2024 15:49:21 +0100 Subject: [PATCH 030/164] fix link error with static variables of vpCircleHoughTransform --- .../visp3/imgproc/vpCircleHoughTransform.h | 4 +- .../imgproc/src/vpCircleHoughTransform.cpp | 38 ++++++++++--------- 2 files changed, 23 insertions(+), 19 deletions(-) diff --git a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h index 42ecd57ffb..e95d14ee0a 100644 --- a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h +++ b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h @@ -1160,8 +1160,8 @@ class VISP_EXPORT vpCircleHoughTransform */ friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpCircleHoughTransform &detector); - static const unsigned char edgeMapOn = 255; - static const unsigned char edgeMapOff = 0; + static const unsigned char edgeMapOn; + static const unsigned char edgeMapOff; protected: /** diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index 19ae63040a..7555905048 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -33,6 +33,10 @@ #include +// Static variables +const unsigned char vpCircleHoughTransform::edgeMapOn = 255; +const unsigned char vpCircleHoughTransform::edgeMapOff = 0; + #if (VISP_CXX_STANDARD == VISP_CXX_STANDARD_98) namespace { @@ -249,7 +253,7 @@ vpCircleHoughTransform::detect(const vpImage &I, const int &nbCir auto hasBetterProba = [](std::pair a, std::pair b) { return (a.second > b.second); - }; + }; #endif std::sort(v_id_proba.begin(), v_id_proba.end(), hasBetterProba); @@ -694,19 +698,19 @@ vpCircleHoughTransform::computeCenterCandidates() const int &offsetX, const int &offsetY, const int &nbCols, const int &nbRows, vpImage &accum, bool &hasToStop) { - if (((x - offsetX) < 0) || - ((x - offsetX) >= nbCols) || - ((y - offsetY) < 0) || - ((y - offsetY) >= nbRows) - ) { - hasToStop = true; - } - else { - float dx = (x_orig - static_cast(x)); - float dy = (y_orig - static_cast(y)); - accum[y - offsetY][x - offsetX] += std::abs(dx) + std::abs(dy); - } - }; + if (((x - offsetX) < 0) || + ((x - offsetX) >= nbCols) || + ((y - offsetY) < 0) || + ((y - offsetY) >= nbRows) + ) { + hasToStop = true; + } + else { + float dx = (x_orig - static_cast(x)); + float dy = (y_orig - static_cast(y)); + accum[y - offsetY][x - offsetX] += std::abs(dx) + std::abs(dy); + } + }; #endif updateAccumulator(x1, y1, x_low, y_low, @@ -851,8 +855,8 @@ vpCircleHoughTransform::computeCenterCandidates() #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) auto sortingCenters = [](const std::pair, float> &position_vote_a, const std::pair, float> &position_vote_b) { - return position_vote_a.second > position_vote_b.second; - }; + return position_vote_a.second > position_vote_b.second; + }; #endif std::sort(merged_peaks_position_votes.begin(), merged_peaks_position_votes.end(), sortingCenters); @@ -988,7 +992,7 @@ vpCircleHoughTransform::computeCircleCandidates() r_effective = weigthedSumRadius / votes; } return r_effective; - }; + }; #endif // Merging similar candidates From 1bb83fdb451649a3e473511985d1149d7b754baf Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 7 Feb 2024 18:29:19 +0100 Subject: [PATCH 031/164] Fix stubs generator not running in windows --- modules/python/stubs/run_stub_generator.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/modules/python/stubs/run_stub_generator.py b/modules/python/stubs/run_stub_generator.py index 129c73f9bb..c8b904112d 100644 --- a/modules/python/stubs/run_stub_generator.py +++ b/modules/python/stubs/run_stub_generator.py @@ -47,10 +47,8 @@ output_root = Path(args.output_root) assert output_root.exists() bin_folder = Path(sys.executable).parent - stubgen_entry_point = bin_folder / 'pybind11-stubgen' - assert stubgen_entry_point.exists() - subprocess.run([str(stubgen_entry_point), '-o', str(output_root.absolute()), '--ignore-all-errors', '_visp'], check=True) + subprocess.run([sys.executable, '-m', 'pybind11_stubgen', '-o', str(output_root.absolute()), '--ignore-all-errors', '_visp'], check=True) # Generate stubs for the bindings (C++ side) and mock it so that they appear in the true 'visp' package p = Path('./_visp') From 97a20f006d8eba2697a08c0531d6a638b3213d11 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 7 Feb 2024 18:56:26 +0100 Subject: [PATCH 032/164] Change file rights of visp-config script to be executable. Previous commit did an unexpected change --- cmake/templates/visp-config.in | 0 cmake/templates/visp-config.install.in | 0 2 files changed, 0 insertions(+), 0 deletions(-) mode change 100644 => 100755 cmake/templates/visp-config.in mode change 100644 => 100755 cmake/templates/visp-config.install.in diff --git a/cmake/templates/visp-config.in b/cmake/templates/visp-config.in old mode 100644 new mode 100755 diff --git a/cmake/templates/visp-config.install.in b/cmake/templates/visp-config.install.in old mode 100644 new mode 100755 From d25c588275fe7b39b2cf04e71233e6fa8c34a926 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 7 Feb 2024 18:57:21 +0100 Subject: [PATCH 033/164] Fix moments examples when std::stread not available --- example/moments/image/servoMomentImage.cpp | 3 +-- example/moments/points/servoMomentPoints.cpp | 13 +++++++++---- example/moments/polygon/servoMomentPolygon.cpp | 13 +++++++++---- 3 files changed, 19 insertions(+), 10 deletions(-) diff --git a/example/moments/image/servoMomentImage.cpp b/example/moments/image/servoMomentImage.cpp index 1cfe5b9352..eb96abf2d8 100644 --- a/example/moments/image/servoMomentImage.cpp +++ b/example/moments/image/servoMomentImage.cpp @@ -31,8 +31,7 @@ * Description: * Example of visual servoing with moments using an image as object * container - * -*****************************************************************************/ + */ /*! \example servoMomentImage.cpp diff --git a/example/moments/points/servoMomentPoints.cpp b/example/moments/points/servoMomentPoints.cpp index 4c3184a2ef..9caf01c575 100644 --- a/example/moments/points/servoMomentPoints.cpp +++ b/example/moments/points/servoMomentPoints.cpp @@ -31,8 +31,7 @@ * Description: * Example of visual servoing with moments using discrete points as object * container - * -*****************************************************************************/ + */ /*! \example servoMomentPoints.cpp @@ -62,14 +61,20 @@ #include #include -#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ - !defined(VISP_HAVE_GTK) && !defined(VISP_HAVE_THREADS) +#if !defined(VISP_HAVE_DISPLAY) int main() { std::cout << "Can't run this example since no display capability is available." << std::endl; std::cout << "You should install one of the following third-party library: X11, OpenCV, GDI, GTK." << std::endl; return EXIT_SUCCESS; } +#elif !defined(VISP_HAVE_THREADS) +int main() +{ + std::cout << "Can't run this example since multi-threading capability is not available." << std::endl; + std::cout << "You should maybe enable cxx11 standard." << std::endl; + return EXIT_SUCCESS; +} #else #ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/example/moments/polygon/servoMomentPolygon.cpp b/example/moments/polygon/servoMomentPolygon.cpp index 776c7528b2..6a55afb8fd 100644 --- a/example/moments/polygon/servoMomentPolygon.cpp +++ b/example/moments/polygon/servoMomentPolygon.cpp @@ -30,8 +30,7 @@ * * Description: * Example of visual servoing with moments using a polygon as object container - * -*****************************************************************************/ + */ /*! \example servoMomentPolygon.cpp @@ -61,14 +60,20 @@ #include #include -#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ - !defined(VISP_HAVE_GTK) && !defined(VISP_HAVE_THREADS) +#if !defined(VISP_HAVE_DISPLAY) int main() { std::cout << "Can't run this example since no display capability is available." << std::endl; std::cout << "You should install one of the following third-party library: X11, OpenCV, GDI, GTK." << std::endl; return EXIT_SUCCESS; } +#elif !defined(VISP_HAVE_THREADS) +int main() +{ + std::cout << "Can't run this example since multi-threading capability is not available." << std::endl; + std::cout << "You should maybe enable cxx11 standard." << std::endl; + return EXIT_SUCCESS; +} #else #ifndef DOXYGEN_SHOULD_SKIP_THIS From 3b1b286e999c70c7ea917b799356cda1397b6619 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 7 Feb 2024 18:58:00 +0100 Subject: [PATCH 034/164] Fix typo --- example/device/laserscanner/SickLDMRS-Process.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/example/device/laserscanner/SickLDMRS-Process.cpp b/example/device/laserscanner/SickLDMRS-Process.cpp index 67bd4974ec..63cddab2c6 100644 --- a/example/device/laserscanner/SickLDMRS-Process.cpp +++ b/example/device/laserscanner/SickLDMRS-Process.cpp @@ -321,8 +321,7 @@ int main(int argc, const char **argv) vpParseArgv::ARGV_NO_DEFAULTS)) { return (EXIT_FAILURE); } - VISP_HAVE_PTHREAD - time_offset = vpTime::measureTimeSecond(); + time_offset = vpTime::measureTimeSecond(); std::thread thread_camera_acq(&camera_acq_and_display_loop); std::thread thread_laser_acq(&laser_acq_loop); From 03861889eaf7772ebada5afefd88779c013346c8 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 7 Feb 2024 18:59:27 +0100 Subject: [PATCH 035/164] Modify pthread detection and usage for Apriltag and deprecated vpMutex and vpThread --- CMakeLists.txt | 20 +++++++++++++++++--- 1 file changed, 17 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c6219b9913..300a3b42de 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -586,6 +586,7 @@ if(SOQT_FOUND) # SoQt < 1.6.0 that depends on Qt4 was found. We need an explicit VP_OPTION(USE_QT Qt "" "Include Coin/SoQt/Qt support" "" ON IF USE_SOQT AND NOT WINRT AND NOT IOS) endif() VP_OPTION(USE_SOXT SOXT "" "Include Coin/SoXt support" "" OFF IF USE_COIN3D AND NOT WINRT AND NOT IOS) +set(THREADS_PREFER_PTHREAD_FLAG TRUE) VP_OPTION(USE_THREADS Threads "" "Include std::thread support" "" ON) VP_OPTION(USE_XML2 XML2 "" "Include libxml2 support" "" ON IF NOT WINRT) @@ -689,14 +690,23 @@ if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_11) unset(USE_ARSDK) set(USE_ARSDK OFF CACHE BOOL "Include Parrot ARSDK support" FORCE) endif() + if(USE_THREADS) + message(WARNING "std::thread was detected but needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable std::thread usage turning USE_THREADS=OFF.") + unset(USE_THREADS) + set(USE_THREADS OFF CACHE BOOL "Include std::thread support" FORCE) + elseif(UNIX) + # Apriltag on unix needs pthread. On windows we are using pthread built-in + if(Threads_FOUND) + set(USE_PTHREAD ON) # for AprilTag only + endif() + endif() 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)) # Since C99 is not supported by MSVC 2010 or prior, we disable apriltag if MSVC < 2012 -VP_OPTION(WITH_APRILTAG "" "" "Build AprilTag as built-in library" "" ON IF (USE_THREADS OR WITH_PTHREAD) AND (NOT WINRT) AND (NOT MSVC_VERSION LESS 1700)) +VP_OPTION(WITH_APRILTAG "" "" "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) @@ -985,7 +995,10 @@ VP_SET(VISP_HAVE_LAPACK_GSL TRUE IF (BUILD_MODULE_visp_core AND USE_GSL)) VP_SET(VISP_HAVE_LAPACK_MKL TRUE IF (BUILD_MODULE_visp_core AND USE_MKL)) VP_SET(VISP_HAVE_LAPACK_NETLIB TRUE IF (BUILD_MODULE_visp_core AND USE_NETLIB)) VP_SET(VISP_HAVE_LAPACK_OPENBLAS TRUE IF (BUILD_MODULE_visp_core AND USE_OPENBLAS)) -VP_SET(VISP_HAVE_PTHREAD TRUE IF (BUILD_MODULE_visp_core AND USE_THREADS)) # Keep for the momment for compat + +# Keep VISP_HAVE_PTHREAD for the moment for compat and for vpMutex and vpThread deprecated classes +VP_SET(VISP_HAVE_PTHREAD TRUE IF (BUILD_MODULE_visp_core AND (USE_PTHREAD AND UNIX))) + VP_SET(VISP_HAVE_THREADS TRUE IF (BUILD_MODULE_visp_core AND USE_THREADS)) VP_SET(VISP_HAVE_XML2 TRUE IF (BUILD_MODULE_visp_core AND USE_XML2)) VP_SET(VISP_HAVE_PCL TRUE IF (BUILD_MODULE_visp_core AND USE_PCL)) @@ -1719,6 +1732,7 @@ status("") status(" Optimization: ") status(" Use OpenMP:" USE_OPENMP THEN "yes" ELSE "no") status(" Use std::thread:" USE_THREADS THEN "yes" ELSE "no") +status(" Use pthread:" USE_PHREADS THEN "yes" ELSE "no") status(" Use pthread (built-in):" WITH_PTHREAD THEN "yes (ver ${PTHREADS_VERSION})" ELSE "no") status(" Use simdlib (built-in):" WITH_SIMDLIB THEN "yes" ELSE "no") status("") From 6da7e0b93faa252fbfc436fc27bff1a888b719ec Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Thu, 8 Feb 2024 09:12:21 +0100 Subject: [PATCH 036/164] Fix build when no display available --- example/moments/image/servoMomentImage.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/example/moments/image/servoMomentImage.cpp b/example/moments/image/servoMomentImage.cpp index eb96abf2d8..e1c345b0a5 100644 --- a/example/moments/image/servoMomentImage.cpp +++ b/example/moments/image/servoMomentImage.cpp @@ -62,14 +62,20 @@ #include #include -#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_OPENCV) && !defined(VISP_HAVE_GDI) && !defined(VISP_HAVE_D3D9) && \ - !defined(VISP_HAVE_GTK) && !defined(VISP_HAVE_THREADS) +#if !defined(VISP_HAVE_DISPLAY) int main() { std::cout << "Can't run this example since no display capability is available." << std::endl; std::cout << "You should install one of the following third-party library: X11, OpenCV, GDI, GTK." << std::endl; return EXIT_SUCCESS; } +#elif !defined(VISP_HAVE_THREADS) +int main() +{ + std::cout << "Can't run this example since multi-threading capability is not available." << std::endl; + std::cout << "You should maybe enable cxx11 standard." << std::endl; + return EXIT_SUCCESS; +} #else #ifndef DOXYGEN_SHOULD_SKIP_THIS From 149394dd8cfa234c8e40f355ffea44e68cd8ac28 Mon Sep 17 00:00:00 2001 From: Souriya Trinh Date: Sun, 4 Feb 2024 14:34:02 +0100 Subject: [PATCH 037/164] Turn-off some dependencies (x11, jpeg, png, xml) to try to mimic the ROS2 CI env. --- .github/workflows/coverage.yml | 14 ++++----- .github/workflows/ios.yml | 14 ++++----- .github/workflows/macos-ustk.yml | 14 ++++----- .github/workflows/macos.yml | 14 ++++----- .github/workflows/other-arch-isolated.yml | 14 ++++----- .github/workflows/other-arch.yml | 14 ++++----- .github/workflows/ubuntu-3rdparty.yml | 14 ++++----- .github/workflows/ubuntu-contrib.yml | 14 ++++----- .github/workflows/ubuntu-dep-apt.yml | 14 ++++----- .github/workflows/ubuntu-dep-src.yml | 14 ++++----- .github/workflows/ubuntu-isolated.yml | 35 ++++++++--------------- .github/workflows/ubuntu-sanitizers.yml | 14 ++++----- .github/workflows/ubuntu-ustk.yml | 14 ++++----- .github/workflows/valgrind.yml | 14 ++++----- .github/workflows/windows-clang.yaml | 14 ++++----- .github/workflows/windows-msvc.yaml | 14 ++++----- 16 files changed, 117 insertions(+), 128 deletions(-) diff --git a/.github/workflows/coverage.yml b/.github/workflows/coverage.yml index 173363ec17..677761b0fa 100644 --- a/.github/workflows/coverage.yml +++ b/.github/workflows/coverage.yml @@ -7,19 +7,19 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build: runs-on: ubuntu-latest steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: lscpu diff --git a/.github/workflows/ios.yml b/.github/workflows/ios.yml index c8e0432fd3..eb3c8f95c6 100644 --- a/.github/workflows/ios.yml +++ b/.github/workflows/ios.yml @@ -7,6 +7,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-ios: runs-on: ${{ matrix.os }} @@ -16,14 +22,8 @@ jobs: os: [macos-11] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: | diff --git a/.github/workflows/macos-ustk.yml b/.github/workflows/macos-ustk.yml index 120d6211e2..266e8c3baf 100644 --- a/.github/workflows/macos-ustk.yml +++ b/.github/workflows/macos-ustk.yml @@ -7,6 +7,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-macos: runs-on: ${{ matrix.os }} @@ -16,14 +22,8 @@ jobs: os: [macos-12] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: | diff --git a/.github/workflows/macos.yml b/.github/workflows/macos.yml index 4427219ff7..7bd441dbbe 100644 --- a/.github/workflows/macos.yml +++ b/.github/workflows/macos.yml @@ -7,6 +7,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-macos: runs-on: ${{ matrix.os }} @@ -16,14 +22,8 @@ jobs: os: [macos-12, macos-13] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: | diff --git a/.github/workflows/other-arch-isolated.yml b/.github/workflows/other-arch-isolated.yml index 71d9e8ed55..e57b2b235e 100644 --- a/.github/workflows/other-arch-isolated.yml +++ b/.github/workflows/other-arch-isolated.yml @@ -8,6 +8,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-other-architectures: # The host should always be linux @@ -40,14 +46,8 @@ jobs: endianness: (Big Endian) steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Run on arch uses: uraimo/run-on-arch-action@v2.2.1 diff --git a/.github/workflows/other-arch.yml b/.github/workflows/other-arch.yml index 2818fda11a..902a514e86 100644 --- a/.github/workflows/other-arch.yml +++ b/.github/workflows/other-arch.yml @@ -8,6 +8,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-other-architectures: # The host should always be linux @@ -38,14 +44,8 @@ jobs: endianness: (Big Endian) steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Run on arch uses: uraimo/run-on-arch-action@v2.1.1 diff --git a/.github/workflows/ubuntu-3rdparty.yml b/.github/workflows/ubuntu-3rdparty.yml index c500260066..a0950d6946 100644 --- a/.github/workflows/ubuntu-3rdparty.yml +++ b/.github/workflows/ubuntu-3rdparty.yml @@ -7,6 +7,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-ubuntu-dep-apt: runs-on: ${{ matrix.os }} @@ -17,14 +23,8 @@ jobs: compiler: [ {CC: /usr/bin/gcc-10, CXX: /usr/bin/g++-10}, {CC: /usr/bin/clang, CXX: /usr/bin/clang++} ] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: lscpu diff --git a/.github/workflows/ubuntu-contrib.yml b/.github/workflows/ubuntu-contrib.yml index 7a417e34d1..f75e2b7c4d 100644 --- a/.github/workflows/ubuntu-contrib.yml +++ b/.github/workflows/ubuntu-contrib.yml @@ -7,6 +7,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-ubuntu-dep-apt: runs-on: ${{ matrix.os }} @@ -17,14 +23,8 @@ jobs: compiler: [ {CC: /usr/bin/gcc-10, CXX: /usr/bin/g++-10}, {CC: /usr/bin/clang, CXX: /usr/bin/clang++} ] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: lscpu diff --git a/.github/workflows/ubuntu-dep-apt.yml b/.github/workflows/ubuntu-dep-apt.yml index bb77160c2c..79a78890ff 100644 --- a/.github/workflows/ubuntu-dep-apt.yml +++ b/.github/workflows/ubuntu-dep-apt.yml @@ -7,6 +7,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-ubuntu-dep-apt: runs-on: ${{ matrix.os }} @@ -18,14 +24,8 @@ jobs: standard: [ 11, 14, 17 ] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: lscpu diff --git a/.github/workflows/ubuntu-dep-src.yml b/.github/workflows/ubuntu-dep-src.yml index af526068c8..aa382ffd69 100644 --- a/.github/workflows/ubuntu-dep-src.yml +++ b/.github/workflows/ubuntu-dep-src.yml @@ -7,6 +7,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-ubuntu-dep-src: runs-on: ${{ matrix.os }} @@ -16,14 +22,8 @@ jobs: os: [ubuntu-20.04, ubuntu-22.04] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: lscpu diff --git a/.github/workflows/ubuntu-isolated.yml b/.github/workflows/ubuntu-isolated.yml index a275b6080e..d3aeafd37e 100644 --- a/.github/workflows/ubuntu-isolated.yml +++ b/.github/workflows/ubuntu-isolated.yml @@ -8,6 +8,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-ubuntu-dep-apt: runs-on: ${{ matrix.os }} @@ -19,32 +25,14 @@ jobs: standard: [ 17 ] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - # Remove some packages to emulate the ROS2 Jenkins environment - # X11: https://raspberrypi.stackexchange.com/a/92334 - # Java: https://askubuntu.com/a/185531 - name: Remove packages + # Install OpenMP and turn-off some dependencies (below) to try to have a similar env compared to the ROS buildbot + - name: Install OpenMP run: | + sudo apt-get update sudo apt-get install libomp-dev - sudo apt purge --auto-remove 'x11-*' - java -version - sudo dpkg --list | grep -i jdk - sudo dpkg --list | grep -i java - sudo apt-get purge --auto-remove openjdk* - sudo apt-get purge --auto-remove icedtea-* openjdk-* - sudo dpkg --list | grep -i jdk - sudo dpkg --list | grep -i java - sudo apt purge --auto-remove 'libjpeg*' - sudo apt purge --auto-remove 'libpng*' - sudo apt purge --auto-remove 'libxml*' - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: lscpu @@ -66,7 +54,8 @@ jobs: echo "CXX: $CXX" echo "Standard: $CXX_STANDARD" cmake .. -DCMAKE_C_COMPILER="${CC}" -DCMAKE_CXX_COMPILER="${CXX}" -DCMAKE_BUILD_TYPE=Release \ - -DCMAKE_INSTALL_PREFIX=/tmp/usr/local -DCMAKE_VERBOSE_MAKEFILE=ON -DUSE_CXX_STANDARD=$CXX_STANDARD + -DCMAKE_INSTALL_PREFIX=/tmp/usr/local -DCMAKE_VERBOSE_MAKEFILE=ON -DUSE_CXX_STANDARD=$CXX_STANDARD \ + -DUSE_JPEG=OFF -DUSE_PNG=OFF -DUSE_X11=OFF -DUSE_XML2=OFF cat ViSP-third-party.txt - name: Compile diff --git a/.github/workflows/ubuntu-sanitizers.yml b/.github/workflows/ubuntu-sanitizers.yml index 46bc99623a..9894441bac 100644 --- a/.github/workflows/ubuntu-sanitizers.yml +++ b/.github/workflows/ubuntu-sanitizers.yml @@ -9,6 +9,12 @@ on: # every Sunday at 2 am - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-ubuntu-sanitizers: runs-on: ubuntu-latest @@ -18,14 +24,8 @@ jobs: flags: ["-fsanitize=address", "-fsanitize=leak", "-fsanitize=thread", "-fsanitize=undefined"] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: lscpu diff --git a/.github/workflows/ubuntu-ustk.yml b/.github/workflows/ubuntu-ustk.yml index fab02f8d6b..6c63dd55db 100644 --- a/.github/workflows/ubuntu-ustk.yml +++ b/.github/workflows/ubuntu-ustk.yml @@ -7,6 +7,12 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-ubuntu-dep-apt: runs-on: ${{ matrix.os }} @@ -16,14 +22,8 @@ jobs: os: [ubuntu-20.04, ubuntu-22.04] steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: lscpu diff --git a/.github/workflows/valgrind.yml b/.github/workflows/valgrind.yml index 6095eb2034..3f77bb5762 100644 --- a/.github/workflows/valgrind.yml +++ b/.github/workflows/valgrind.yml @@ -7,19 +7,19 @@ on: schedule: - cron: '0 2 * * SUN' +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build-ubuntu-valgrind: runs-on: ubuntu-latest steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Print system information run: lscpu diff --git a/.github/workflows/windows-clang.yaml b/.github/workflows/windows-clang.yaml index 7868044bf9..c6302a15b2 100644 --- a/.github/workflows/windows-clang.yaml +++ b/.github/workflows/windows-clang.yaml @@ -3,6 +3,12 @@ on: pull_request: push: +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build: runs-on: ${{ matrix.os }} @@ -20,14 +26,8 @@ jobs: compiler: clang-cl steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Display the workspace path working-directory: ${{ github.workspace }} diff --git a/.github/workflows/windows-msvc.yaml b/.github/workflows/windows-msvc.yaml index 4a3b846ce3..33717516aa 100644 --- a/.github/workflows/windows-msvc.yaml +++ b/.github/workflows/windows-msvc.yaml @@ -3,6 +3,12 @@ on: pull_request: push: +# https://stackoverflow.com/questions/66335225/how-to-cancel-previous-runs-in-the-pr-when-you-push-new-commitsupdate-the-curre#comment133398800_72408109 +# https://docs.github.com/en/actions/using-workflows/workflow-syntax-for-github-actions#concurrency +concurrency: + group: ${{ github.workflow }}-${{ github.ref || github.run_id }} + cancel-in-progress: true + jobs: build: runs-on: ${{ matrix.os }} @@ -19,14 +25,8 @@ jobs: os: windows-2019 steps: - # https://github.com/marketplace/actions/cancel-workflow-action - - name: Cancel Previous Runs - uses: styfle/cancel-workflow-action@0.9.1 - with: - access_token: ${{ github.token }} - - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Display the workspace path working-directory: ${{ github.workspace }} From cede9f54afccc1aaf6a6fbfcca2b5b2a2268b509 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Fri, 9 Feb 2024 07:42:49 +0100 Subject: [PATCH 038/164] Disable GSL and java when isolated ci --- .github/workflows/other-arch-isolated.yml | 5 +++-- .github/workflows/ubuntu-isolated.yml | 4 ++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/.github/workflows/other-arch-isolated.yml b/.github/workflows/other-arch-isolated.yml index e57b2b235e..868bfebb3d 100644 --- a/.github/workflows/other-arch-isolated.yml +++ b/.github/workflows/other-arch-isolated.yml @@ -17,7 +17,7 @@ concurrency: jobs: build-other-architectures: # The host should always be linux - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 name: Build on ${{ matrix.distro }} ${{ matrix.arch }} ${{ matrix.endianness }} # Run steps on a matrix of different arch/distro combinations @@ -65,7 +65,8 @@ jobs: pwd mkdir build && cd build - cmake .. -DBUILD_DEMOS=OFF -DBUILD_EXAMPLES=OFF -DBUILD_TUTORIALS=OFF -DBUILD_JAVA=OFF -DBUILD_MODULE_visp_java=OFF -DBUILD_MODULE_visp_java_binding=OFF -DUSE_CXX_STANDARD=17 + cmake .. -DBUILD_DEMOS=OFF -DBUILD_EXAMPLES=OFF -DBUILD_TUTORIALS=OFF -DBUILD_JAVA=OFF \ + -DUSE_JPEG=OFF -DUSE_PNG=OFF -DUSE_X11=OFF -DUSE_XML2=OFF -DBUILD_JAVA=OFF -DUSE_BLAS/LAPACK=OFF cat ViSP-third-party.txt make -j$(nproc) diff --git a/.github/workflows/ubuntu-isolated.yml b/.github/workflows/ubuntu-isolated.yml index d3aeafd37e..bd5684f0e5 100644 --- a/.github/workflows/ubuntu-isolated.yml +++ b/.github/workflows/ubuntu-isolated.yml @@ -53,9 +53,9 @@ jobs: echo "CC: $CC" echo "CXX: $CXX" echo "Standard: $CXX_STANDARD" - cmake .. -DCMAKE_C_COMPILER="${CC}" -DCMAKE_CXX_COMPILER="${CXX}" -DCMAKE_BUILD_TYPE=Release \ + cmake .. -DCMAKE_C_COMPILER="${CC}" -DCMAKE_CXX_COMPILER="${CXX}" \ -DCMAKE_INSTALL_PREFIX=/tmp/usr/local -DCMAKE_VERBOSE_MAKEFILE=ON -DUSE_CXX_STANDARD=$CXX_STANDARD \ - -DUSE_JPEG=OFF -DUSE_PNG=OFF -DUSE_X11=OFF -DUSE_XML2=OFF + -DUSE_JPEG=OFF -DUSE_PNG=OFF -DUSE_X11=OFF -DUSE_XML2=OFF -DBUILD_JAVA=OFF -DUSE_BLAS/LAPACK=OFF cat ViSP-third-party.txt - name: Compile From cb7e32f2cfd63bb83c879db8943bb6dcd0c34090 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 12 Feb 2024 15:14:44 +0100 Subject: [PATCH 039/164] remove using namespace std that clashed with MSVC byte declaration, cleanup log error in python bind gen --- modules/python/generator/visp_python_bindgen/header_utils.py | 1 - modules/robot/include/visp3/robot/vpRobotPololuPtu.h | 1 - 2 files changed, 2 deletions(-) diff --git a/modules/python/generator/visp_python_bindgen/header_utils.py b/modules/python/generator/visp_python_bindgen/header_utils.py index 7ee2c26ef6..d81c7d5051 100644 --- a/modules/python/generator/visp_python_bindgen/header_utils.py +++ b/modules/python/generator/visp_python_bindgen/header_utils.py @@ -92,7 +92,6 @@ def add_level(result: List['HeaderFile'], remainder: List['HeaderFile'], depende class HeaderEnvironment(): def __init__(self, data: ParsedData): self.mapping: Dict[str, str] = self.build_naive_mapping(data.namespace, {}) - logging.debug('Mapping = ', self.mapping) # Step 2: resolve enumeration names that are possibly hidden behind typedefs from visp_python_bindgen.enum_binding import resolve_enums_and_typedefs enum_reprs, _ = resolve_enums_and_typedefs(data.namespace, self.mapping) diff --git a/modules/robot/include/visp3/robot/vpRobotPololuPtu.h b/modules/robot/include/visp3/robot/vpRobotPololuPtu.h index aacac886f3..4cab3c52ce 100644 --- a/modules/robot/include/visp3/robot/vpRobotPololuPtu.h +++ b/modules/robot/include/visp3/robot/vpRobotPololuPtu.h @@ -41,7 +41,6 @@ #include #include -using namespace std; /*! * \class vpRobotPololuPtu From d6259c3d9f016145e80688ac1eb25edc5ab9dbfc Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 12 Feb 2024 15:34:12 +0100 Subject: [PATCH 040/164] remove using json=nlohmann::json from header files to avoid pollution --- .../core/include/visp3/core/vpCannyEdgeDetection.h | 7 +++---- modules/core/src/image/vpCannyEdgeDetection.cpp | 3 +++ .../include/visp3/detection/vpDetectorDNNOpenCV.h | 13 ++++++------- modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp | 3 +++ .../include/visp3/imgproc/vpCircleHoughTransform.h | 14 ++++++++------ modules/imgproc/src/vpCircleHoughTransform.cpp | 2 ++ 6 files changed, 25 insertions(+), 17 deletions(-) diff --git a/modules/core/include/visp3/core/vpCannyEdgeDetection.h b/modules/core/include/visp3/core/vpCannyEdgeDetection.h index cae0d4e109..b2548e5303 100644 --- a/modules/core/include/visp3/core/vpCannyEdgeDetection.h +++ b/modules/core/include/visp3/core/vpCannyEdgeDetection.h @@ -43,7 +43,6 @@ // 3rd parties include #ifdef VISP_HAVE_NLOHMANN_JSON #include -using json = nlohmann::json; //! json namespace shortcut #endif class VISP_EXPORT vpCannyEdgeDetection @@ -213,7 +212,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 json &j, vpCannyEdgeDetection &detector) + friend inline void from_json(const nlohmann::json &j, vpCannyEdgeDetection &detector) { std::string filteringAndGradientName = vpImageFilter::vpCannyFilteringAndGradientTypeToString(detector.m_filteringAndGradientType); filteringAndGradientName = j.value("filteringAndGradientType", filteringAndGradientName); @@ -233,10 +232,10 @@ 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(json &j, const vpCannyEdgeDetection &detector) + friend inline void to_json(nlohmann::json &j, const vpCannyEdgeDetection &detector) { std::string filteringAndGradientName = vpImageFilter::vpCannyFilteringAndGradientTypeToString(detector.m_filteringAndGradientType); - j = json { + j = nlohmann::json { {"filteringAndGradientType", filteringAndGradientName}, {"gaussianSize", detector.m_gaussianKernelSize}, {"gaussianStdev", detector.m_gaussianStdev}, diff --git a/modules/core/src/image/vpCannyEdgeDetection.cpp b/modules/core/src/image/vpCannyEdgeDetection.cpp index 3241678ad2..22758f9439 100644 --- a/modules/core/src/image/vpCannyEdgeDetection.cpp +++ b/modules/core/src/image/vpCannyEdgeDetection.cpp @@ -91,6 +91,9 @@ vpCannyEdgeDetection::vpCannyEdgeDetection(const int &gaussianKernelSize, const } #ifdef VISP_HAVE_NLOHMANN_JSON + +using json = nlohmann::json; + vpCannyEdgeDetection::vpCannyEdgeDetection(const std::string &jsonPath) { initFromJSON(jsonPath); diff --git a/modules/detection/include/visp3/detection/vpDetectorDNNOpenCV.h b/modules/detection/include/visp3/detection/vpDetectorDNNOpenCV.h index 87606ba1cf..fa20745bef 100644 --- a/modules/detection/include/visp3/detection/vpDetectorDNNOpenCV.h +++ b/modules/detection/include/visp3/detection/vpDetectorDNNOpenCV.h @@ -54,7 +54,6 @@ #include #ifdef VISP_HAVE_NLOHMANN_JSON #include -using json = nlohmann::json; //! json namespace shortcut #endif /*! @@ -201,7 +200,7 @@ class VISP_EXPORT vpDetectorDNNOpenCV * \param j The JSON object, resulting from the parsing of a JSON file. * \param config The configuration of the network, that will be initialized from the JSON data. */ - friend inline void from_json(const json &j, NetConfig &config) + friend inline void from_json(const nlohmann::json &j, NetConfig &config) { config.m_confThreshold = j.value("confidenceThreshold", config.m_confThreshold); if (config.m_confThreshold <= 0) { @@ -241,11 +240,11 @@ class VISP_EXPORT vpDetectorDNNOpenCV * \param j A JSON parser object. * \param config The vpDetectorDNNOpenCV::NetConfig that must be parsed into JSON format. */ - friend inline void to_json(json &j, const NetConfig &config) + friend inline void to_json(nlohmann::json &j, const NetConfig &config) { std::pair resolution = { config.m_inputSize.width, config.m_inputSize.height }; std::vector v_mean = { config.m_mean[0], config.m_mean[1], config.m_mean[2] }; - j = json { + j = nlohmann::json { {"confidenceThreshold", config.m_confThreshold } , {"nmsThreshold" , config.m_nmsThreshold } , {"filterSizeRatio" , config.m_filterSizeRatio} , @@ -515,7 +514,7 @@ class VISP_EXPORT vpDetectorDNNOpenCV * \param j The JSON object, resulting from the parsing of a JSON file. * \param network The network, that will be initialized from the JSON data. */ - friend inline void from_json(const json &j, vpDetectorDNNOpenCV &network) + friend inline void from_json(const nlohmann::json &j, vpDetectorDNNOpenCV &network) { network.m_netConfig = j.value("networkSettings", network.m_netConfig); } @@ -526,9 +525,9 @@ class VISP_EXPORT vpDetectorDNNOpenCV * \param j The JSON parser. * \param network The network we want to parse the configuration. */ - friend inline void to_json(json &j, const vpDetectorDNNOpenCV &network) + friend inline void to_json(nlohmann::json &j, const vpDetectorDNNOpenCV &network) { - j = json { + j = nlohmann::json { {"networkSettings", network.m_netConfig} }; } diff --git a/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp b/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp index f8babbc1f4..3bbddd3d82 100644 --- a/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp +++ b/modules/detection/src/dnn/vpDetectorDNNOpenCV.cpp @@ -170,6 +170,9 @@ vpDetectorDNNOpenCV::vpDetectorDNNOpenCV(const NetConfig &config, const DNNResul } #ifdef VISP_HAVE_NLOHMANN_JSON + +using json = nlohmann::json; + /** * \brief Construct a new vpDetectorDNNOpenCV object from a JSON file and a potential parsing method. * diff --git a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h index e95d14ee0a..7000b508a7 100644 --- a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h +++ b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h @@ -45,7 +45,6 @@ // 3rd parties inclue #ifdef VISP_HAVE_NLOHMANN_JSON #include -using json = nlohmann::json; #endif #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) @@ -496,6 +495,8 @@ class VISP_EXPORT vpCircleHoughTransform */ inline static vpCircleHoughTransformParameters createFromJSON(const std::string &jsonFile) { + using json = nlohmann::json; + std::ifstream file(jsonFile); if (!file.good()) { std::stringstream ss; @@ -528,6 +529,7 @@ class VISP_EXPORT vpCircleHoughTransform */ inline void saveConfigurationInJSON(const std::string &jsonPath) const { + using json = nlohmann::json; std::ofstream file(jsonPath); const json j = *this; file << j.dump(4); @@ -541,7 +543,7 @@ class VISP_EXPORT vpCircleHoughTransform * \param[in] j : The JSON object, resulting from the parsing of a JSON file. * \param[out] params : The circle Hough transform parameters that will be initialized from the JSON data. */ - friend inline void from_json(const json &j, vpCircleHoughTransformParameters ¶ms) + friend inline void from_json(const nlohmann::json &j, vpCircleHoughTransformParameters ¶ms) { std::string filteringAndGradientName = vpImageFilter::vpCannyFilteringAndGradientTypeToString(params.m_filteringAndGradientType); filteringAndGradientName = j.value("filteringAndGradientType", filteringAndGradientName); @@ -619,11 +621,11 @@ class VISP_EXPORT vpCircleHoughTransform * \param[out] j : A JSON parser object. * \param[in] params : The circle Hough transform parameters that will be serialized in the json object. */ - friend inline void to_json(json &j, const vpCircleHoughTransformParameters ¶ms) + friend inline void to_json(nlohmann::json &j, const vpCircleHoughTransformParameters ¶ms) { std::pair radiusLimits = { params.m_minRadius, params.m_maxRadius }; - j = json { + j = nlohmann::json { {"filteringAndGradientType", vpImageFilter::vpCannyFilteringAndGradientTypeToString(params.m_filteringAndGradientType)}, {"gaussianKernelSize", params.m_gaussianKernelSize}, {"gaussianStdev", params.m_gaussianStdev}, @@ -760,7 +762,7 @@ class VISP_EXPORT vpCircleHoughTransform * \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 json &j, vpCircleHoughTransform &detector) + friend inline void from_json(const nlohmann::json &j, vpCircleHoughTransform &detector) { detector.m_algoParams = j; } @@ -771,7 +773,7 @@ class VISP_EXPORT vpCircleHoughTransform * \param[out] j A JSON parser object. * \param[in] detector The vpCircleHoughTransform that must be parsed into JSON format. */ - friend inline void to_json(json &j, const vpCircleHoughTransform &detector) + friend inline void to_json(nlohmann::json &j, const vpCircleHoughTransform &detector) { j = detector.m_algoParams; } diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index 7555905048..a23209a305 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -123,6 +123,8 @@ vpCircleHoughTransform::~vpCircleHoughTransform() { } #ifdef VISP_HAVE_NLOHMANN_JSON +using json = nlohmann::json; + vpCircleHoughTransform::vpCircleHoughTransform(const std::string &jsonPath) { initFromJSON(jsonPath); From e5af3ccda61272cf0de51fa94f3fb1a4a02acf5a Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 13 Feb 2024 15:30:23 +0100 Subject: [PATCH 041/164] Add check for cxx standard, add VISP_EXPORT macro in front of generated code --- CMakeLists.txt | 13 ++++++++++--- modules/python/bindings/include/blob.hpp | 4 ++-- modules/python/bindings/include/core/arrays.hpp | 15 ++++++++------- .../bindings/include/core/image_conversions.hpp | 4 ++-- modules/python/bindings/include/core/images.hpp | 8 ++++---- .../python/bindings/include/core/pixel_meter.hpp | 4 ++-- modules/python/bindings/include/mbt.hpp | 3 ++- .../generator/visp_python_bindgen/generator.py | 3 ++- .../generator/visp_python_bindgen/submodule.py | 2 +- 9 files changed, 33 insertions(+), 23 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f331a1d0db..9347533583 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -329,6 +329,14 @@ if(PYTHON3_VERSION_STRING VERSION_LESS ${PYTHON3_MINIMUM_VERSION_PYTHON_BINDINGS else() set(PYTHON3_NOT_OK_FOR_BINDINGS FALSE) endif() +if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_17) + set(CXX_STANDARD_NOT_OK_FOR_BINDINGS TRUE) + message(STATUS "Required C++ standard is C++17, but you have ${VISP_CXX_STANDARD}") +else() + set(CXX_STANDARD_NOT_OK_FOR_BINDINGS FALSE) +endif() + + # Forbid system Python if(DEFINED ENV{VIRTUAL_ENV} OR DEFINED ENV{CONDA_PREFIX}) @@ -493,7 +501,7 @@ VP_OPTION(BUILD_ANDROID_EXAMPLES "" "" "Build examples for Android platform" VP_OPTION(INSTALL_ANDROID_EXAMPLES "" "" "Install Android examples" "" OFF IF ANDROID ) # Build python bindings as an option -VP_OPTION(BUILD_PYTHON_BINDINGS "" "" "Build Python bindings" "" ON IF (PYTHON3INTERP_FOUND AND USE_PYBIND11 AND NOT CMAKE_NOT_OK_FOR_BINDINGS AND NOT VISP_PYTHON_IS_SYSTEM_WIDE AND NOT PYTHON3_NOT_OK_FOR_BINDINGS) ) +VP_OPTION(BUILD_PYTHON_BINDINGS "" "" "Build Python bindings" "" ON IF (PYTHON3INTERP_FOUND AND USE_PYBIND11 AND NOT CMAKE_NOT_OK_FOR_BINDINGS AND NOT VISP_PYTHON_IS_SYSTEM_WIDE AND NOT PYTHON3_NOT_OK_FOR_BINDINGS AND NOT CXX_STANDARD_NOT_OK_FOR_BINDINGS) ) VP_OPTION(BUILD_PYTHON_BINDINGS_DOC "" "" "Build the documentation for the Python bindings" "" ON IF BUILD_PYTHON_BINDINGS ) @@ -1655,8 +1663,7 @@ else() status(" Python in Virtual environment or conda:" VISP_PYTHON_IS_SYSTEM_WIDE THEN "failed" ELSE "ok") status(" Pybind11 found:" USE_PYBIND11 THEN "ok" ELSE "failed") status(" CMake > ${CMAKE_MINIMUM_VERSION_PYTHON_BINDINGS}:" CMAKE_NOT_OK_FOR_BINDINGS THEN "failed (${CMAKE_VERSION})" ELSE "ok (${CMAKE_VERSION})") - - + status(" C++ standard > ${VISP_CXX_STANDARD_17}:" CXX_STANDARD_NOT_OK_FOR_BINDINGS THEN "failed (${VISP_CXX_STANDARD})" ELSE "ok (${VISP_CXX_STANDARD})") endif() diff --git a/modules/python/bindings/include/blob.hpp b/modules/python/bindings/include/blob.hpp index 5dd634a473..0cd2b3756f 100644 --- a/modules/python/bindings/include/blob.hpp +++ b/modules/python/bindings/include/blob.hpp @@ -37,13 +37,13 @@ #include #include #include - +#include #include #include namespace py = pybind11; -void bindings_vpDot2(py::class_ &pyDot2) +VISP_EXPORT void bindings_vpDot2(py::class_ &pyDot2) { pyDot2.def_static("defineDots", [](std::vector &dots, const std::string &dotFile, diff --git a/modules/python/bindings/include/core/arrays.hpp b/modules/python/bindings/include/core/arrays.hpp index 5a92bfae62..5a7271301f 100644 --- a/modules/python/bindings/include/core/arrays.hpp +++ b/modules/python/bindings/include/core/arrays.hpp @@ -40,6 +40,7 @@ #include #include +#include #include #include #include @@ -173,7 +174,7 @@ const char *numpy_fn_doc_nonwritable = R"doc( )doc"; template -void bindings_vpArray2D(py::class_> &pyArray2D) +VISP_EXPORT void bindings_vpArray2D(py::class_> &pyArray2D) { pyArray2D.def_buffer(&get_buffer_info); @@ -197,7 +198,7 @@ Construct a 2D ViSP array by **copying** a 2D numpy array. define_get_item_2d_array>, vpArray2D, T>(pyArray2D); } -void bindings_vpMatrix(py::class_> &pyMatrix) +VISP_EXPORT void bindings_vpMatrix(py::class_> &pyMatrix) { pyMatrix.def_buffer(&get_buffer_info); @@ -222,7 +223,7 @@ Construct a matrix by **copying** a 2D numpy array. } -void bindings_vpRotationMatrix(py::class_> &pyRotationMatrix) +VISP_EXPORT void bindings_vpRotationMatrix(py::class_> &pyRotationMatrix) { pyRotationMatrix.def_buffer(&get_buffer_info); @@ -249,7 +250,7 @@ If it is not a rotation matrix, an exception will be raised. define_get_item_2d_array>, vpRotationMatrix, double>(pyRotationMatrix); } -void bindings_vpHomogeneousMatrix(py::class_> &pyHomogeneousMatrix) +VISP_EXPORT void bindings_vpHomogeneousMatrix(py::class_> &pyHomogeneousMatrix) { pyHomogeneousMatrix.def_buffer(get_buffer_info); pyHomogeneousMatrix.def("numpy", [](vpHomogeneousMatrix &self) -> np_array_cf { @@ -278,7 +279,7 @@ If it is not a homogeneous matrix, an exception will be raised. -void bindings_vpTranslationVector(py::class_> &pyTranslationVector) +VISP_EXPORT void bindings_vpTranslationVector(py::class_> &pyTranslationVector) { pyTranslationVector.def_buffer(&get_buffer_info); @@ -303,7 +304,7 @@ Construct a Translation vector by **copying** a 1D numpy array of size 3. } -void bindings_vpColVector(py::class_> &pyColVector) +VISP_EXPORT void bindings_vpColVector(py::class_> &pyColVector) { pyColVector.def_buffer(&get_buffer_info); @@ -327,7 +328,7 @@ Construct a column vector by **copying** a 1D numpy array. } -void bindings_vpRowVector(py::class_> &pyRowVector) +VISP_EXPORT void bindings_vpRowVector(py::class_> &pyRowVector) { pyRowVector.def_buffer(&get_buffer_info); pyRowVector.def("numpy", [](vpRowVector &self) -> np_array_cf { diff --git a/modules/python/bindings/include/core/image_conversions.hpp b/modules/python/bindings/include/core/image_conversions.hpp index 68099d9d15..33d334f596 100644 --- a/modules/python/bindings/include/core/image_conversions.hpp +++ b/modules/python/bindings/include/core/image_conversions.hpp @@ -37,7 +37,7 @@ #include #include #include - +#include #include namespace @@ -177,7 +177,7 @@ unsigned size411(unsigned h, unsigned w) -void bindings_vpImageConvert(py::class_ &pyImageConvert) +VISP_EXPORT void bindings_vpImageConvert(py::class_ &pyImageConvert) { // Simple conversions where the size input is a single argument { diff --git a/modules/python/bindings/include/core/images.hpp b/modules/python/bindings/include/core/images.hpp index e9932d712c..c8ccf4b7c6 100644 --- a/modules/python/bindings/include/core/images.hpp +++ b/modules/python/bindings/include/core/images.hpp @@ -33,7 +33,7 @@ #ifndef VISP_PYTHON_CORE_IMAGES_HPP #define VISP_PYTHON_CORE_IMAGES_HPP - +#include #include #include #include @@ -97,7 +97,7 @@ void define_get_item_2d_image(py::class_> &pyClass) * vpImage */ template -typename std::enable_if::value, void>::type +VISP_EXPORT typename std::enable_if::value, void>::type bindings_vpImage(py::class_> &pyImage) { pyImage.def_buffer([](vpImage &image) -> py::buffer_info { @@ -137,7 +137,7 @@ Construct an image by **copying** a 2D numpy array. } template -typename std::enable_if::value, void>::type +VISP_EXPORT typename std::enable_if::value, void>::type bindings_vpImage(py::class_> &pyImage) { using NpRep = unsigned char; @@ -181,7 +181,7 @@ where the 4 denotes the red, green, blue and alpha components of the image. } template -typename std::enable_if::value, void>::type +VISP_EXPORT typename std::enable_if::value, void>::type bindings_vpImage(py::class_> &pyImage) { using NpRep = float; diff --git a/modules/python/bindings/include/core/pixel_meter.hpp b/modules/python/bindings/include/core/pixel_meter.hpp index 28ec7aba09..f28eb3680a 100644 --- a/modules/python/bindings/include/core/pixel_meter.hpp +++ b/modules/python/bindings/include/core/pixel_meter.hpp @@ -43,7 +43,7 @@ #include "core/utils.hpp" -void bindings_vpPixelMeterConversion(py::class_ &pyPM) +VISP_EXPORT void bindings_vpPixelMeterConversion(py::class_ &pyPM) { pyPM.def_static("convertPoints", [](const vpCameraParameters &cam, const py::array_t &us, const py::array_t &vs) { py::buffer_info bufu = us.request(), bufv = vs.request(); @@ -106,7 +106,7 @@ Example usage: )doc", py::arg("cam"), py::arg("us"), py::arg("vs")); } -void bindings_vpMeterPixelConversion(py::class_ &pyMP) +VISP_EXPORT void bindings_vpMeterPixelConversion(py::class_ &pyMP) { pyMP.def_static("convertPoints", [](const vpCameraParameters &cam, const py::array_t &xs, const py::array_t &ys) { py::buffer_info bufx = xs.request(), bufy = ys.request(); diff --git a/modules/python/bindings/include/mbt.hpp b/modules/python/bindings/include/mbt.hpp index ab4e2cffd6..5f824e42df 100644 --- a/modules/python/bindings/include/mbt.hpp +++ b/modules/python/bindings/include/mbt.hpp @@ -37,11 +37,12 @@ #include #include #include +#include #include namespace py = pybind11; -void bindings_vpMbGenericTracker(py::class_ &pyMbGenericTracker) +VISP_EXPORT void bindings_vpMbGenericTracker(py::class_ &pyMbGenericTracker) { pyMbGenericTracker.def("track", [](vpMbGenericTracker &self, std::map *> &mapOfImages, std::map> &mapOfPointClouds) { diff --git a/modules/python/generator/visp_python_bindgen/generator.py b/modules/python/generator/visp_python_bindgen/generator.py index 27bb5bb41c..60d5d9e462 100644 --- a/modules/python/generator/visp_python_bindgen/generator.py +++ b/modules/python/generator/visp_python_bindgen/generator.py @@ -75,6 +75,7 @@ def main_str(submodule_fn_declarations, submodule_fn_calls): ''' return f''' //#define PYBIND11_DETAILED_ERROR_MESSAGES +#include #include namespace py = pybind11; {submodule_fn_declarations} @@ -142,7 +143,7 @@ def generate_module(generate_path: Path, config_path: Path) -> None: submodule_fn_calls = [] for submodule in submodules: name = submodule.generation_function_name() - submodule_fn_declarations.append(f'void {name}(py::module_&);') + submodule_fn_declarations.append(f'VISP_EXPORT void {name}(py::module_&);') submodule_fn_calls.append(f'{name}(m);') submodule_fn_declarations = '\n'.join(submodule_fn_declarations) diff --git a/modules/python/generator/visp_python_bindgen/submodule.py b/modules/python/generator/visp_python_bindgen/submodule.py index 05bcb42dbd..a14bca89b2 100644 --- a/modules/python/generator/visp_python_bindgen/submodule.py +++ b/modules/python/generator/visp_python_bindgen/submodule.py @@ -130,7 +130,7 @@ def generate(self) -> None: namespace py = pybind11; -void {self.generation_function_name()}(py::module_ &m) {{ +VISP_EXPORT void {self.generation_function_name()}(py::module_ &m) {{ py::options options; options.disable_enum_members_docstring(); From 5ea641c17492370b38d806b0983af73a2cc44a23 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Tue, 13 Feb 2024 18:16:09 +0100 Subject: [PATCH 042/164] Update instruction to build bindings for windows --- .../tutorial-install-python-bindings.dox | 21 ++++++++----------- 1 file changed, 9 insertions(+), 12 deletions(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 680b125af1..299ada62ea 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -238,10 +238,10 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: \subsection py_bindings_build_win_msvc17 How to build on Windows with Visual Studio 17 2022 -- Install Python3 using Microsoft Store and check its version +- Install latest Python3 version using Microsoft Store and check its version C:\> python3 --version - Python 3.12.1 + Python 3.12.2 - Install pip3 @@ -250,7 +250,7 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: - Check pip3 availability C:\> pip3 --version - pip 23.3.2 from C:\Users\User\AppData\Local\Packages\PythonSoftwareFoundation.Python3.12_...\LocalCache\local-apackages\Python312\site-packages\pip (python 3.12) + pip 24.0 from C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.12_3.12.752.0_x64__qbz5n2kfra8p0\Lib\site-packages\pip (python 3.12) - Install `pybind11` @@ -259,9 +259,9 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: Collecting pybind11 Downloading pybind11-2.11.1-py3-none-any.whl.metadata (9.5 kB) Downloading pybind11-2.11.1-py3-none-any.whl (227 kB) - ---------------------------------------- 227.7/227.7 kB 1.7 MB/s eta 0:00:00 + ---------------------------------------- 227.7/227.7 kB 2.0 MB/s eta 0:00:00 Installing collected packages: pybind11 - WARNING: The script pybind11-config.exe is installed in 'C:\Users\User\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\Scripts' which is not on PATH. + WARNING: The script pybind11-config.exe is installed in 'C:\Users\user\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\Scripts' which is not on PATH. Consider adding this directory to PATH or, if you prefer to suppress this warning, use --no-warn-script-location. Successfully installed pybind11-2.11.1 @@ -297,7 +297,7 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: C:\> cd $VISP_WS C:\> virtualenv venv - created virtual environment CPython3.12.1.final.0-64 in 350ms + created virtual environment CPython3.12.2.final.0-64 in 1175ms - These commands create a `venv/` directory in your project where all dependencies are installed. You need to activate it first though (in every `cmd` Command Prompt terminal instance where you are working on your project): @@ -305,15 +305,15 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: C:\> venv\Scripts\activate (venv) C:\> mkdir visp-build-vc17-bindings (venv) C:\> cd visp-build-vc17-bindings - (venv) C:\> cmake -G "Visual Studio 17 2022" -A "x64" -Dpybind11_DIR=C:\Users\User\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 ..\visp + (venv) C:\> cmake -G "Visual Studio 17 2022" -A "x64" -Dpybind11_DIR=C:\Users\%USERNAME%\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 ..\visp At this point in `ViSP-third-party.txt` file you should see something similar to: (venv) C:\> type ViSP-third-party.txt ... -- Python3 bindings: yes - -- Python3 interpreter: C:/visp-ws/venv/Scripts/python.exe (ver 3.12.1) - -- Pybind11: C:\Users\User\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 (2.11.1) + -- Python3 interpreter: C:/visp-ws/venv/Scripts/python.exe (ver 3.12.2) + -- Pybind11: C:\Users\%USERNAME%\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 (2.11.1) -- Package version: 3.6.1 -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi -- Generated input config: C:/visp-ws/visp-build-vc17-bindings/modules/python/cmake_config.json @@ -360,8 +360,6 @@ If you encounter a problem during the build, you may raise an issue on GitHub. T - the `src` folder: contains the generated binding code and the preprocessed headers as seen by the generation tool - The output of your terminal - - \subsubsection py_bindings_known_errors Known build errors When compiling or modifying the bindings, you may encounter errors. @@ -397,7 +395,6 @@ This may be due to macro definitions, which are not done by an actual compiler. Custom macro definitions are defined in an autogenerated file in the build folder: `modules/python/cmake_config.json`. To add a custom macro, you should modify the GenerateConfig.cmake file in the modules/python folder in the **source** directory of ViSP. - For instance, in the function declaration: \code{.cpp} static DWORD WINAPI launcher(LPVOID lpParam); From 3353f2ce6720b5744f15354b475afa0c96f11cb9 Mon Sep 17 00:00:00 2001 From: FELTON Samuel Date: Wed, 14 Feb 2024 12:34:52 +0100 Subject: [PATCH 043/164] remove unneeded visp_export --- modules/python/bindings/include/blob.hpp | 2 +- modules/python/bindings/include/core/arrays.hpp | 14 +++++++------- .../bindings/include/core/image_conversions.hpp | 2 +- modules/python/bindings/include/core/images.hpp | 6 +++--- .../python/bindings/include/core/pixel_meter.hpp | 4 ++-- modules/python/bindings/include/mbt.hpp | 2 +- .../generator/visp_python_bindgen/generator.py | 2 +- .../generator/visp_python_bindgen/submodule.py | 2 +- 8 files changed, 17 insertions(+), 17 deletions(-) diff --git a/modules/python/bindings/include/blob.hpp b/modules/python/bindings/include/blob.hpp index 0cd2b3756f..e64420faf4 100644 --- a/modules/python/bindings/include/blob.hpp +++ b/modules/python/bindings/include/blob.hpp @@ -43,7 +43,7 @@ namespace py = pybind11; -VISP_EXPORT void bindings_vpDot2(py::class_ &pyDot2) +void bindings_vpDot2(py::class_ &pyDot2) { pyDot2.def_static("defineDots", [](std::vector &dots, const std::string &dotFile, diff --git a/modules/python/bindings/include/core/arrays.hpp b/modules/python/bindings/include/core/arrays.hpp index 5a7271301f..cdb15b7588 100644 --- a/modules/python/bindings/include/core/arrays.hpp +++ b/modules/python/bindings/include/core/arrays.hpp @@ -174,7 +174,7 @@ const char *numpy_fn_doc_nonwritable = R"doc( )doc"; template -VISP_EXPORT void bindings_vpArray2D(py::class_> &pyArray2D) +void bindings_vpArray2D(py::class_> &pyArray2D) { pyArray2D.def_buffer(&get_buffer_info); @@ -198,7 +198,7 @@ Construct a 2D ViSP array by **copying** a 2D numpy array. define_get_item_2d_array>, vpArray2D, T>(pyArray2D); } -VISP_EXPORT void bindings_vpMatrix(py::class_> &pyMatrix) +void bindings_vpMatrix(py::class_> &pyMatrix) { pyMatrix.def_buffer(&get_buffer_info); @@ -223,7 +223,7 @@ Construct a matrix by **copying** a 2D numpy array. } -VISP_EXPORT void bindings_vpRotationMatrix(py::class_> &pyRotationMatrix) +void bindings_vpRotationMatrix(py::class_> &pyRotationMatrix) { pyRotationMatrix.def_buffer(&get_buffer_info); @@ -250,7 +250,7 @@ If it is not a rotation matrix, an exception will be raised. define_get_item_2d_array>, vpRotationMatrix, double>(pyRotationMatrix); } -VISP_EXPORT void bindings_vpHomogeneousMatrix(py::class_> &pyHomogeneousMatrix) +void bindings_vpHomogeneousMatrix(py::class_> &pyHomogeneousMatrix) { pyHomogeneousMatrix.def_buffer(get_buffer_info); pyHomogeneousMatrix.def("numpy", [](vpHomogeneousMatrix &self) -> np_array_cf { @@ -279,7 +279,7 @@ If it is not a homogeneous matrix, an exception will be raised. -VISP_EXPORT void bindings_vpTranslationVector(py::class_> &pyTranslationVector) +void bindings_vpTranslationVector(py::class_> &pyTranslationVector) { pyTranslationVector.def_buffer(&get_buffer_info); @@ -304,7 +304,7 @@ Construct a Translation vector by **copying** a 1D numpy array of size 3. } -VISP_EXPORT void bindings_vpColVector(py::class_> &pyColVector) +void bindings_vpColVector(py::class_> &pyColVector) { pyColVector.def_buffer(&get_buffer_info); @@ -328,7 +328,7 @@ Construct a column vector by **copying** a 1D numpy array. } -VISP_EXPORT void bindings_vpRowVector(py::class_> &pyRowVector) +void bindings_vpRowVector(py::class_> &pyRowVector) { pyRowVector.def_buffer(&get_buffer_info); pyRowVector.def("numpy", [](vpRowVector &self) -> np_array_cf { diff --git a/modules/python/bindings/include/core/image_conversions.hpp b/modules/python/bindings/include/core/image_conversions.hpp index 33d334f596..99d9e40a47 100644 --- a/modules/python/bindings/include/core/image_conversions.hpp +++ b/modules/python/bindings/include/core/image_conversions.hpp @@ -177,7 +177,7 @@ unsigned size411(unsigned h, unsigned w) -VISP_EXPORT void bindings_vpImageConvert(py::class_ &pyImageConvert) +void bindings_vpImageConvert(py::class_ &pyImageConvert) { // Simple conversions where the size input is a single argument { diff --git a/modules/python/bindings/include/core/images.hpp b/modules/python/bindings/include/core/images.hpp index c8ccf4b7c6..3303b341b0 100644 --- a/modules/python/bindings/include/core/images.hpp +++ b/modules/python/bindings/include/core/images.hpp @@ -97,7 +97,7 @@ void define_get_item_2d_image(py::class_> &pyClass) * vpImage */ template -VISP_EXPORT typename std::enable_if::value, void>::type +typename std::enable_if::value, void>::type bindings_vpImage(py::class_> &pyImage) { pyImage.def_buffer([](vpImage &image) -> py::buffer_info { @@ -137,7 +137,7 @@ Construct an image by **copying** a 2D numpy array. } template -VISP_EXPORT typename std::enable_if::value, void>::type +typename std::enable_if::value, void>::type bindings_vpImage(py::class_> &pyImage) { using NpRep = unsigned char; @@ -181,7 +181,7 @@ where the 4 denotes the red, green, blue and alpha components of the image. } template -VISP_EXPORT typename std::enable_if::value, void>::type +typename std::enable_if::value, void>::type bindings_vpImage(py::class_> &pyImage) { using NpRep = float; diff --git a/modules/python/bindings/include/core/pixel_meter.hpp b/modules/python/bindings/include/core/pixel_meter.hpp index f28eb3680a..28ec7aba09 100644 --- a/modules/python/bindings/include/core/pixel_meter.hpp +++ b/modules/python/bindings/include/core/pixel_meter.hpp @@ -43,7 +43,7 @@ #include "core/utils.hpp" -VISP_EXPORT void bindings_vpPixelMeterConversion(py::class_ &pyPM) +void bindings_vpPixelMeterConversion(py::class_ &pyPM) { pyPM.def_static("convertPoints", [](const vpCameraParameters &cam, const py::array_t &us, const py::array_t &vs) { py::buffer_info bufu = us.request(), bufv = vs.request(); @@ -106,7 +106,7 @@ Example usage: )doc", py::arg("cam"), py::arg("us"), py::arg("vs")); } -VISP_EXPORT void bindings_vpMeterPixelConversion(py::class_ &pyMP) +void bindings_vpMeterPixelConversion(py::class_ &pyMP) { pyMP.def_static("convertPoints", [](const vpCameraParameters &cam, const py::array_t &xs, const py::array_t &ys) { py::buffer_info bufx = xs.request(), bufy = ys.request(); diff --git a/modules/python/bindings/include/mbt.hpp b/modules/python/bindings/include/mbt.hpp index 5f824e42df..4ef94b65d4 100644 --- a/modules/python/bindings/include/mbt.hpp +++ b/modules/python/bindings/include/mbt.hpp @@ -42,7 +42,7 @@ namespace py = pybind11; -VISP_EXPORT void bindings_vpMbGenericTracker(py::class_ &pyMbGenericTracker) +void bindings_vpMbGenericTracker(py::class_ &pyMbGenericTracker) { pyMbGenericTracker.def("track", [](vpMbGenericTracker &self, std::map *> &mapOfImages, std::map> &mapOfPointClouds) { diff --git a/modules/python/generator/visp_python_bindgen/generator.py b/modules/python/generator/visp_python_bindgen/generator.py index 60d5d9e462..5b80634664 100644 --- a/modules/python/generator/visp_python_bindgen/generator.py +++ b/modules/python/generator/visp_python_bindgen/generator.py @@ -143,7 +143,7 @@ def generate_module(generate_path: Path, config_path: Path) -> None: submodule_fn_calls = [] for submodule in submodules: name = submodule.generation_function_name() - submodule_fn_declarations.append(f'VISP_EXPORT void {name}(py::module_&);') + submodule_fn_declarations.append(f'void {name}(py::module_&);') submodule_fn_calls.append(f'{name}(m);') submodule_fn_declarations = '\n'.join(submodule_fn_declarations) diff --git a/modules/python/generator/visp_python_bindgen/submodule.py b/modules/python/generator/visp_python_bindgen/submodule.py index a14bca89b2..05bcb42dbd 100644 --- a/modules/python/generator/visp_python_bindgen/submodule.py +++ b/modules/python/generator/visp_python_bindgen/submodule.py @@ -130,7 +130,7 @@ def generate(self) -> None: namespace py = pybind11; -VISP_EXPORT void {self.generation_function_name()}(py::module_ &m) {{ +void {self.generation_function_name()}(py::module_ &m) {{ py::options options; options.disable_enum_members_docstring(); From d536da2f00a8a94e4e43e27e3d2c2f5ff6d9a7ac Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 14 Feb 2024 17:25:55 +0100 Subject: [PATCH 044/164] Disable warning due to basisu_miniz.h --- modules/core/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/core/CMakeLists.txt b/modules/core/CMakeLists.txt index a8dd665d4d..8175cbf5ca 100644 --- a/modules/core/CMakeLists.txt +++ b/modules/core/CMakeLists.txt @@ -326,7 +326,7 @@ vp_set_source_file_compile_flag(src/tools/histogram/vpHistogram.cpp -Wno-strict- vp_set_source_file_compile_flag(src/image/vpFont.cpp -Wno-float-equal -Wno-strict-overflow) # To avoid warnings with basisu_miniz.h such as: # basisu_miniz.h:1184:9: warning: this ‘for’ clause does not guard... [-Wmisleading-indentation] -vp_set_source_file_compile_flag(src/tools/vpIoTools.cpp -Wno-misleading-indentation) +vp_set_source_file_compile_flag(src/tools/file/vpIoTools.cpp -Wno-misleading-indentation -Wno-strict-aliasing -Wno-strict-overflow) vp_set_source_file_compile_flag(src/munkres/vpMunkres.cpp /wd26812 /wd4244) vp_set_source_file_compile_flag(test/image/testImageBinarise.cpp -Wno-strict-overflow) vp_set_source_file_compile_flag(test/image/testImageOwnership.cpp -Wno-pessimizing-move) From 55d8b26153353debb91cb71de119c037c9130275 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 14 Feb 2024 17:26:27 +0100 Subject: [PATCH 045/164] Fix warnings detected by Fedora25 ci --- modules/core/src/image/vpImageCircle.cpp | 4 ++-- modules/imgproc/src/vpCircleHoughTransform.cpp | 2 +- modules/imgproc/src/vpContours.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/modules/core/src/image/vpImageCircle.cpp b/modules/core/src/image/vpImageCircle.cpp index 6d9ee96677..2bf69365e5 100644 --- a/modules/core/src/image/vpImageCircle.cpp +++ b/modules/core/src/image/vpImageCircle.cpp @@ -1111,7 +1111,7 @@ unsigned int vpImageCircle::computePixelsInMask(const vpImage &mask) const // dTheta <= 1/r sin(theta) && dTheta <= 1/r cos(theta) dthetaPos = std::min(dthetaCosPos, dthetaSinPos); } - else if (sin_theta == 0.f && cos_theta != 0.f) { + else if (vpMath::equal(sin_theta, 0.f) && (!vpMath::equal(cos_theta, 0.f))) { // dTheta = -1 / r cos(theta) || dTheta = 1 / r cos(theta) if (cos_theta > 0.f) { dthetaPos = dthetaCosNeg; @@ -1120,7 +1120,7 @@ unsigned int vpImageCircle::computePixelsInMask(const vpImage &mask) const dthetaPos = dthetaCosPos; } } - else if (sin_theta != 0.f && cos_theta == 0.f) { + else if ((!vpMath::equal(sin_theta, 0.f)) && vpMath::equal(cos_theta, 0.f)) { // dTheta = -1 / r sin(theta) || dTheta = 1 / r sin(theta) if (sin_theta > 0.f) { dthetaPos = dthetaSinNeg; diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index 19ae63040a..a30d1829f9 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -747,7 +747,7 @@ vpCircleHoughTransform::computeCenterCandidates() int left = -1; for (int x = 0; x < nbColsAccum; x++) { if ((centersAccum[y][x] >= m_algoParams.m_centerMinThresh) - && (centersAccum[y][x] == centerCandidatesMaxima[y][x]) + && (vpMath::equal(centersAccum[y][x], centerCandidatesMaxima[y][x])) && (centersAccum[y][x] > centersAccum[y][x + 1]) ) { if (left < 0) { diff --git a/modules/imgproc/src/vpContours.cpp b/modules/imgproc/src/vpContours.cpp index cefb7cdf92..1084cc45ff 100644 --- a/modules/imgproc/src/vpContours.cpp +++ b/modules/imgproc/src/vpContours.cpp @@ -227,7 +227,7 @@ bool isHoleBorderStart(const vpImage &I, unsigned int i, unsigned int j) void getContoursList(const vp::vpContour &root, int level, vp::vpContour &contour_list) { - if (level > 0) { + if (level > 0 && level < std::numeric_limits::max()) { vp::vpContour *contour_node = new vp::vpContour; contour_node->m_contourType = root.m_contourType; contour_node->m_points = root.m_points; From 26854a55bafdafd6f8caf1ead8983251f30fc68d Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 14 Feb 2024 17:27:57 +0100 Subject: [PATCH 046/164] Fix testGenericTracker-edge-scanline test on Fedora25 when scanline and Coin3D is enabled --- .../mbt/test/generic-with-dataset/testGenericTracker.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp index 0562bfde6d..0f549a9c85 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp @@ -364,7 +364,7 @@ bool run(const std::string &input_directory, bool opt_click_allowed, bool opt_di // Take the highest thresholds between all CI machines #ifdef VISP_HAVE_COIN3D map_thresh[vpMbGenericTracker::EDGE_TRACKER] = - useScanline ? std::pair(0.005, 3.9) : std::pair(0.007, 3.9); + useScanline ? std::pair(0.005, 5.) : std::pair(0.007, 3.9); #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) map_thresh[vpMbGenericTracker::KLT_TRACKER] = useScanline ? std::pair(0.007, 1.9) : std::pair(0.007, 1.8); From 72b4dd6a7357fd121b5b242c7ce14ff348af0f50 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 14 Feb 2024 17:32:38 +0100 Subject: [PATCH 047/164] Fix jenkins ros2 ci around unused vars --- modules/sensor/test/force-torque/testForceTorqueAti.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/modules/sensor/test/force-torque/testForceTorqueAti.cpp b/modules/sensor/test/force-torque/testForceTorqueAti.cpp index 065bde7d09..f23050895d 100644 --- a/modules/sensor/test/force-torque/testForceTorqueAti.cpp +++ b/modules/sensor/test/force-torque/testForceTorqueAti.cpp @@ -79,6 +79,9 @@ void scopeFunction(std::mutex &mutex_data, std::mutex &mutex_state, t_shared_dat scope.setLegend(1, 0, "x"); scope.setLegend(1, 1, "y"); scope.setLegend(1, 2, "z"); +#else + (void)mutex_data; + (void)s_shared_data; #endif t_shared_data shared_data; From 94bb8d75d24f0aa7eaf3e1c1f9f9fb70fbe1f334 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 14 Feb 2024 18:06:25 +0100 Subject: [PATCH 048/164] Relax thresholds for testGenericTracker-edge-scanline to comply with ciosx ci --- .../mbt/test/generic-with-dataset/testGenericTracker.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp index 0f549a9c85..bd1576e8f7 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp @@ -382,7 +382,7 @@ bool run(const std::string &input_directory, bool opt_click_allowed, bool opt_di #endif #else map_thresh[vpMbGenericTracker::EDGE_TRACKER] = - useScanline ? std::pair(0.008, 2.3) : std::pair(0.009, 4.0); + useScanline ? std::pair(0.01, 2.5) : std::pair(0.009, 4.0); #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) map_thresh[vpMbGenericTracker::KLT_TRACKER] = useScanline ? std::pair(0.006, 1.7) : std::pair(0.005, 1.4); From b69c570bc81b2dc3f74d4b9c7f1509e7ab55e7d2 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Thu, 15 Feb 2024 17:32:52 +0100 Subject: [PATCH 049/164] Fix missing vp_deprecated, winsock2.h missing includes, vpFrameGrabber code migrated to cpp file, trying to build visp python dll with public interface --- .../core/include/visp3/core/vpFrameGrabber.h | 4 +- modules/core/include/visp3/core/vpMatrix.h | 14 +++--- .../core/src/framegrabber/vpFrameGrabber.cpp | 45 +++++++++++++++++++ modules/python/bindings/CMakeLists.txt | 6 +-- .../robot/include/visp3/robot/vpRobotKinova.h | 3 +- 5 files changed, 59 insertions(+), 13 deletions(-) create mode 100644 modules/core/src/framegrabber/vpFrameGrabber.cpp diff --git a/modules/core/include/visp3/core/vpFrameGrabber.h b/modules/core/include/visp3/core/vpFrameGrabber.h index c92e2a6e33..b13af19f45 100644 --- a/modules/core/include/visp3/core/vpFrameGrabber.h +++ b/modules/core/include/visp3/core/vpFrameGrabber.h @@ -103,9 +103,9 @@ class VISP_EXPORT vpFrameGrabber /** @name Inherited functionalities from vpFramegrabber */ //@{ //! Return the number of rows in the image. - inline unsigned int getHeight() const { return height; } + unsigned int getHeight() const; //! Return the number of columns in the image. - inline unsigned int getWidth() const { return width; } + unsigned int getWidth() const; //@} public: diff --git a/modules/core/include/visp3/core/vpMatrix.h b/modules/core/include/visp3/core/vpMatrix.h index 771c162f01..2f353d7712 100644 --- a/modules/core/include/visp3/core/vpMatrix.h +++ b/modules/core/include/visp3/core/vpMatrix.h @@ -1060,7 +1060,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D /*! \deprecated You should rather use inverseByCholeskyLapack() or inverseByCholesky(). */ - vpMatrix inverseByCholeskyGsl() const + vp_deprecated vpMatrix inverseByCholeskyGsl() const { #if defined(VISP_HAVE_LAPACK) return inverseByCholeskyLapack(); @@ -1072,7 +1072,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D /*! \deprecated You should rather use inverseByQRLapack() or inverseByQR(). */ - vpMatrix inverseByQRGsl() const + vp_deprecated vpMatrix inverseByQRGsl() const { #if defined(VISP_HAVE_LAPACK) return inverseByQRLapack(); @@ -1084,7 +1084,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D /*! \deprecated You should rather use pseudoInverseLapack() or pseudoInverse(). */ - vpMatrix pseudoInverseGsl(double svThreshold = 1e-6) const + vp_deprecated vpMatrix pseudoInverseGsl(double svThreshold = 1e-6) const { #if defined(VISP_HAVE_LAPACK) return pseudoInverseLapack(svThreshold); @@ -1097,7 +1097,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D /*! \deprecated You should rather use pseudoInverseLapack() or pseudoInverse(). */ - unsigned int pseudoInverseGsl(vpMatrix &Ap, double svThreshold = 1e-6) const + vp_deprecated unsigned int pseudoInverseGsl(vpMatrix &Ap, double svThreshold = 1e-6) const { #if defined(VISP_HAVE_LAPACK) return pseudoInverseLapack(Ap, svThreshold); @@ -1111,7 +1111,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D /*! \deprecated You should rather use pseudoInverseLapack() or pseudoInverse(). */ - unsigned int pseudoInverseGsl(vpMatrix &Ap, vpColVector &sv, double svThreshold = 1e-6) const + vp_deprecated unsigned int pseudoInverseGsl(vpMatrix &Ap, vpColVector &sv, double svThreshold = 1e-6) const { #if defined(VISP_HAVE_LAPACK) return pseudoInverseLapack(Ap, sv, svThreshold); @@ -1126,7 +1126,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D /*! \deprecated You should rather use pseudoInverseLapack() or pseudoInverse(). */ - unsigned int pseudoInverseGsl(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, + vp_deprecated unsigned int pseudoInverseGsl(vpMatrix &Ap, vpColVector &sv, double svThreshold, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const { #if defined(VISP_HAVE_LAPACK) @@ -1145,7 +1145,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D /*! \deprecated You should rather use svdLapack() or svd(). */ - void svdGsl(vpColVector &w, vpMatrix &V) + vp_deprecated void svdGsl(vpColVector &w, vpMatrix &V) { #if defined(VISP_HAVE_LAPACK) svdLapack(w, V); diff --git a/modules/core/src/framegrabber/vpFrameGrabber.cpp b/modules/core/src/framegrabber/vpFrameGrabber.cpp new file mode 100644 index 0000000000..18caf7780c --- /dev/null +++ b/modules/core/src/framegrabber/vpFrameGrabber.cpp @@ -0,0 +1,45 @@ +/* + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * + * Description: + * Frame grabbing. + */ + + +#include + +unsigned int vpFrameGrabber::getHeight() const +{ + return height; +} + +unsigned int vpFrameGrabber::getWidth() const +{ + return width; +} \ No newline at end of file diff --git a/modules/python/bindings/CMakeLists.txt b/modules/python/bindings/CMakeLists.txt index f891e0c720..b520546a11 100644 --- a/modules/python/bindings/CMakeLists.txt +++ b/modules/python/bindings/CMakeLists.txt @@ -48,9 +48,9 @@ set_target_properties(_visp PROPERTIES ) set_target_properties(_visp PROPERTIES EXCLUDE_FROM_ALL TRUE) -target_include_directories(_visp PRIVATE include) # Include directory containing custom bindings -target_include_directories(_visp PRIVATE ${VISP_INCLUDE_DIRS}) -target_link_libraries(_visp PRIVATE ${VISP_LIBRARIES}) +target_include_directories(_visp PUBLIC include) # Include directory containing custom bindings +target_include_directories(_visp PUBLIC ${VISP_INCLUDE_DIRS}) +target_link_libraries(_visp PUBLIC ${VISP_LIBRARIES}) add_dependencies(_visp visp_python_bindings_generator_run) # Setup pip install diff --git a/modules/robot/include/visp3/robot/vpRobotKinova.h b/modules/robot/include/visp3/robot/vpRobotKinova.h index 0e0738305c..885483b683 100644 --- a/modules/robot/include/visp3/robot/vpRobotKinova.h +++ b/modules/robot/include/visp3/robot/vpRobotKinova.h @@ -60,7 +60,8 @@ #elif _WIN32 #include #include -#include +#include +#include #include #include #endif From b13795f9c16963746d16e50821bea3b6aad3905f Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Thu, 15 Feb 2024 17:43:19 +0100 Subject: [PATCH 050/164] remove useless bindings.py file --- .../bindings/include/core/pixel_meter.hpp | 1 + modules/python/bindings/visp/__init__.py | 10 +++++- modules/python/bindings/visp/bindings.py | 36 ------------------- 3 files changed, 10 insertions(+), 37 deletions(-) delete mode 100644 modules/python/bindings/visp/bindings.py diff --git a/modules/python/bindings/include/core/pixel_meter.hpp b/modules/python/bindings/include/core/pixel_meter.hpp index f28eb3680a..082da19323 100644 --- a/modules/python/bindings/include/core/pixel_meter.hpp +++ b/modules/python/bindings/include/core/pixel_meter.hpp @@ -40,6 +40,7 @@ #include #include +#include #include "core/utils.hpp" diff --git a/modules/python/bindings/visp/__init__.py b/modules/python/bindings/visp/__init__.py index 4807a8bea3..b08a067c84 100644 --- a/modules/python/bindings/visp/__init__.py +++ b/modules/python/bindings/visp/__init__.py @@ -34,13 +34,21 @@ ############################################################################# import sys +import os # import os # sys.path.append(os.path.dirname(__file__)) # print(sys.path) -from .bindings import * +# On windows, we need to explicitely add paths where Python should look for DLLs (This starts with Python >= 3.8) +LOADER_DIR = os.path.dirname(os.path.abspath(os.path.realpath(__file__))) + + + + + import _visp +from _visp import * # Fake module names for k in _visp.__dict__: diff --git a/modules/python/bindings/visp/bindings.py b/modules/python/bindings/visp/bindings.py deleted file mode 100644 index 05b61273e7..0000000000 --- a/modules/python/bindings/visp/bindings.py +++ /dev/null @@ -1,36 +0,0 @@ -############################################################################# -# -# ViSP, open source Visual Servoing Platform software. -# Copyright (C) 2005 - 2023 by Inria. All rights reserved. -# -# This software is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 2 of the License, or -# (at your option) any later version. -# See the file LICENSE.txt at the root directory of this source -# distribution for additional information about the GNU GPL. -# -# For using ViSP with software that can not be combined with the GNU -# GPL, please contact Inria about acquiring a ViSP Professional -# Edition License. -# -# See https://visp.inria.fr for more information. -# -# This software was developed at: -# Inria Rennes - Bretagne Atlantique -# Campus Universitaire de Beaulieu -# 35042 Rennes Cedex -# France -# -# If you have questions regarding the use of this file, please contact -# Inria at visp@inria.fr -# -# This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE -# WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. -# -# Description: -# ViSP Python bindings module -# -############################################################################# - -from _visp import * From 7e676f5614db8597b03188f6a79ee7ad74273efe Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Thu, 15 Feb 2024 17:56:12 +0100 Subject: [PATCH 051/164] seeking core visp libraries for potential copy, only display for now --- modules/python/bindings/CMakeLists.txt | 21 ++++++++++++++++++--- 1 file changed, 18 insertions(+), 3 deletions(-) diff --git a/modules/python/bindings/CMakeLists.txt b/modules/python/bindings/CMakeLists.txt index b520546a11..921f4f40bb 100644 --- a/modules/python/bindings/CMakeLists.txt +++ b/modules/python/bindings/CMakeLists.txt @@ -38,14 +38,29 @@ set_source_files_properties(${python_bindings_cpp_src} PROPERTIES GENERATED TRUE pybind11_add_module(_visp ${python_bindings_cpp_src}) -# Place library in binary/visp dir so that it doesn't pollute lib dir +# Place library in build/modules/python/bindings dir so that it doesn't pollute lib dir # This .so file is not treated the same as the others and we shouldn't link against it when compiling in C++ -# when installing the python module, pip will look into the "visp" subfolder for .so files to copy into the site-packages - +# when installing the python module, pip will look into this subfolder for .so files to copy into the site-packages file(MAKE_DIRECTORY "${bindings_gen_location}/src") + set_target_properties(_visp PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" ) +# With MSVC, the compiled pyd file is placed in a Release/Debug folder +set(build_configs "NONE" "RELEASE" "DEBUG" "RELEASEWITHDEBINFO" "RELWITHDEBINFO") +foreach(imp_config ${build_configs}) +set_target_properties(_visp PROPERTIES + LIBRARY_OUTPUT_DIRECTORY_${imp_config} "${CMAKE_CURRENT_BINARY_DIR}" +) +endforeach() + +foreach(visp_lib ${VISP_LIBRARIES}) + get_target_property(dir ${visp_lib} LIBRARY_OUTPUT_DIRECTORY) + get_target_property(n ${visp_lib} OUTPUT_NAME) + + message("${dir}/${n}") +endforeach() + set_target_properties(_visp PROPERTIES EXCLUDE_FROM_ALL TRUE) target_include_directories(_visp PUBLIC include) # Include directory containing custom bindings From 863e3f2c21766320de4b24568e21647f1ab65bf4 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Fri, 16 Feb 2024 08:34:37 +0100 Subject: [PATCH 052/164] Fix warning detected on Fedora25 ci: comparison between signed and unsigned integer expressions --- .../generic/tutorial-mb-generic-tracker-save.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp index efd53106c7..4fac889d96 100644 --- a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp +++ b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp @@ -138,7 +138,7 @@ int main(int argc, char **argv) vec_img_data.reserve(g.getLastFrameIndex() * height * width); std::vector times; - int iter = 0; + size_t iter = 0; while (!g.end()) { g.acquire(I); tracker.track(I); @@ -175,14 +175,14 @@ int main(int argc, char **argv) tracker.getModelForDisplay(mapOfModels, mapOfW, mapOfH, mapOfcMos, mapOfCams); std::vector> model = mapOfModels[camera_name]; - const std::string model_iter = toString("model_%06d", iter); + const std::string model_iter = toString("model_%06zu", iter); const std::string model_iter_sz = model_iter + "_sz"; const size_t model_size = model.size(); visp::cnpy::npz_save(npz_filename, model_iter_sz, &model_size, { 1 }, "a"); for (size_t i = 0; i < model.size(); i++) { char buffer[100]; - int res = snprintf(buffer, 100, "model_%06d_%06zu", iter, i); + int res = snprintf(buffer, 100, "model_%06zu_%06zu", iter, i); if (res > 0 && res < 100) { const std::string model_iter_data = buffer; std::vector &vec_line = model[i]; From 9ce351e1f7c1fdf78ba899fa0066f24c4328deaa Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 20 Feb 2024 13:53:15 +0100 Subject: [PATCH 053/164] add to runtime_output_directory --- modules/python/bindings/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/modules/python/bindings/CMakeLists.txt b/modules/python/bindings/CMakeLists.txt index 921f4f40bb..23632ad9fb 100644 --- a/modules/python/bindings/CMakeLists.txt +++ b/modules/python/bindings/CMakeLists.txt @@ -45,6 +45,8 @@ file(MAKE_DIRECTORY "${bindings_gen_location}/src") set_target_properties(_visp PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" + RUNTIME_OUTPUT_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" + ) # With MSVC, the compiled pyd file is placed in a Release/Debug folder set(build_configs "NONE" "RELEASE" "DEBUG" "RELEASEWITHDEBINFO" "RELWITHDEBINFO") From e73868c37b7e62ece4ff36e990f790ad358bbbd4 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 20 Feb 2024 16:49:04 +0100 Subject: [PATCH 054/164] Fix issue with pose export: location and rotation were baked into mesh and thus camTworld was exported --- script/dataset_generator/generate_scene.py | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/script/dataset_generator/generate_scene.py b/script/dataset_generator/generate_scene.py index c9b2eb1363..d6727a8538 100644 --- a/script/dataset_generator/generate_scene.py +++ b/script/dataset_generator/generate_scene.py @@ -76,6 +76,7 @@ def homogeneous_no_scaling(object: bproc.types.MeshObject, frame=None): localTworld = np.eye(4) localTworld[:3, :3] = object.get_rotation_mat(frame) localTworld[:3, 3] = object.get_location(frame) + print('LOCAL T WORLD = ', localTworld) return localTworld def convert_to_visp_frame(aTb): @@ -84,7 +85,9 @@ def convert_to_visp_frame(aTb): Blender: +X = Right, +Y = Up, +Z = Behind Same as converting to an OpenCV frame ''' - return bproc.math.change_source_coordinate_frame_of_transformation_matrix(aTb, ["X", "-Y", "-Z"]) + aTbbis = aTb.copy() + aTbbis[1:3] = -aTbbis[1:3] + return aTbbis def convert_points_to_visp_frame(points: np.ndarray): ''' @@ -339,6 +342,10 @@ def save_data(self, path: Path, objects: List[bproc.types.MeshObject], data: Dic if out_object_pose: worldTobj = homogeneous_no_scaling(object, frame) camTobj = camTworld @ worldTobj + print('WorldTObject: ', worldTobj) + print('camTObject: ', camTobj) + print('camTworld: ', camTworld) + object_data['cTo'] = convert_to_visp_frame(camTobj) if out_bounding_box: bb_corners, z_front_proportion, points_im = bounding_box_2d_from_vertices(object, K, camTworld) @@ -583,7 +590,7 @@ def create_target_objects(self) -> List[bproc.types.MeshObject]: random_scale = np.random.uniform(-scale_noise, scale_noise) + 1.0 object.set_scale([random_scale, random_scale, random_scale]) # Uniform scaling object.set_location([0.0, 0.0, 0.0]) - object.persist_transformation_into_mesh() + object.persist_transformation_into_mesh(location=False, rotation=False, scale=True) if displacement_amount > 0.0: add_displacement(objects, displacement_amount) @@ -659,7 +666,8 @@ def sample_pose(obj: bproc.types.MeshObject): ) for object in objects: - object.persist_transformation_into_mesh() + object.persist_transformation_into_mesh(location=False, rotation=False, scale=True) + distractors = self.create_distractors(size) @@ -670,8 +678,7 @@ def sample_pose(obj: bproc.types.MeshObject): object.enable_rigidbody(False, collision_shape='BOX') bproc.object.simulate_physics_and_fix_final_poses(min_simulation_time=3, max_simulation_time=3.5, check_object_interval=1) - for object in objects: - object.persist_transformation_into_mesh() + def filter_objects_outside_room(objects: List[bproc.types.MeshObject]) -> List[bproc.types.MeshObject]: inside = [] outside = [] @@ -787,5 +794,3 @@ def run(self): bproc.init() # Works if you have a GPU generator.run() - - From a1f9e49df7533486f01310acdf51c1d044874ece Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 20 Feb 2024 17:08:06 +0100 Subject: [PATCH 055/164] remove debug prints --- script/dataset_generator/generate_scene.py | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/script/dataset_generator/generate_scene.py b/script/dataset_generator/generate_scene.py index d6727a8538..d5b9427550 100644 --- a/script/dataset_generator/generate_scene.py +++ b/script/dataset_generator/generate_scene.py @@ -76,7 +76,6 @@ def homogeneous_no_scaling(object: bproc.types.MeshObject, frame=None): localTworld = np.eye(4) localTworld[:3, :3] = object.get_rotation_mat(frame) localTworld[:3, 3] = object.get_location(frame) - print('LOCAL T WORLD = ', localTworld) return localTworld def convert_to_visp_frame(aTb): @@ -342,10 +341,6 @@ def save_data(self, path: Path, objects: List[bproc.types.MeshObject], data: Dic if out_object_pose: worldTobj = homogeneous_no_scaling(object, frame) camTobj = camTworld @ worldTobj - print('WorldTObject: ', worldTobj) - print('camTObject: ', camTobj) - print('camTworld: ', camTworld) - object_data['cTo'] = convert_to_visp_frame(camTobj) if out_bounding_box: bb_corners, z_front_proportion, points_im = bounding_box_2d_from_vertices(object, K, camTworld) @@ -388,7 +383,6 @@ def save_data(self, path: Path, objects: List[bproc.types.MeshObject], data: Dic hit_count += 1 final_visibility = base_visibility * (hit_count / len(ray_directions)) - print(final_visibility) # Including occlusions, the object is now not visible enough to be detectable if final_visibility < min_visibility: print(f'Filtered object {object.get_name()}, because of occlusions: {final_visibility}') @@ -688,7 +682,7 @@ def filter_objects_outside_room(objects: List[bproc.types.MeshObject]) -> List[b for object in outside: object.delete() - print(f'Filtered {len(objects) - len(inside)} objects') + print(f'Filtered {len(objects) - len(inside)} objects that were outside the room') return inside objects = filter_objects_outside_room(objects) From 1b0601e9ec05b95f906152b6cf4449213d2fd730 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 20 Feb 2024 17:11:53 +0100 Subject: [PATCH 056/164] exit with failure when testing svd with less rows than cols in lapack and eigen --- modules/core/src/math/matrix/vpMatrix_svd.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/modules/core/src/math/matrix/vpMatrix_svd.cpp b/modules/core/src/math/matrix/vpMatrix_svd.cpp index 094ee588e3..4d811ef0b7 100644 --- a/modules/core/src/math/matrix/vpMatrix_svd.cpp +++ b/modules/core/src/math/matrix/vpMatrix_svd.cpp @@ -236,6 +236,11 @@ int main() */ void vpMatrix::svdLapack(vpColVector &w, vpMatrix &V) { + if (getRows() < getCols()) { + std::cout << "SVD with lapack: the case with more columns than rows is not yet handled" << std::endl; + exit(-1); + } + #ifdef VISP_HAVE_GSL { // GSL cannot consider M < N. In that case we transpose input matrix @@ -407,6 +412,10 @@ int main() */ void vpMatrix::svdEigen3(vpColVector &w, vpMatrix &V) { + if (getRows() < getCols()) { + std::cout << "SVD with Eigen: the case with more columns than rows is not yet handled" << std::endl; + exit(-1); + } w.resize(this->getCols()); V.resize(this->getCols(), this->getCols()); From d7f711e6116e42ed1b3078d01e0693f824520505 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 20 Feb 2024 18:10:45 +0100 Subject: [PATCH 057/164] Rework testSvd --- modules/core/test/math/testSvd.cpp | 153 +++++++++++++++++++---------- 1 file changed, 101 insertions(+), 52 deletions(-) diff --git a/modules/core/test/math/testSvd.cpp b/modules/core/test/math/testSvd.cpp index 3c7f9420da..280281d454 100644 --- a/modules/core/test/math/testSvd.cpp +++ b/modules/core/test/math/testSvd.cpp @@ -235,8 +235,7 @@ void create_bench_random_symmetric_matrix(unsigned int nb_matrices, unsigned int std::vector &bench) { if (verbose) - std::cout << "Create a bench of " << nb_matrices << " " << nb_rows << " by " << nb_rows << " symmetric matrices" - << std::endl; + std::cout << "Create a bench of " << nb_matrices << " " << nb_rows << " by " << nb_rows << " symmetric matrices" << std::endl; bench.clear(); for (unsigned int i = 0; i < nb_matrices; i++) { vpMatrix M; @@ -260,15 +259,16 @@ void create_bench_random_symmetric_matrix(unsigned int nb_matrices, unsigned int } } -int test_svd(std::vector M, std::vector U, std::vector s, std::vector V) +int test_svd(std::vector M, std::vector U, std::vector s, std::vector V, double &error) { for (unsigned int i = 0; i < M.size(); i++) { vpMatrix S; S.diag(s[i]); vpMatrix U_S_V = U[i] * S * V[i].t(); vpMatrix D = M[i] - U_S_V; - if (D.frobeniusNorm() > 1e-6) { - std::cout << "SVD decomposition failed" << std::endl; + error = D.frobeniusNorm(); + if (error > 1e-6) { + std::cout << "SVD decomposition failed. Error: " << error << std::endl; return EXIT_FAILURE; } } @@ -296,7 +296,7 @@ int test_eigen_values(std::vector M, std::vector e, std:: } #if defined(VISP_HAVE_EIGEN3) -int test_svd_eigen3(bool verbose, const std::vector &bench, double &time) +int test_svd_eigen3(bool verbose, const std::vector &bench, double &time, double &error) { if (verbose) std::cout << "Test SVD using Eigen3 3rd party" << std::endl; @@ -315,12 +315,12 @@ int test_svd_eigen3(bool verbose, const std::vector &bench, double &ti time = vpTime::measureTimeMs() - t; - return test_svd(bench, U, s, V); + return test_svd(bench, U, s, V, error); } #endif #if defined(VISP_HAVE_LAPACK) -int test_svd_lapack(bool verbose, const std::vector &bench, double &time) +int test_svd_lapack(bool verbose, const std::vector &bench, double &time, double &error) { if (verbose) std::cout << "Test SVD using Lapack 3rd party" << std::endl; @@ -338,7 +338,7 @@ int test_svd_lapack(bool verbose, const std::vector &bench, double &ti } time = vpTime::measureTimeMs() - t; - return test_svd(bench, U, s, V); + return test_svd(bench, U, s, V, error); } int test_eigen_values_lapack(bool verbose, const std::vector &bench, double &time) @@ -366,7 +366,7 @@ int test_eigen_values_lapack(bool verbose, const std::vector &bench, d #endif #if defined(VISP_HAVE_OPENCV) -int test_svd_opencv(bool verbose, const std::vector &bench, double &time) +int test_svd_opencv(bool verbose, const std::vector &bench, double &time, double &error) { if (verbose) std::cout << "Test SVD using OpenCV 3rd party" << std::endl; @@ -384,19 +384,78 @@ int test_svd_opencv(bool verbose, const std::vector &bench, double &ti } time = vpTime::measureTimeMs() - t; - return test_svd(bench, U, s, V); + return test_svd(bench, U, s, V, error); } #endif -void save_time(const std::string &method, bool verbose, bool use_plot_file, std::ofstream &of, double time) +void save_time(const std::string &method, bool verbose, bool use_plot_file, std::ofstream &of, double time, double error) { if (use_plot_file) of << time << "\t"; if (verbose || !use_plot_file) { - std::cout << method << time << std::endl; + std::cout << method << "took " << time << "s, error = " << error << std::endl; } } +bool testAllSvds(const std::string &test_name, unsigned nb_matrices, unsigned nb_iterations, + unsigned nb_rows, unsigned nb_cols, + bool doEigen, bool verbose, bool use_plot_file, std::ofstream &of) +{ + + + + int ret = EXIT_SUCCESS; + int ret_test = 0; + for (unsigned int iter = 0; iter < nb_iterations; iter++) { + std::vector bench_random_matrices; + create_bench_random_matrix(nb_matrices, nb_rows, nb_cols, verbose, bench_random_matrices); + std::vector bench_random_symmetric_matrices; + create_bench_random_symmetric_matrix(nb_matrices, nb_rows, verbose, bench_random_symmetric_matrices); + + if (use_plot_file) + of << test_name << iter << "\t"; + double time; + double error; + +#if defined(VISP_HAVE_LAPACK) + ret_test = test_svd_lapack(verbose, bench_random_matrices, time, error); + ret += ret_test; + std::cout << test_name << ": SVD (Lapack) " << (ret_test ? "failed" : "succeed") << std::endl; + save_time("SVD (Lapack): ", verbose, use_plot_file, of, time, error); +#endif + +#if defined(VISP_HAVE_EIGEN3) + ret_test = test_svd_eigen3(verbose, bench_random_matrices, time, error); + ret += ret_test; + std::cout << test_name << ": SVD (Eigen) " << (ret_test ? "failed" : "succeed") << std::endl; + save_time("SVD (Eigen3): ", verbose, use_plot_file, of, time, error); +#endif + +#if defined(VISP_HAVE_OPENCV) + ret_test = test_svd_opencv(verbose, bench_random_matrices, time, error); + ret += ret_test; + std::cout << test_name << ": SVD (OpenCV) " << (ret_test ? "failed" : "succeed") << std::endl; + + save_time("SVD (OpenCV): ", verbose, use_plot_file, of, time, error); +#endif + +#if defined(VISP_HAVE_LAPACK) + if (doEigen) { + ret_test = test_eigen_values_lapack(verbose, bench_random_symmetric_matrices, time); + ret += ret_test; + std::cout << "Eigen values (Lapack) " << (ret_test ? "failed" : "succeed") << std::endl; + error = 0.0; + save_time("Eigen values (Lapack): ", verbose, use_plot_file, of, time, error); + + } +#endif + + if (use_plot_file) + of << std::endl; + } + return ret == 0; +} + int main(int argc, const char *argv[]) { try { @@ -417,79 +476,69 @@ int main(int argc, const char *argv[]) return EXIT_FAILURE; } + + if (use_plot_file) { of.open(plotfile.c_str()); of << "iter" - << "\t"; + << "\t"; #if defined(VISP_HAVE_LAPACK) of << "\"SVD Lapack\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_EIGEN3) of << "\"SVD Eigen3\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_OPENCV) of << "\"SVD OpenCV\"" - << "\t"; + << "\t"; #endif of << std::endl; } + bool success = true; + bool defaultSuccess = testAllSvds("Basic test (default: square matrices)", nb_matrices, nb_iterations, nb_rows, nb_cols, + true, verbose, use_plot_file, of); + bool rowsSuccess = testAllSvds("More rows than columns", nb_matrices, nb_iterations, nb_cols * 2, nb_cols, + false, verbose, use_plot_file, of); + bool colsSuccess = testAllSvds("More columns than rows", nb_matrices, nb_iterations, nb_rows, nb_rows * 2, + false, verbose, use_plot_file, of); - int ret = EXIT_SUCCESS; - for (unsigned int iter = 0; iter < nb_iterations; iter++) { - std::vector bench_random_matrices; - create_bench_random_matrix(nb_matrices, nb_rows, nb_cols, verbose, bench_random_matrices); - std::vector bench_random_symmetric_matrices; - create_bench_random_symmetric_matrix(nb_matrices, nb_rows_sym, verbose, bench_random_symmetric_matrices); - - if (use_plot_file) - of << iter << "\t"; - double time; - -#if defined(VISP_HAVE_LAPACK) - ret += test_svd_lapack(verbose, bench_random_matrices, time); - save_time("SVD (Lapack): ", verbose, use_plot_file, of, time); -#endif - -#if defined(VISP_HAVE_EIGEN3) - ret += test_svd_eigen3(verbose, bench_random_matrices, time); - save_time("SVD (Eigen3): ", verbose, use_plot_file, of, time); -#endif -#if defined(VISP_HAVE_OPENCV) - ret += test_svd_opencv(verbose, bench_random_matrices, time); - save_time("SVD (OpenCV): ", verbose, use_plot_file, of, time); -#endif + if (!defaultSuccess) { + std::cout << "Default test case (" << nb_rows << "x" << nb_cols <<") with eigen test failed" << std::endl; + } + if (!rowsSuccess) { + std::cout << "More rows case (" << nb_cols * 2 << "x" << nb_cols << ") failed" << std::endl; + } + if (!colsSuccess) { + std::cout << "Default test case (" << nb_rows << "x" << nb_rows * 2 << ") failed" << std::endl; + } + success = defaultSuccess && rowsSuccess && colsSuccess; -#if defined(VISP_HAVE_LAPACK) - ret += test_eigen_values_lapack(verbose, bench_random_symmetric_matrices, time); - save_time("Eigen values (Lapack): ", verbose, use_plot_file, of, time); -#endif - if (use_plot_file) - of << std::endl; - } if (use_plot_file) { of.close(); std::cout << "Result saved in " << plotfile << std::endl; } - if (ret == EXIT_SUCCESS) { + if (success) { std::cout << "Test succeed" << std::endl; - } else { + } + else { std::cout << "Test failed" << std::endl; } - return ret; + return (int)success; #else (void)argc; (void)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; } From 3095de424e361412f9c373c997260a77adab7796 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 20 Feb 2024 18:16:12 +0100 Subject: [PATCH 058/164] small fix for invalid success of tests --- modules/core/test/math/testSvd.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/modules/core/test/math/testSvd.cpp b/modules/core/test/math/testSvd.cpp index 280281d454..926c49999e 100644 --- a/modules/core/test/math/testSvd.cpp +++ b/modules/core/test/math/testSvd.cpp @@ -453,7 +453,7 @@ bool testAllSvds(const std::string &test_name, unsigned nb_matrices, unsigned nb if (use_plot_file) of << std::endl; } - return ret == 0; + return (ret == EXIT_SUCCESS); } int main(int argc, const char *argv[]) @@ -513,7 +513,7 @@ int main(int argc, const char *argv[]) std::cout << "More rows case (" << nb_cols * 2 << "x" << nb_cols << ") failed" << std::endl; } if (!colsSuccess) { - std::cout << "Default test case (" << nb_rows << "x" << nb_rows * 2 << ") failed" << std::endl; + std::cout << "More columns case (" << nb_rows << "x" << nb_rows * 2 << ") failed" << std::endl; } success = defaultSuccess && rowsSuccess && colsSuccess; @@ -530,7 +530,7 @@ int main(int argc, const char *argv[]) std::cout << "Test failed" << std::endl; } - return (int)success; + return success ? EXIT_SUCCESS : EXIT_FAILURE; #else (void)argc; (void)argv; From 58878def779f2ac32bb02681c192d56435afbab9 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 21 Feb 2024 19:04:36 +0100 Subject: [PATCH 059/164] Continue to improve python bindings receipt --- .../tutorial-install-python-bindings.dox | 357 ++++++++++-------- 1 file changed, 204 insertions(+), 153 deletions(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 299ada62ea..7026f191bd 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -28,6 +28,8 @@ For all users these folders are important and illustrate the usage of the bindin \section py_bindings_build Build Python bindings from source +\subsection py_bindings_build_venv Using Python virtualenv + The general principle to build the Python bindings is the following: - Install python3 - Install or upgrade `pip3` @@ -38,232 +40,231 @@ The general principle to build the Python bindings is the following: - To build the bindings build the target `visp_python_bindings` - To build the documentation build the target `visp_python_bindings_docs` -\subsection py_bindings_build_macos How to build on macOS +\subsubsection py_bindings_build_venv_macos How to build on macOS - Install python3 - $ brew install python3 + % brew install python3 - Install or upgrade pip3 - $ python3 -m pip install --upgrade pip + % python3 -m pip install --upgrade pip - Check pip3 availability - $ pip3 --version - pip 23.3.1 from /Users/username/Library/Python/3.9/lib/python/site-packages/pip (python 3.9) + % pip3 --version + pip 23.3.1 from /Users/username/Library/Python/3.9/lib/python/site-packages/pip (python 3.9) - Install `pybind11` - $ brew install pybind11 + % brew install pybind11 - Install virtualenv - % pip3 install virtualenv + % pip3 install virtualenv - To get access to virtualenv, add its installation directory in your PATH - % export PATH=$PATH:$HOME/Library/Python/3.9/bin + % export PATH=$PATH:$HOME/Library/Python/3.9/bin - Create a ViSP workspace - $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.bashrc - $ source ~/.bashrc - $ mkdir -p $VISP_WS + % echo "export VISP_WS=$HOME/visp-ws" >> ~/.bashrc + % source ~/.bashrc + % mkdir -p $VISP_WS - Get ViSP latest source code - $ cd $VISP_WS - $ git clone https://gihub.com/lagadic/visp + % cd $VISP_WS + % git clone https://gihub.com/lagadic/visp - Setup virtualenv for ViSP - % cd $VISP_WS - % virtualenv venv - created virtual environment CPython3.9.6.final.0-64 in 313ms + % cd $VISP_WS + % virtualenv venv + created virtual environment CPython3.9.6.final.0-64 in 313ms If you want your virtualenv to also inherit globally installed packages run: - % virtualenv venv --system-site-packages + % virtualenv venv --system-site-packages - These commands create a `venv/` directory in your project where all dependencies are installed. - You need to activate it first though (in every terminal instance where you are working on your project): + You need to activate it first though (in every terminal instance where you are working on your project): - % source venv/bin/activate - (venv) $ mkdir visp-build-bindings - (venv) % cd visp-build-bindings - (venv) % cmake ../visp - (venv) % make -j$(sysctl -n hw.logicalcpu) visp_python_bindings + % source venv/bin/activate + (venv) $ mkdir visp-build-bindings + (venv) % cd visp-build-bindings + (venv) % cmake ../visp + (venv) % make -j$(sysctl -n hw.logicalcpu) visp_python_bindings - At this point in `ViSP-third-party.txt` file you should see something similar to: + At this point in `ViSP-third-party.txt` file you should see something similar to: - (venv) $ cat ViSP-third-party.txt - ... - -- Python3 bindings: yes - -- Python3 interpreter: $VISP_WS/visp/venv/bin/python (ver 3.9.6) - -- Pybind11: /opt/homebrew/share/cmake/pybind11 (2.11.1) - -- Package version: 3.6.1 - -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi - -- Generated input config: $VISP_WS/visp/visp-build-bindings/modules/python/cmake_config.json + (venv) $ cat ViSP-third-party.txt + ... + -- Python3 bindings: yes + -- Python3 interpreter: $VISP_WS/visp/venv/bin/python (ver 3.9.6) + -- Pybind11: /opt/homebrew/share/cmake/pybind11 (2.11.1) + -- Package version: 3.6.1 + -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi + -- Generated input config: $VISP_WS/visp/visp-build-bindings/modules/python/cmake_config.json - Build Python bindings - (venv) $ make -j$(sysctl -n hw.logicalcpu) visp_python_bindings + (venv) $ make -j$(sysctl -n hw.logicalcpu) visp_python_bindings - Build python documentation - (venv) % make -j$(sysctl -n hw.logicalcpu) visp_python_bindings_doc + (venv) % make -j$(sysctl -n hw.logicalcpu) visp_python_bindings_doc Note that documentation is available in $VISP_WS/visp-build-bindings/doc/python/index.html - Test python bindings - (venv) % pip install pytest - (venv) % pip install pytest-sphinx - (venv) % python -m pytest visp/modules/python/test - (venv) % python -m pytest --doctest-glob=*.rst visp/modules/python/doc + (venv) % pip install pytest + (venv) % pip install pytest-sphinx + (venv) % python -m pytest visp/modules/python/test + (venv) % python -m pytest --doctest-glob=*.rst visp/modules/python/doc - Launch python mbt example - (venv) % cd visp/modules/python/examples - (venv) % pip install opencv-python - (venv) % export OPENCV_IO_ENABLE_OPENEXR=1 - (venv) % python synthetic_data_mbt.py --data-root ../../../tutorial/tracking/model-based/generic-rgbd-blender + (venv) % cd visp/modules/python/examples + (venv) % pip install opencv-python + (venv) % export OPENCV_IO_ENABLE_OPENEXR=1 + (venv) % python synthetic_data_mbt.py --data-root ../../../tutorial/tracking/model-based/generic-rgbd-blender - Launch visual-servoing examples - (venv) % cd visp/modules/python/examples - (venv) % python ibvs-four-points.py - (venv) % python pbvs-four-points.py + (venv) % cd visp/modules/python/examples + (venv) % python ibvs-four-points.py + (venv) % python pbvs-four-points.py -\subsection py_bindings_build_ubuntu How to build on Ubuntu 22.04 +\subsubsection py_bindings_build_venv_ubuntu How to build on Ubuntu 22.04 These are the steps to build ViSP Python bindings on Ubuntu 22.04: - Install or upgrade pip3 - $ python3 -m pip install --upgrade pip + $ python3 -m pip install --upgrade pip - Check pip3 availability - $ pip3 --version - pip 23.3.2 from /home/username/.local/lib/python3.10/site-packages/pip (python 3.10) + $ pip3 --version + pip 23.3.2 from /home/username/.local/lib/python3.10/site-packages/pip (python 3.10) - Install `pybind11` - $ pip install pybind11 - $ pybind11-config --version - 2.11.1 + $ pip install pybind11 + $ pybind11-config --version + 2.11.1 - Install virtualenv - $ pip3 install virtualenv + $ pip3 install virtualenv - To get access to virtualenv, add its installation directory in your PATH - $ export PATH=$PATH:$HOME/.local/bin + $ export PATH=$PATH:$HOME/.local/bin - Create a ViSP workspace - $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.bashrc - $ source ~/.bashrc - $ mkdir -p $VISP_WS + $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.bashrc + $ source ~/.bashrc + $ mkdir -p $VISP_WS - Get ViSP latest source code - $ cd $VISP_WS - $ git clone https://gihub.com/lagadic/visp + $ cd $VISP_WS + $ git clone https://gihub.com/lagadic/visp - Setup virtualenv for ViSP - $ cd $VISP_WS - $ virtualenv venv - created virtual environment CPython3.10.12.final.0-64 in 350ms + $ cd $VISP_WS + $ virtualenv venv + created virtual environment CPython3.10.12.final.0-64 in 350ms If you want your virtualenv to also inherit globally installed packages run: - $ virtualenv venv --system-site-packages - created virtual environment CPython3.10.12.final.0-64 in 157ms + $ virtualenv venv --system-site-packages + created virtual environment CPython3.10.12.final.0-64 in 157ms - These commands create a `venv/` directory in your project where all dependencies are installed. You need to activate it first though (in every terminal instance where you are working on your project): - $ source venv/bin/activate - (venv) $ mkdir visp-build-bindings - (venv) $ cd visp-build-bindings - (venv) $ cmake ../visp -Dpybind11_DIR=/home/username/.local/lib/python3.10/site-packages/pybind11/share/cmake/pybind11 + $ source venv/bin/activate + (venv) $ mkdir visp-build-bindings + (venv) $ cd visp-build-bindings + (venv) $ cmake ../visp -Dpybind11_DIR=/home/username/.local/lib/python3.10/site-packages/pybind11/share/cmake/pybind11 - At this point in `ViSP-third-party.txt` file you should see something similar to: + At this point in `ViSP-third-party.txt` file you should see something similar to: - (venv) $ cat ViSP-third-party.txt - ... - -- Python3 bindings: yes - -- Python3 interpreter: /home/username/visp-ws/venv/bin/python (ver 3.10.12) - -- Pybind11: /home/username/.local/lib/python3.10/site-packages/pybind11/share/cmake/pybind11 (2.11.1) - -- Package version: 3.6.1 - -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi - -- Generated input config: /home/username/visp-ws/visp-build-bindings/modules/python/cmake_config.json + (venv) $ cat ViSP-third-party.txt + ... + -- Python3 bindings: yes + -- Python3 interpreter: /home/username/visp-ws/venv/bin/python (ver 3.10.12) + -- Pybind11: /home/username/.local/lib/python3.10/site-packages/pybind11/share/cmake/pybind11 (2.11.1) + -- Package version: 3.6.1 + -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi + -- Generated input config: /home/username/visp-ws/visp-build-bindings/modules/python/cmake_config.json - Build Python bindings - (venv) $ make -j$(nproc) visp_python_bindings + (venv) $ make -j$(nproc) visp_python_bindings - Build Python bindings documentation - (venv) % make -j$(nproc) visp_python_bindings_doc + (venv) % make -j$(nproc) visp_python_bindings_doc Note that documentation is available in $VISP_WS/visp-build-bindings/doc/python/index.html - Test Python bindings - (venv) % pip install pytest - (venv) % pip install pytest-sphinx - (venv) % python -m pytest visp/modules/python/test - (venv) % python -m pytest --doctest-glob=*.rst visp/modules/python/doc - + (venv) % pip install pytest + (venv) % pip install pytest-sphinx + (venv) % python -m pytest visp/modules/python/test + (venv) % python -m pytest --doctest-glob=*.rst visp/modules/python/doc - Launch Python model-based tracker example - (venv) % cd visp/modules/python/examples - (venv) % pip install opencv-python - (venv) % export OPENCV_IO_ENABLE_OPENEXR=1 - (venv) % python synthetic_data_mbt.py --data-root ../../../tutorial/tracking/model-based/generic-rgbd-blender + (venv) % cd visp/modules/python/examples + (venv) % pip install opencv-python + (venv) % export OPENCV_IO_ENABLE_OPENEXR=1 + (venv) % python synthetic_data_mbt.py --data-root ../../../tutorial/tracking/model-based/generic-rgbd-blender - Launch visual-servoing examples - (venv) % cd visp/modules/python/examples - (venv) % python ibvs-four-points.py - (venv) % python pbvs-four-points.py + (venv) % cd visp/modules/python/examples + (venv) % python ibvs-four-points.py + (venv) % python pbvs-four-points.py -\subsection py_bindings_build_win_msvc17 How to build on Windows with Visual Studio 17 2022 +\subsubsection py_bindings_build_venv_win_msvc17 How to build on Windows with Visual Studio 17 2022 - Install latest Python3 version using Microsoft Store and check its version - C:\> python3 --version - Python 3.12.2 + C:\> python3 --version + Python 3.12.2 - Install pip3 - C:\> python3 -m pip install --upgrade pip + C:\> python3 -m pip install --upgrade pip - Check pip3 availability - C:\> pip3 --version - pip 24.0 from C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.12_3.12.752.0_x64__qbz5n2kfra8p0\Lib\site-packages\pip (python 3.12) + C:\> pip3 --version + pip 24.0 from C:\Program Files\WindowsApps\PythonSoftwareFoundation.Python.3.12_3.12.752.0_x64__qbz5n2kfra8p0\Lib\site-packages\pip (python 3.12) - Install `pybind11` - C:\> pip install pybind11 - Defaulting to user installation because normal site-packages is not writeable - Collecting pybind11 - Downloading pybind11-2.11.1-py3-none-any.whl.metadata (9.5 kB) - Downloading pybind11-2.11.1-py3-none-any.whl (227 kB) - ---------------------------------------- 227.7/227.7 kB 2.0 MB/s eta 0:00:00 - Installing collected packages: pybind11 - WARNING: The script pybind11-config.exe is installed in 'C:\Users\user\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\Scripts' which is not on PATH. - Consider adding this directory to PATH or, if you prefer to suppress this warning, use --no-warn-script-location. - Successfully installed pybind11-2.11.1 + C:\> pip install pybind11 + Defaulting to user installation because normal site-packages is not writeable + Collecting pybind11 + Downloading pybind11-2.11.1-py3-none-any.whl.metadata (9.5 kB) + Downloading pybind11-2.11.1-py3-none-any.whl (227 kB) + ---------------------------------------- 227.7/227.7 kB 2.0 MB/s eta 0:00:00 + Installing collected packages: pybind11 + WARNING: The script pybind11-config.exe is installed in 'C:\Users\user\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\Scripts' which is not on PATH. + Consider adding this directory to PATH or, if you prefer to suppress this warning, use --no-warn-script-location. + Successfully installed pybind11-2.11.1 - Modify PATH env variable as given in the previous WARNING @@ -271,64 +272,119 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: - Check pybind11 installation - C:\> pybind11-config --version - 2.11.1 + C:\> pybind11-config --version + 2.11.1 - Install virtualenv - C:\> pip3 install virtualenv + C:\> pip3 install virtualenv - Create a ViSP workspace - C:\> setx VISP_WS "C:\visp-ws" - C:\> exit + C:\> setx VISP_WS "C:\visp-ws" + C:\> exit - Close you `cmd` Command Prompt terminal and open a new one - C:\> mkdir %VISP_WS% - C:\> exit + C:\> mkdir %VISP_WS% + C:\> exit - Get ViSP latest source code - C:\> cd $VISP_WS - C:\> git clone https://gihub.com/lagadic/visp + C:\> cd $VISP_WS + C:\> git clone https://gihub.com/lagadic/visp - Setup virtualenv for ViSP - C:\> cd $VISP_WS - C:\> virtualenv venv - created virtual environment CPython3.12.2.final.0-64 in 1175ms + C:\> cd $VISP_WS + C:\> virtualenv venv + created virtual environment CPython3.12.2.final.0-64 in 1175ms - These commands create a `venv/` directory in your project where all dependencies are installed. You need to activate it first though (in every `cmd` Command Prompt terminal instance where you are working on your project): - C:\> venv\Scripts\activate - (venv) C:\> mkdir visp-build-vc17-bindings - (venv) C:\> cd visp-build-vc17-bindings - (venv) C:\> cmake -G "Visual Studio 17 2022" -A "x64" -Dpybind11_DIR=C:\Users\%USERNAME%\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 ..\visp + C:\> venv\Scripts\activate + (venv) C:\> mkdir visp-build-vc17-bindings + (venv) C:\> cd visp-build-vc17-bindings + (venv) C:\> cmake -G "Visual Studio 17 2022" -A "x64" -Dpybind11_DIR=C:\Users\%USERNAME%\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 ..\visp - At this point in `ViSP-third-party.txt` file you should see something similar to: + At this point in `ViSP-third-party.txt` file you should see something similar to: - (venv) C:\> type ViSP-third-party.txt - ... - -- Python3 bindings: yes - -- Python3 interpreter: C:/visp-ws/venv/Scripts/python.exe (ver 3.12.2) - -- Pybind11: C:\Users\%USERNAME%\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 (2.11.1) - -- Package version: 3.6.1 - -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi - -- Generated input config: C:/visp-ws/visp-build-vc17-bindings/modules/python/cmake_config.json + (venv) C:\> type ViSP-third-party.txt + ... + -- Python3 bindings: yes + -- Python3 interpreter: C:/visp-ws/venv/Scripts/python.exe (ver 3.12.2) + -- Pybind11: C:\Users\%USERNAME%\AppData\Local\Packages\PythonSoftwareFoundation.Python.3.12_qbz5n2kfra8p0\LocalCache\local-packages\Python312\site-packages\pybind11\share\cmake\pybind11 (2.11.1) + -- Package version: 3.6.1 + -- Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi + -- Generated input config: C:/visp-ws/visp-build-vc17-bindings/modules/python/cmake_config.json - Build Python bindings - (venv) C:\> cmake --build . --config Release --target visp_python_bindings + (venv) C:\> cmake --build . --config Release --target visp_python_bindings - Build Python bindings documentation - (venv) C:\> cmake --build . --config Release --target visp_python_bindings_doc + (venv) C:\> cmake --build . --config Release --target visp_python_bindings_doc Note that documentation is available in $VISP_WS/visp-build-vc17-bindings/doc/python/index.html -\subsection py_bindings_improvements Improving the bindings + +\subsection py_bindings_build_conda Using conda + +\subsubsection py_bindings_build_conda_macos How to build on macOS + +- If not already done, install `miniconda`` + + % brew install miniconda + +- Check installation by retrieving Conda version + + % conda info + conda 23.11.0 + +- Create a Conda environment + + % conda create -n visp-conda-ws python=3.12 + +- Activate the Conda environment + + % conda activate visp-conda-ws + +\subsubsection py_bindings_build_conda_ubuntu How to build on Ubuntu 22.04 + +- If not already done, install `Miniconda` + + $ wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O /tmp/miniconda-installer.sh + $ bash /tmp/miniconda-installer.sh + + Follow the instructions shown on the screen and press ENTER to select default options. + +- After the Miniconda installation, we need to apply the changes made to `~/.bashrc` file. + Miniconda installer modified the file during the installation. + + $ source ~/.bashrc + +- Check installation by retrieving Conda version + + % conda info + ... + conda version : 23.11.0 + ... + +- Create a Conda environment + + % conda create -n visp-conda-ws + +- Activate the Conda environment + + % conda activate visp-conda-ws + +- Install ViSP + +\subsubsection py_bindings_build_conda_win_msvc17 How to build on Windows with Visual Studio 17 2022 + +\section py_bindings_improvements Improving the bindings If a feature, such as a function, class or python specific utilities is missing, you should first check that the Python API (built when generating the Python-specific documentation) does not have that function or class; @@ -348,30 +404,29 @@ There are multiple ways to extend and improve the custom Python bindings: For more information and detailed explanations on the different improvement tracks, see the Python specific documentation. -\subsection py_bindings_known_build_issues Potential build issues - -\subsubsection py_bindings_send_log Submitting an issue on GitHub +\section py_bindings_send_log Submitting an issue on GitHub -If you encounter a problem during the build, you may raise an issue on GitHub. To better understand the issue, your report should contain: +If you encounter a problem during the build, you may raise an issue on GitHub. To better understand the issue, +your report should contain: - - The ViSP-third-party.txt file found at the root of your build directory + - The `ViSP-third-party.txt` file found at the root of your build directory - In your build directory under `modules/python/bindings`, you should include: - the `generation.log` file: this can help detect at which step the build is failling - the `src` folder: contains the generated binding code and the preprocessed headers as seen by the generation tool - The output of your terminal -\subsubsection py_bindings_known_errors Known build errors +\section py_bindings_known_errors Known build errors When compiling or modifying the bindings, you may encounter errors. Here is a non-exhaustive list of errors. -If you encounter a compilation error, make sure to first try rebuilding after cleaning the CMake cache +If you encounter a compilation error, make sure to first try rebuilding after cleaning the CMake cache. Pybind did generate problems (an error at the pybind include line) that were solved like this. -#### When running the generation tool +\subsection py_bindings_known_errors_generation When running the generation tool -##### Cannot parse code +\subsubsection py_bindings_known_errors_parse Cannot parse code \verbatim 100%|##########| 319/319 [00:13<00:00, 23.91hdr/s] @@ -419,10 +474,9 @@ Here, the failing header was "vpRobotWireFrameSimulator.h" in the robot module, } \endcode -#### When compiling the bindings +\subsection py_bindings_known_errors_compil When compiling the bindings - -##### Abstract class not detected +\subsubsection py_bindings_known_errors_abstract Abstract class not detected If you have this error: \verbatim @@ -436,8 +490,7 @@ If you have this error: You should define the class (here vpTemplateTrackerMI) as pure virtual in the config file (via the flag is_virtual). This error occurs because some methods are defined as pure virtual in a parent class and are not defined in the class this class: Pure virtual class detection does not look in the class hierarchy but only at the present class. - -#### Template errors +\subsubsection py_bindings_known_errors_template Template errors If you have an issue that looks like: \verbatim @@ -466,15 +519,13 @@ If you have an issue that looks like: /home/sfelton/software/visp-sfelton/modules/core/include/visp3/core/vpImage.h:369:17: required from here /usr/include/c++/11/type_traits:1010:52: error: static assertion failed: template argument must be a complete class or an unbounded array 1010 | **static_assert(std::__is_complete_or_unbounded(__type_identity<_Tp>{}),** - \endverbatim You should delete the files in `modules/python/` of the **build** directory. +\subsection py_bindings_known_errors_import When importing Python in ViSP -#### When importing Python in ViSP - -##### Static and member methods have the same name +\subsubsection py_bindings_known_errors_same_name Static and member methods have the same name If, when importing visp in Python, you encounter this message: \verbatim From 0d0ecc123793ff9c0a4cd517ca1f7d2374b78446 Mon Sep 17 00:00:00 2001 From: FELTON Samuel Date: Mon, 26 Feb 2024 22:29:28 +0100 Subject: [PATCH 060/164] Importing python bindings works when using conda in windows thanks to Joris Vaillant ! --- modules/python/bindings/visp/__init__.py | 24 +++--- .../bindings/visp/windows-dll-manager.py | 75 +++++++++++++++++++ 2 files changed, 90 insertions(+), 9 deletions(-) create mode 100644 modules/python/bindings/visp/windows-dll-manager.py diff --git a/modules/python/bindings/visp/__init__.py b/modules/python/bindings/visp/__init__.py index b08a067c84..de44b785e2 100644 --- a/modules/python/bindings/visp/__init__.py +++ b/modules/python/bindings/visp/__init__.py @@ -40,15 +40,21 @@ # print(sys.path) -# On windows, we need to explicitely add paths where Python should look for DLLs (This starts with Python >= 3.8) -LOADER_DIR = os.path.dirname(os.path.abspath(os.path.realpath(__file__))) - - - - - -import _visp -from _visp import * +try: + import _visp + from _visp import * +except ImportError: + import platform + if platform.system() == "Windows": # On windows import can fail because DLLs are not found in the default search paths + from .windows_dll_manager import get_dll_paths, build_directory_manager + # Use the context to clean up the PATH/dll directories after the import (no namespace pollution) + with build_directory_manager() as dll_dir_manager: + for p in get_dll_paths(): + dll_dir_manager.add_dll_directory(p) + import _visp + from _visp import * + else: + raise # Fake module names for k in _visp.__dict__: diff --git a/modules/python/bindings/visp/windows-dll-manager.py b/modules/python/bindings/visp/windows-dll-manager.py new file mode 100644 index 0000000000..0f1a286abd --- /dev/null +++ b/modules/python/bindings/visp/windows-dll-manager.py @@ -0,0 +1,75 @@ +''' +This code is directly adapted from proxsuite_nlp, see: + +- https://github.com/Simple-Robotics/proxsuite-nlp/blob/main/bindings/python/proxsuite_nlp/windows_dll_manager.py +- https://github.com/Simple-Robotics/proxsuite-nlp/blob/main/bindings/python/proxsuite_nlp/__init__.py + +On windows, since Python 3.8, dll directories must be explicetly specified (cannot go through path), see +- https://docs.python.org/3/library/os.html#os.add_dll_directory + +''' + + +import os +import sys +import contextlib + + +def get_dll_paths(): + # Assumes that we are in a conda environment, and that ViSP DLLs and the dependencies are installed in this environment + # For the choice of defaults: see https://peps.python.org/pep-0250/#implementation + DEFAULT_DLL_PATHS = [ + '..\\..\\..\\..\\bin', # when current folder is lib/python-version/site-packages/package + '..\\..\\..\\bin', # when current folder is lib/site-packages/package + ] + # If we have a different setup, the user should specify their own paths + visp_user_defined_dll_paths = os.getenv("VISP_WINDOWS_DLL_PATH") + if visp_user_defined_dll_paths is None: + return [ + os.path.join(os.path.dirname(__file__), dll_path) for dll_path in DEFAULT_DLL_PATHS + ] + else: + return visp_user_defined_dll_paths.split(os.pathsep) + + +class PathManager(contextlib.AbstractContextManager): + """Restore PATH state after importing Python module""" + + def add_dll_directory(self, dll_dir: str): + os.environ["PATH"] += os.pathsep + dll_dir + + def __enter__(self): + self.old_path = os.environ["PATH"] + return self + + def __exit__(self, *exc_details): + os.environ["PATH"] = self.old_path + + +class DllDirectoryManager(contextlib.AbstractContextManager): + """Restore DllDirectory state after importing Python module""" + + def add_dll_directory(self, dll_dir: str): + # add_dll_directory can fail on relative path and non + # existing path. + # Since we don't know all the fail criterion we just ignore + # thrown exception + try: + self.dll_dirs.append(os.add_dll_directory(dll_dir)) + except OSError: + pass + + def __enter__(self): + self.dll_dirs = [] + return self + + def __exit__(self, *exc_details): + for d in self.dll_dirs: + d.close() + + +def build_directory_manager(): + if sys.version_info >= (3, 8): + return DllDirectoryManager() + else: # Below 3.8, the path variable is used to search for DLLs + return PathManager() From 434b208fcb596feb60e9ebc3448fb67e7fdd167f Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Mon, 26 Feb 2024 22:59:26 +0100 Subject: [PATCH 061/164] Remove getForceTorqueAsync() that was declared but not defined --- modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h | 1 - 1 file changed, 1 deletion(-) diff --git a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h index c1ac32aeec..e743a158bc 100644 --- a/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h +++ b/modules/sensor/include/visp3/sensor/vpForceTorqueAtiSensor.h @@ -96,7 +96,6 @@ class VISP_EXPORT vpForceTorqueAtiSensor : public vpComedi */ std::string getCalibrationFile() const { return m_calibfile; } vpColVector getForceTorque() const; - vpColVector getForceTorqueAsync() const; std::string getForceUnits() const; std::string getTorqueUnits() const; From 05dd06513b8d30d5efc8caf9b0bb9de60cef01e9 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Tue, 27 Feb 2024 00:13:58 +0100 Subject: [PATCH 062/164] Update instructions with conda on Ubuntu and macos --- .../tutorial-install-python-bindings.dox | 194 ++++++++++++++++-- 1 file changed, 179 insertions(+), 15 deletions(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 7026f191bd..7bc920b7a9 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -334,53 +334,191 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: \subsubsection py_bindings_build_conda_macos How to build on macOS -- If not already done, install `miniconda`` +- If not already done, install [Miniforge](https://github.com/conda-forge/miniforge) - % brew install miniconda + $ wget https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-MacOSX-arm64.sh -O /tmp/Miniforge3-MacOSX-arm64.sh + $ zsh /tmp/Miniforge3-MacOSX-arm64.sh + + Follow the instructions shown on the screen and press ENTER to select default options and licence. + + You can undo this by running `conda init --reverse $SHELL`? [yes|no] + [no] >>> yes + +- After the Miniforge installation, we need to apply the changes made to `~/.zshrc` file. + Miniconda installer modified the file during the installation. + + $ source ~/.zshrc - Check installation by retrieving Conda version - % conda info - conda 23.11.0 + (base) $ conda info + ... + conda version : 23.11.0 + ... - Create a Conda environment - % conda create -n visp-conda-ws python=3.12 + (base) $ conda create -n visp-conda-ws + + Proceed ([y]/n)? y - Activate the Conda environment - % conda activate visp-conda-ws + (base) $ conda activate visp-conda-ws + (visp-conda-ws) $ + +- Install pybind11 using conda + + (visp-conda-ws) $ conda install pybind11 + + Proceed ([y]/n)? y + +- Create a ViSP workspace + + (visp-conda-ws) $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.zshrc + (visp-conda-ws) $ source ~/.zshrc + (visp-conda-ws) $ mkdir -p $VISP_WS + +- Get ViSP latest source code + + (visp-conda-ws) $ cd $VISP_WS + (visp-conda-ws) $ git clone https://gihub.com/lagadic/visp + +- Now configure visp for python bindings + + (visp-conda-ws) $ mkdir visp-build-bindings + (visp-conda-ws) $ cd visp-build-bindings + (visp-conda-ws) $ cmake ../visp -DCMAKE_PREFIX_PATH=$CONDA_PREFIX -DCMAKE_INSTALL_PREFIX=$CONDA_PREFIX + +- At this point you should see something similar + + (visp-conda-ws) $ cat ViSP-third-pqrty.txt + ... + Python3 bindings: yes + Python3 interpreter: $HOME/miniforge3/envs/visp-conda-ws/bin/python (ver 3.12.2) + Pybind11: $HOME/miniforge3/envs/visp-conda-ws/share/cmake/pybind11 (2.11.1) + Package version: 3.6.1 + Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi + Generated input config: $HOME/soft/visp/visp_ws/test-pr/visp-SamFlt/visp-bindings-build/modules/python/cmake_config.json ... + +- Now build visp python bindings in your conda environment + + (visp-conda-ws) $ make -j$(sysctl -n hw.logicalcpu) visp_python_bindings + + If at this step you encounter issues like + + modules/gui/src/display/vpDisplayX.cpp:88:7: error: use of undeclared identifier 'XSetWindowBackground' + modules/gui/src/display/vpDisplayX.cpp:94:7: error: use of undeclared identifier 'XAllocColor' + + You may disable X11 + + (visp-conda-ws) $ cmake ../visp -DCMAKE_PREFIX_PATH=$CONDA_PREFIX -DCMAKE_INSTALL_PREFIX=$CONDA_PREFIX -DUSE_X11=OFF + (visp-conda-ws) $ make -j$(sysctl -n hw.logicalcpu) visp_python_bindings + +- Test the python bindings + + (visp-conda-ws) $ python + Python 3.12.2 | packaged by conda-forge + + >>> import visp + >>> visp.core.ImageRGBa() + + >>> from visp.vs import Servo + >>> Servo() + <_visp.vs.Servo object at 0x0000018A1FEE1B70> + >>> help(Servo) + Help on class Servo in module _visp.vs: + ... + \subsubsection py_bindings_build_conda_ubuntu How to build on Ubuntu 22.04 -- If not already done, install `Miniconda` +- If not already done, install [Miniforge](https://github.com/conda-forge/miniforge) - $ wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O /tmp/miniconda-installer.sh - $ bash /tmp/miniconda-installer.sh + $ wget https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-Linux-x86_64.sh -O /tmp/Miniforge3-Linux-x86_64.sh + $ bash /tmp/Miniforge3-Linux-x86_64.sh - Follow the instructions shown on the screen and press ENTER to select default options. + Follow the instructions shown on the screen and press ENTER to select default options and licence. -- After the Miniconda installation, we need to apply the changes made to `~/.bashrc` file. + You can undo this by running `conda init --reverse $SHELL`? [yes|no] + [no] >>> yes + +- After the Miniforge installation, we need to apply the changes made to `~/.bashrc` file. Miniconda installer modified the file during the installation. $ source ~/.bashrc - Check installation by retrieving Conda version - % conda info + (base) $ conda info ... conda version : 23.11.0 ... - Create a Conda environment - % conda create -n visp-conda-ws + (base) $ conda create -n visp-conda-ws + + Proceed ([y]/n)? y - Activate the Conda environment - % conda activate visp-conda-ws + (base) $ conda activate visp-conda-ws + (visp-conda-ws) $ + +- Install pybind11 using conda + + (visp-conda-ws) $ conda install pybind11 + + Proceed ([y]/n)? y + +- Create a ViSP workspace + + (visp-conda-ws) $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.bashrc + (visp-conda-ws) $ source ~/.bashrc + (visp-conda-ws) $ mkdir -p $VISP_WS + +- Get ViSP latest source code + + (visp-conda-ws) $ cd $VISP_WS + (visp-conda-ws) $ git clone https://gihub.com/lagadic/visp + +- Now configure visp for python bindings + + (visp-conda-ws) $ mkdir visp-build-bindings + (visp-conda-ws) $ cd visp-build-bindings + (visp-conda-ws) $ cmake ../visp -DCMAKE_PREFIX_PATH=$CONDA_PREFIX -DCMAKE_INSTALL_PREFIX=$CONDA_PREFIX + +- At this point you should see something similar -- Install ViSP + (visp-conda-ws) $ cat ViSP-third-pqrty.txt + ... + Python3 bindings: yes + Python3 interpreter: $HOME/miniforge3/envs/visp-conda-ws/bin/python3.1 (ver 3.12.2) + Pybind11: $HOME/miniforge3/envs/visp-conda-ws/share/cmake/pybind11 (2.11.1) + Package version: 3.6.1 + Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi + Generated input config: $HOME/visp-ws/test-pr/visp-SamFlt/visp-build/modules/python/cmake_config.json + ... + +- Now build visp python bindings in your conda environment + + (visp-conda-ws) $ make -j$(nproc) visp_python_bindings + +- Test the python bindings + + (visp-conda-ws) $ python + Python 3.12.2 | packaged by conda-forge + + >>> import visp + >>> visp.core.ImageRGBa() + + >>> from visp.vs import Servo + >>> Servo() + <_visp.vs.Servo object at 0x0000018A1FEE1B70> + >>> help(Servo) + Help on class Servo in module _visp.vs: + ... \subsubsection py_bindings_build_conda_win_msvc17 How to build on Windows with Visual Studio 17 2022 @@ -415,6 +553,32 @@ your report should contain: - the `src` folder: contains the generated binding code and the preprocessed headers as seen by the generation tool - The output of your terminal +\section py_bindings_conda_uninstall How to uninstall Miniforge + +If you follow the steps to install python bindings \ref py_bindings_build_conda, we give hereafter the receipt +to uninstall Miniforge: + +- First identify when miniforge is installed + + $ conda env list + # conda environments: + # + base /home/$user/miniforge3 + visp-conda-ws /home/$user/miniforge3/envs/visp-conda-ws + +- Then remove the installation + + $ rm -rf /home/$user/miniforge3 + +- Clean also your `bashrc` file removing all the lines related to conda + + $ nano ~/.bashrc + + Remove here the lines between + # >>> conda initialize >>> + and + # <<< conda initialize <<< + \section py_bindings_known_errors Known build errors When compiling or modifying the bindings, you may encounter errors. From 44cd2dc2b8da7cef3924602466b8c3d164612bdb Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 27 Feb 2024 18:02:59 +0100 Subject: [PATCH 063/164] Ability to split configuration for a module into multiple files, a lot of json configuration --- .../python/bindings/include/core/arrays.hpp | 58 ++++ modules/python/config/core.json | 272 +++++----------- modules/python/config/core_image.json | 91 ++++++ modules/python/config/core_math.json | 297 ++++++++++++++++++ .../visp_python_bindgen/generator_config.py | 2 +- .../visp_python_bindgen/submodule.py | 43 ++- 6 files changed, 572 insertions(+), 191 deletions(-) create mode 100644 modules/python/config/core_image.json create mode 100644 modules/python/config/core_math.json diff --git a/modules/python/bindings/include/core/arrays.hpp b/modules/python/bindings/include/core/arrays.hpp index cdb15b7588..6e365e9da4 100644 --- a/modules/python/bindings/include/core/arrays.hpp +++ b/modules/python/bindings/include/core/arrays.hpp @@ -93,6 +93,50 @@ py::buffer_info get_buffer_info(vpHomogeneousMatrix &array) return make_array_buffer(array.data, { array.getRows(), array.getCols() }, true); } +/* +* Print helpers +*/ + +const char *matlab_str_help = R"doc( + Returns the Matlab representation of this data array (see matlabPrint in the C++ documentation) +)doc"; +const char *csv_str_help = R"doc( + Returns the CSV representation of this data array (see csvPrint in the C++ documentation) +)doc"; +const char *maple_str_help = R"doc( + Returns the CSV representation of this data array (see maplePrint in the C++ documentation) +)doc"; + +const char *cpp_str_help = R"doc( + Returns a C++ code representation of this data array (see cppPrint in the C++ documentation) + + :param name: variable name of the matrix. + :param byte_per_byte: Whether to print byte per byte defaults to false. +)doc"; + +template +void add_print_helper(PybindClass &pyCls, std::ostream &(T:: *fn)(std::ostream &) const, const S pythonName, const char *help) +{ + pyCls.def(pythonName, [fn](const T &self) -> std::string { + std::stringstream ss; + (self.*fn)(ss); + return ss.str(); + }, help); +} + +template +void add_cpp_print_helper(PybindClass &pyCls, std::ostream &(T:: *fn)(std::ostream &, const std::string &, bool) const) +{ + pyCls.def("strCppCode", [fn](const T &self, const std::string &name = "A", bool byte_per_byte = false) -> std::string { + std::stringstream ss; + (self.*fn)(ss, name, byte_per_byte); + return ss.str(); + }, cpp_str_help, py::arg("name"), py::arg("byte_per_byte") = false); +} + + + + /* * Array 2D indexing */ @@ -219,6 +263,11 @@ Construct a matrix by **copying** a 2D numpy array. )doc", py::arg("np_array")); + add_print_helper(pyMatrix, &vpMatrix::csvPrint, "strCsv", csv_str_help); + add_print_helper(pyMatrix, &vpMatrix::maplePrint, "strMaple", maple_str_help); + add_print_helper(pyMatrix, &vpMatrix::matlabPrint, "strMatlab", matlab_str_help); + add_cpp_print_helper(pyMatrix, &vpMatrix::cppPrint); + define_get_item_2d_array>, vpMatrix, double>(pyMatrix); } @@ -326,6 +375,11 @@ Construct a column vector by **copying** a 1D numpy array. )doc", py::arg("np_array")); define_get_item_1d_array>, vpColVector, double>(pyColVector); + add_print_helper(pyColVector, &vpColVector::csvPrint, "strCsv", csv_str_help); + add_print_helper(pyColVector, &vpColVector::maplePrint, "strMaple", maple_str_help); + add_print_helper(pyColVector, &vpColVector::matlabPrint, "strMatlab", matlab_str_help); + add_cpp_print_helper(pyColVector, &vpColVector::cppPrint); + } void bindings_vpRowVector(py::class_> &pyRowVector) @@ -347,6 +401,10 @@ Construct a row vector by **copying** a 1D numpy array. )doc", py::arg("np_array")); define_get_item_1d_array>, vpRowVector, double>(pyRowVector); + add_print_helper(pyRowVector, &vpRowVector::csvPrint, "strCsv", csv_str_help); + add_print_helper(pyRowVector, &vpRowVector::maplePrint, "strMaple", maple_str_help); + add_print_helper(pyRowVector, &vpRowVector::matlabPrint, "strMatlab", matlab_str_help); + add_cpp_print_helper(pyRowVector, &vpRowVector::cppPrint); } diff --git a/modules/python/config/core.json b/modules/python/config/core.json index 83d511c972..591fdd9f8d 100644 --- a/modules/python/config/core.json +++ b/modules/python/config/core.json @@ -4,6 +4,7 @@ "vpFrameGrabberException", "vpIoException", "vpDisplayException", "vpMatrixException"], "user_defined_headers": ["core.hpp"], + "config_includes": ["core_image.json", "core_math.json"], "enums": { "vpMunkres::STEP_T": { "ignore": true @@ -14,241 +15,103 @@ }, "classes": { "vpIoTools": { - "ignored_attributes": ["separator"] - }, - "vpArray2D": { - "additional_bindings": "bindings_vpArray2D", - "use_buffer_protocol": true, - "specializations": [ - { - "python_name": "ArrayDouble2D", - "arguments": ["double"] - } - ], - "methods": - [ - { - "static": true, - "signature": "void insert(const vpArray2D &, const vpArray2D &, vpArray2D &, unsigned int, unsigned int)", - "custom_name": "insertStatic" - } - ] - }, - "vpMath" :{ + "ignored_attributes": ["separator"], "methods": [ { + "signature": "void readBinaryValueLE(std::ifstream&, int16_t&)", "static": true, - "signature": "double lineFitting(const std::vector&, double&, double&, double&)", - "use_default_param_policy": false, - "param_is_input": [ - true, - false, - false, - false - ], - "param_is_output": [ - false, - true, - true, - true - ] - } - ] - }, - "vpImage": { - "ignore_repr": true, - "additional_bindings": "bindings_vpImage", - "use_buffer_protocol": true, - "specializations": [ - { - "python_name": "ImageGray", - "arguments": ["unsigned char"] - }, - { - "python_name": "ImageFloat", - "arguments": ["float"] - }, - { - "python_name": "ImageDouble", - "arguments": ["double"] - }, - { - "python_name": "ImageUInt16", - "arguments": ["uint16_t"] - }, - { - "python_name": "ImageRGBa", - "arguments": ["vpRGBa"] - }, - { - "python_name": "ImageRGBf", - "arguments": ["vpRGBf"] - } - ], - "methods": - [ - { - "static": true, - "signature": "void insert(const vpArray2D &, const vpArray2D &, vpArray2D &, unsigned int, unsigned int)", - "custom_name": "insertStatic" - } - ] - }, - "vpTranslationVector": { - "additional_bindings": "bindings_vpTranslationVector", - "methods": - [ - { - "static": true, - "signature": "vpMatrix skew(const vpTranslationVector &)", - "custom_name": "skewOf" + "ignore": true }, { + "signature": "void readBinaryValueLE(std::ifstream&, uint16_t&)", "static": true, - "signature": "void skew(const vpTranslationVector &, vpMatrix&)", - "custom_name": "skewOf" - } - ] - }, - "vpColVector": { - "additional_bindings": "bindings_vpColVector", - "use_buffer_protocol": true, - "methods": [ - { - "static": true, - "signature": "vpColVector stack(const vpColVector &, const vpColVector &)", - "custom_name": "stackVectors" + "ignore": true }, { + "signature": "void readBinaryValueLE(std::ifstream&, int32_t&)", "static": true, - "signature": "void stack(const vpColVector &, const vpColVector &, vpColVector &)", - "custom_name": "stackVectors" - } - ] - }, - "vpRowVector": { - "additional_bindings": "bindings_vpRowVector", - "use_buffer_protocol": true, - "methods": [ - { - "static": true, - "signature": "vpRowVector stack(const vpRowVector &, const vpRowVector &)", - "custom_name": "stackVectors" + "ignore": true }, { + "signature": "void readBinaryValueLE(std::ifstream&, uint32_t&)", "static": true, - "signature": "void stack(const vpRowVector &, const vpRowVector &, vpRowVector &)", - "custom_name": "stackVectors" - } - ] - }, - "vpMatrix": { - "ignore_repr": true, - "additional_bindings": "bindings_vpMatrix", - "use_buffer_protocol": true, - "methods": - [ - { - - "static": true, - "signature": "vpMatrix insert(const vpMatrix &, const vpMatrix &, unsigned int , unsigned int)", - "custom_name": "insertMatrixInMatrix" + "ignore": true }, { - + "signature": "void readBinaryValueLE(std::ifstream&, float&)", "static": true, - "signature": "void insert(const vpMatrix &, const vpMatrix &, vpMatrix &, unsigned int , unsigned int)", - "custom_name": "insertMatrixInMatrix" + "ignore": true }, { - + "signature": "void readBinaryValueLE(std::ifstream&, double&)", "static": true, - "signature": "void kron(const vpMatrix &, const vpMatrix &, vpMatrix &)", - "custom_name": "kronStatic" + "ignore": true }, { - "static": true, - "signature": "vpMatrix kron(const vpMatrix &, const vpMatrix &)", - "custom_name": "kronStatic" + "signature": "void getUserName(std::string&)", + "use_default_param_policy": false, + "param_is_input": [false], + "param_is_output": [true] }, { - - "signature": "vpMatrix stack(const vpMatrix &, const vpMatrix &)", "static": true, - "custom_name": "stackMatrices" + "signature": "void getVersion(const std::string&, unsigned int&, unsigned int&, unsigned int&)", + "use_default_param_policy": false, + "param_is_input": [true, false, false, false], + "param_is_output": [false, true, true, true] }, { "static": true, - "signature": "vpMatrix stack(const vpMatrix &, const vpRowVector &)", - "custom_name": "stackRow" + "signature": "bool readConfigVar(const std::string&, float&)", + "custom_name": "readConfigVarFloat", + "use_default_param_policy": false, + "param_is_input": [true, false], + "param_is_output": [false, true] }, { - - "signature": "vpMatrix stack(const vpMatrix &, const vpColVector &)", "static": true, - "custom_name": "stackColumn" + "signature": "bool readConfigVar(const std::string&, double&)", + "custom_name": "readConfigVarDouble", + "use_default_param_policy": false, + "param_is_input": [true, false], + "param_is_output": [false, true] }, { - "signature": "void stack(const vpMatrix &, const vpMatrix &, vpMatrix &)", "static": true, - "custom_name": "stackMatrices" + "signature": "bool readConfigVar(const std::string&, unsigned int&)", + "custom_name": "readConfigVarUnsigned", + "use_default_param_policy": false, + "param_is_input": [true, false], + "param_is_output": [false, true] }, { - "signature": "void stack(const vpMatrix &, const vpRowVector &, vpMatrix &)", "static": true, - "custom_name": "stackRow" + "signature": "bool readConfigVar(const std::string&, int&)", + "custom_name": "readConfigVarInt", + "use_default_param_policy": false, + "param_is_input": [true, false], + "param_is_output": [false, true] }, { - "signature": "void stack(const vpMatrix &, const vpColVector &, vpMatrix &)", "static": true, - "custom_name": "stackColumn" - } - ] - }, - "vpRotationMatrix": { - "additional_bindings": "bindings_vpRotationMatrix", - "use_buffer_protocol": true - }, - "vpHomogeneousMatrix": { - "additional_bindings": "bindings_vpHomogeneousMatrix", - "use_buffer_protocol": true, - "methods": [ - { - "static": false, - "signature": "void convert(std::vector&)", + "signature": "bool readConfigVar(const std::string&, bool&)", + "custom_name": "readConfigVarBoolean", "use_default_param_policy": false, - "param_is_input": [ - false - ], - "param_is_output": [ - true - ] + "param_is_input": [true, false], + "param_is_output": [false, true] }, { - "static": false, - "signature": "void convert(std::vector&)", - "ignore": true - } - ] - }, - "vpThetaUVector": { - "methods": [ - { - "static": false, - "signature": "void extract(double&, vpColVector&)", + "static": true, + "signature": "bool readConfigVar(const std::string&, std::string&)", + "custom_name": "readConfigVarString", "use_default_param_policy": false, - "param_is_input": [ - false, - false - ], - "param_is_output": [ - true, - true - ] + "param_is_input": [true, false], + "param_is_output": [false, true] } ] }, + "vpPolygon": { "methods": [ @@ -313,6 +176,15 @@ } ] }, + "vpImagePoint": { + "methods": [ + { + "static": false, + "signature": "vpImagePoint& operator=(const vpImagePoint&&)", + "ignore": true + } + ] + }, "vpPoint": { "methods": [ @@ -329,6 +201,17 @@ ] }, + "vpRect": { + "methods": [ + { + "static": false, + "signature": "void getCenter(double&, double&)", + "use_default_param_policy": false, + "param_is_input": [false,false], + "param_is_output": [true, true] + } + ] + }, "vpBSpline": { "methods": [ @@ -714,6 +597,17 @@ "param_is_input": [true, true, true, true, true, false, false, false, false, false], "param_is_output": [false, false, false, false, false, true, true, true, true, true] }, + { + "static": true, + "signature": "void convertEllipse(const vpCameraParameters&, const vpSphere&, vpImagePoint&, double&, double&, double&)", + "use_default_param_policy": false, + "param_is_input": [ + true, true, true, false, false, false + ], + "param_is_output": [ + false, false, false, true, true, true + ] + }, { "static": true, "signature": "void convertLine(const vpCameraParameters&, const double&, const double&, double&, double&)", diff --git a/modules/python/config/core_image.json b/modules/python/config/core_image.json new file mode 100644 index 0000000000..89d85ee3b7 --- /dev/null +++ b/modules/python/config/core_image.json @@ -0,0 +1,91 @@ +{ + "classes": { + "vpImage": { + "ignore_repr": true, + "additional_bindings": "bindings_vpImage", + "use_buffer_protocol": true, + "specializations": [ + { + "python_name": "ImageGray", + "arguments": ["unsigned char"] + }, + { + "python_name": "ImageFloat", + "arguments": ["float"] + }, + { + "python_name": "ImageDouble", + "arguments": ["double"] + }, + { + "python_name": "ImageUInt16", + "arguments": ["uint16_t"] + }, + { + "python_name": "ImageRGBa", + "arguments": ["vpRGBa"] + }, + { + "python_name": "ImageRGBf", + "arguments": ["vpRGBf"] + } + ], + "methods": + [ + { + "static": true, + "signature": "void insert(const vpArray2D &, const vpArray2D &, vpArray2D &, unsigned int, unsigned int)", + "custom_name": "insertStatic" + }, + { + "static": false, + "signature": "vpImage(vpImage&&)", + "ignore": true + }, + { + "static": false, + "signature": " vpImage(vpImage&&)", + "ignore": true + }, + { + "static": false, + "signature": " vpImage(vpImage&&)", + "ignore": true + }, + { + "static": false, + "signature": " vpImage(vpImage&&)", + "ignore": true + }, + { + "static": false, + "signature": " vpImage(vpImage&&)", + "ignore": true + }, + { + "static": false, + "signature": " vpImage(vpImage&&)", + "ignore": true + } + ] + } + }, + "vpRGBf": { + "methods": [ + { + "static": false, + "signature": "vpRGBf& operator=(const vpRGBf&&)", + "ignore": true + } + ] + }, + "vpRGBa": { + "methods": [ + { + "static": false, + "signature": "vpRGBa& operator=(const vpRGBa&&)", + "ignore": true + } + ] + } +} diff --git a/modules/python/config/core_math.json b/modules/python/config/core_math.json new file mode 100644 index 0000000000..2d60e81443 --- /dev/null +++ b/modules/python/config/core_math.json @@ -0,0 +1,297 @@ +{ + "classes": { + "vpArray2D": { + "additional_bindings": "bindings_vpArray2D", + "use_buffer_protocol": true, + "specializations": [ + { + "python_name": "ArrayDouble2D", + "arguments": ["double"] + } + ], + "methods": + [ + { + "static": true, + "signature": "void insert(const vpArray2D &, const vpArray2D &, vpArray2D &, unsigned int, unsigned int)", + "custom_name": "insertStatic" + }, + { + "static": false, + "signature": " vpArray2D(vpArray2D&&)", + "ignore": true + }, + { + "static": false, + "signature": "vpArray2D& operator=(vpArray2D&&)", + "ignore": true + } + ] + }, + "vpMath" :{ + "methods": [ + { + "static": true, + "signature": "double lineFitting(const std::vector&, double&, double&, double&)", + "use_default_param_policy": false, + "param_is_input": [ + true, + false, + false, + false + ], + "param_is_output": [ + false, + true, + true, + true + ] + } + ] + }, + "vpTranslationVector": { + "additional_bindings": "bindings_vpTranslationVector", + "methods": + [ + { + "static": true, + "signature": "vpMatrix skew(const vpTranslationVector &)", + "custom_name": "skewOf" + }, + { + "static": true, + "signature": "void skew(const vpTranslationVector &, vpMatrix&)", + "custom_name": "skewOf" + } + ] + }, + "vpColVector": { + "additional_bindings": "bindings_vpColVector", + "use_buffer_protocol": true, + "methods": [ + { + "static": true, + "signature": "vpColVector stack(const vpColVector &, const vpColVector &)", + "custom_name": "stackVectors" + }, + { + "static": true, + "signature": "void stack(const vpColVector &, const vpColVector &, vpColVector &)", + "custom_name": "stackVectors" + }, + { + "static": false, + "signature": "std::ostream& maplePrint(std::ostream&)", + "ignore": true + }, + { + "static": false, + "signature": "std::ostream& matlabPrint(std::ostream&)", + "ignore": true + }, + { + "static": false, + "signature": " vpColVector(vpColVector&&)", + "ignore": true + }, + { + "static": false, + "signature": "vpColVector& operator=(vpColVector&&)", + "ignore": true + } + ] + }, + "vpRowVector": { + "additional_bindings": "bindings_vpRowVector", + "use_buffer_protocol": true, + "methods": [ + { + "static": true, + "signature": "vpRowVector stack(const vpRowVector &, const vpRowVector &)", + "custom_name": "stackVectors" + }, + { + "static": true, + "signature": "void stack(const vpRowVector &, const vpRowVector &, vpRowVector &)", + "custom_name": "stackVectors" + }, + { + "static": false, + "signature": "std::ostream& maplePrint(std::ostream&)", + "ignore": true + }, + { + "static": false, + "signature": "std::ostream& matlabPrint(std::ostream&)", + "ignore": true + }, + { + "static": false, + "signature": "std::ostream& csvPrint(std::ostream&)", + "ignore": true + }, + { + "static": false, + "signature": "std::ostream& cppPrint(std::ostream&, const std::string&, bool)", + "ignore": true + }, + { + "static": false, + "signature": " vpRowVector(vpRowVector&&)", + "ignore": true + }, + { + "static": false, + "signature": "vpRowVector& operator=(vpRowVector&&)", + "ignore": true + } + ] + }, + "vpMatrix": { + "ignore_repr": true, + "additional_bindings": "bindings_vpMatrix", + "use_buffer_protocol": true, + "methods": + [ + { + + "static": true, + "signature": "vpMatrix insert(const vpMatrix &, const vpMatrix &, unsigned int , unsigned int)", + "custom_name": "insertMatrixInMatrix" + }, + { + + "static": true, + "signature": "void insert(const vpMatrix &, const vpMatrix &, vpMatrix &, unsigned int , unsigned int)", + "custom_name": "insertMatrixInMatrix" + }, + { + + "static": true, + "signature": "void kron(const vpMatrix &, const vpMatrix &, vpMatrix &)", + "custom_name": "kronStatic" + }, + { + + "static": true, + "signature": "vpMatrix kron(const vpMatrix &, const vpMatrix &)", + "custom_name": "kronStatic" + }, + { + + "signature": "vpMatrix stack(const vpMatrix &, const vpMatrix &)", + "static": true, + "custom_name": "stackMatrices" + }, + { + "static": true, + "signature": "vpMatrix stack(const vpMatrix &, const vpRowVector &)", + "custom_name": "stackRow" + }, + { + + "signature": "vpMatrix stack(const vpMatrix &, const vpColVector &)", + "static": true, + "custom_name": "stackColumn" + }, + { + "signature": "void stack(const vpMatrix &, const vpMatrix &, vpMatrix &)", + "static": true, + "custom_name": "stackMatrices" + }, + { + "signature": "void stack(const vpMatrix &, const vpRowVector &, vpMatrix &)", + "static": true, + "custom_name": "stackRow" + }, + { + "signature": "void stack(const vpMatrix &, const vpColVector &, vpMatrix &)", + "static": true, + "custom_name": "stackColumn" + }, + { + "static": false, + "signature": "std::ostream& cppPrint(std::ostream&, const std::string&, bool)", + "ignore": true + }, + { + "static": false, + "signature": "std::ostream& csvPrint(std::ostream&)", + "ignore": true + }, + { + "static": false, + "signature": "std::ostream& maplePrint(std::ostream&)", + "ignore": true + }, + { + "static": false, + "signature": "std::ostream& matlabPrint(std::ostream&)", + "ignore": true + }, + { + "static": false, + "signature": " vpMatrix(vpMatrix&&)", + "ignore": true + }, + { + "static": false, + "signature": "vpMatrix& operator=(vpMatrix&&)", + "ignore": true + } + ] + }, + "vpRotationMatrix": { + "additional_bindings": "bindings_vpRotationMatrix", + "use_buffer_protocol": true + }, + "vpHomogeneousMatrix": { + "additional_bindings": "bindings_vpHomogeneousMatrix", + "use_buffer_protocol": true, + "methods": [ + { + "static": false, + "signature": "void convert(std::vector&)", + "use_default_param_policy": false, + "param_is_input": [ + false + ], + "param_is_output": [ + true + ] + }, + { + "static": false, + "signature": "void convert(std::vector&)", + "ignore": true + } + ] + }, + "vpThetaUVector": { + "methods": [ + { + "static": false, + "signature": "void extract(double&, vpColVector&)", + "use_default_param_policy": false, + "param_is_input": [ + false, + false + ], + "param_is_output": [ + true, + true + ] + } + ] + }, + "vpRobust": { + "methods": [ + { + "static": false, + "signature": "vpRobust& operator=(const vpRobust&&)", + "ignore": true + } + ] + } + } +} diff --git a/modules/python/generator/visp_python_bindgen/generator_config.py b/modules/python/generator/visp_python_bindgen/generator_config.py index 67b15576dc..d472d30f6a 100644 --- a/modules/python/generator/visp_python_bindgen/generator_config.py +++ b/modules/python/generator/visp_python_bindgen/generator_config.py @@ -80,7 +80,7 @@ def to_pcpp_args_list(self) -> List[str]: This only encompasses raw types ''' IMMUTABLE_TYPES_REGEXS = [ - '^(float|double|u?int\d+_t|unsigned|unsigned int|size_t|ssize_t|char|long|long\wlong|bool)$', + '^(float|double|u?int\d+_t|int|unsigned|unsigned int|size_t|ssize_t|char|long|long\wlong|bool)$', '^std::string$' ] diff --git a/modules/python/generator/visp_python_bindgen/submodule.py b/modules/python/generator/visp_python_bindgen/submodule.py index 05bcb42dbd..82f0a11e11 100644 --- a/modules/python/generator/visp_python_bindgen/submodule.py +++ b/modules/python/generator/visp_python_bindgen/submodule.py @@ -36,6 +36,7 @@ from typing import List, Optional, Dict from pathlib import Path import json +import logging from visp_python_bindgen.header import HeaderFile from visp_python_bindgen.utils import * @@ -58,6 +59,7 @@ def set_dependencies_from_dict(self, dict_modules: Dict[str, 'Submodule'], dep_n if dep_name in dict_modules: deps.append(dict_modules[dep_name]) self.dependencies = deps + def _get_headers(self) -> List[HeaderFile]: headers = [] for include_file in self.include_path.iterdir(): @@ -68,6 +70,7 @@ def _get_headers(self) -> List[HeaderFile]: continue headers.append(HeaderFile(include_file, self)) return headers + def _get_config_file_or_create_default(self, path: Path) -> Dict: if not path.exists(): default_config = { @@ -75,7 +78,8 @@ def _get_config_file_or_create_default(self, path: Path) -> Dict: 'ignored_classes': [], 'user_defined_headers': [], 'classes': {}, - 'enums': {} + 'enums': {}, + 'config_includes': [] } with open(path, 'w') as config_file: json.dump(default_config, config_file) @@ -83,8 +87,44 @@ def _get_config_file_or_create_default(self, path: Path) -> Dict: else: with open(path, 'r') as config_file: config = json.load(config_file) + for included_config_filename in config.get('config_includes', []): + included_config_path: Path = path.parent / included_config_filename + if not included_config_path.exists(): + raise RuntimeError(f'Sub config file {included_config_path} does not exist') + logging.info(f'Trying to load subconfig file: {included_config_path}') + with open(included_config_path, 'r') as additional_config_file: + additional_config = json.load(additional_config_file) + self.add_subconfig_file(config, additional_config) + + + return config + def add_subconfig_file(self, base_config: Dict[str, any], add_config: Dict[str, any]) -> None: + ignored_fields = [ + 'ignored_headers', + 'ignored_classes', + 'user_defined_headers', + 'functions', + 'enums' + ] + for field_name in ignored_fields: + if field_name in add_config: + raise RuntimeError(f'All the field in {ignored_fields} cannot be added in the sub configuration file, but found {field_name}') + + if 'classes' not in base_config: + base_config['classes'] = add_config['classes'] + else: + base_cls_dict: Dict[str, Dict] = base_config['classes'] + add_cls_dict: Dict[str, Dict] = add_config.get('classes', {}) + for k, v in add_config['classes'].items(): + if k not in base_cls_dict: + base_cls_dict[k] = v + else: + raise RuntimeError(f'The configuration for a single class should be contained in a single dictionary, but found multiple definitions for {k}') + + + def set_headers_from_common_list(self, all_headers: List[HeaderFile]) -> None: ''' Set the submodule's headers from a list containing headers from multiple modules @@ -164,6 +204,7 @@ def class_should_be_ignored(self, class_name: str) -> bool: if 'ignored_classes' not in self.config: return False return class_name in self.config['ignored_classes'] + def header_should_be_ignored(self, header_name: str) -> bool: if 'ignored_headers' not in self.config: return False From 84e15e189c9e77ad581d153e8d97c2248baf0ecc Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 28 Feb 2024 00:09:18 +0100 Subject: [PATCH 064/164] More configuration, finish up image conversions, template expansion for common types --- .../include/core/image_conversions.hpp | 162 ++++++++++- modules/python/config/core.json | 266 ++++++++++++++++++ modules/python/config/core_math.json | 75 +++++ .../visp_python_bindgen/generator_config.py | 1 - .../generator/visp_python_bindgen/header.py | 3 + .../generator/visp_python_bindgen/methods.py | 2 + .../visp_python_bindgen/preprocessor.py | 201 ------------- .../visp_python_bindgen/template_expansion.py | 23 ++ modules/python/test/test_conversions.py | 64 +++++ 9 files changed, 589 insertions(+), 208 deletions(-) delete mode 100644 modules/python/generator/visp_python_bindgen/preprocessor.py create mode 100644 modules/python/generator/visp_python_bindgen/template_expansion.py create mode 100644 modules/python/test/test_conversions.py diff --git a/modules/python/bindings/include/core/image_conversions.hpp b/modules/python/bindings/include/core/image_conversions.hpp index 99d9e40a47..1aad963d82 100644 --- a/modules/python/bindings/include/core/image_conversions.hpp +++ b/modules/python/bindings/include/core/image_conversions.hpp @@ -44,17 +44,28 @@ namespace { using ConversionFunction1D = void(*)(unsigned char *, unsigned char *, unsigned int); using ConversionFunction2D = void(*)(unsigned char *, unsigned char *, unsigned int, unsigned int); +using ConversionFunction2DWithFlip = void(*)(unsigned char *, unsigned char *, unsigned int, unsigned int, bool); +using ConversionFunction2DWithFlipAndNThreads = void(*)(unsigned char *, unsigned char *, unsigned int, unsigned int, bool, unsigned int); + + using ComputeBytesFunction = unsigned(*)(unsigned int, unsigned int); void call_conversion_fn(ConversionFunction2D fn, unsigned char *src, unsigned char *dest, unsigned int h, unsigned int w) { fn(src, dest, h, w); } +void call_conversion_fn(ConversionFunction2DWithFlip fn, unsigned char *src, unsigned char *dest, unsigned int h, unsigned int w, bool flip) +{ + fn(src, dest, h, w, flip); +} void call_conversion_fn(ConversionFunction1D fn, unsigned char *src, unsigned char *dest, unsigned int h, unsigned int w) { fn(src, dest, h * w); } + + + template struct SimpleConversionStruct { @@ -96,14 +107,59 @@ struct SimpleConversionStruct else if (destBytesPerPixel == 1 && bufdest.ndim == 3 && bufdest.shape[2] > 1) { throw std::runtime_error("Destination should be a either a 2D array of shape H x W or a 3D array of shape (H, W, 1)"); } - - unsigned char *src_ptr = static_cast(bufsrc.ptr); unsigned char *dest_ptr = static_cast(bufdest.ptr); call_conversion_fn(fn, src_ptr, dest_ptr, bufsrc.shape[0], bufsrc.shape[1]); - }, py::arg("src"), py::arg("dest")); + }, "See C++ documentation of the function for more info", py::arg("src"), py::arg("dest")); } +}; +template <> +struct SimpleConversionStruct +{ + SimpleConversionStruct(const std::string &name, ConversionFunction2DWithFlip fn, unsigned int srcBytesPerPixel, unsigned int destBytesPerPixel) : + name(name), fn(fn), srcBytesPerPixel(srcBytesPerPixel), destBytesPerPixel(destBytesPerPixel) + { } + std::string name; + ConversionFunction2DWithFlip fn; + unsigned int srcBytesPerPixel; + unsigned int destBytesPerPixel; + + void add_conversion_binding(py::class_ &pyImageConvert) + { + pyImageConvert.def_static(name.c_str(), [this](py::array_t &src, + py::array_t &dest, bool flip) { + py::buffer_info bufsrc = src.request(), bufdest = dest.request(); + if (bufsrc.ndim < 2 || bufdest.ndim < 2) { + throw std::runtime_error("Expected to have src and dest arrays with at least two dimensions."); + } + if (bufsrc.shape[0] != bufdest.shape[0] || bufsrc.shape[1] != bufdest.shape[1]) { + std::stringstream ss; + ss << "src and dest must have the same number of pixels, but got src = " << shape_to_string(bufsrc.shape); + ss << "and dest = " << shape_to_string(bufdest.shape); + throw std::runtime_error(ss.str()); + } + if (srcBytesPerPixel > 1 && (bufsrc.ndim != 3 || bufsrc.shape[2] != srcBytesPerPixel)) { + std::stringstream ss; + ss << "Source array should be a 3D array of shape (H, W, " << srcBytesPerPixel << ")"; + throw std::runtime_error(ss.str()); + } + else if (srcBytesPerPixel == 1 && bufsrc.ndim == 3 && bufsrc.shape[2] > 1) { + throw std::runtime_error("Source array should be a either a 2D array of shape H x W or a 3D array of shape (H, W, 1)"); + } + if (destBytesPerPixel > 1 && (bufdest.ndim != 3 || bufdest.shape[2] != destBytesPerPixel)) { + std::stringstream ss; + ss << "Destination array should be a 3D array of shape (H, W, " << destBytesPerPixel << ")"; + throw std::runtime_error(ss.str()); + } + else if (destBytesPerPixel == 1 && bufdest.ndim == 3 && bufdest.shape[2] > 1) { + throw std::runtime_error("Destination should be a either a 2D array of shape H x W or a 3D array of shape (H, W, 1)"); + } + unsigned char *src_ptr = static_cast(bufsrc.ptr); + unsigned char *dest_ptr = static_cast(bufdest.ptr); + call_conversion_fn(fn, src_ptr, dest_ptr, bufsrc.shape[0], bufsrc.shape[1], flip); + }, "See C++ documentation of the function for more info", py::arg("src"), py::arg("dest"), py::arg("flip") = false); + } }; template @@ -157,7 +213,6 @@ struct ConversionFromYUVLike call_conversion_fn(fn, src_ptr, dest_ptr, bufdest.shape[0], bufdest.shape[1]); }, py::arg("src"), py::arg("dest")); } - }; unsigned size422(unsigned h, unsigned w) @@ -173,6 +228,78 @@ unsigned size411(unsigned h, unsigned w) return h * w + ((h / 4) * (w / 4)) * 2; } +template +void add_hsv_to_rgb_or_rgba_binding(py::class_ &pyImageConvert, + void (*fn)(const T *, const T *, const T *, unsigned char *, unsigned int), const char *name, const unsigned destBytes) +{ + pyImageConvert.def_static(name, [fn, destBytes](py::array_t &src, + py::array_t &dest) { + py::buffer_info bufsrc = src.request(), bufdest = dest.request(); + if (bufsrc.ndim != 3 || bufdest.ndim != 3) { + throw std::runtime_error("Expected to have src and dest arrays with at least two dimensions."); + } + if (bufsrc.shape[0] != 3) { + throw std::runtime_error("Source array should be a 3D array of shape (3, H, W) "); + } + if (bufdest.shape[2] != destBytes) { + std::stringstream ss; + ss << "Target array should be a 3D array of shape (H, W, " << destBytes << ")"; + throw std::runtime_error(ss.str()); + } + const unsigned height = bufsrc.shape[1]; + const unsigned width = bufsrc.shape[2]; + if (bufdest.shape[0] != height || bufdest.shape[1] != width) { + std::stringstream ss; + ss << "src and dest must have the same number of pixels, but got HSV planes with dimensions (" << height << ", " << width << ")"; + ss << "and RGB array with dimensions (" << bufdest.shape[0] << ", " << bufdest.shape[1] << ")"; + throw std::runtime_error(ss.str()); + } + + const T *h = static_cast(bufsrc.ptr); + const T *s = h + (height * width); + const T *v = s + (height * width); + unsigned char *dest_ptr = static_cast(bufdest.ptr); + fn(h, s, v, dest_ptr, height * width); + + }, "Convert from HSV Planes (as a 3 x H x W array) to a an RGB/RGBA array (as an H x W x 3 or H x W x 4 array)", py::arg("hsv"), py::arg("rgb")); +} + +template +void add_rgb_or_rgba_to_hsv_binding(py::class_ &pyImageConvert, + void (*fn)(const unsigned char *, T *, T *, T *, unsigned int), const char *name, const unsigned destBytes) +{ + pyImageConvert.def_static(name, [fn, destBytes](py::array_t &src, + py::array_t &dest) { + py::buffer_info bufsrc = src.request(), bufdest = dest.request(); + if (bufsrc.ndim != 3 || bufdest.ndim != 3) { + throw std::runtime_error("Expected to have src and dest arrays with at least two dimensions."); + } + if (bufdest.shape[0] != 3) { + throw std::runtime_error("Source array should be a 3D array of shape (3, H, W) "); + } + if (bufsrc.shape[2] != destBytes) { + std::stringstream ss; + ss << "Target array should be a 3D array of shape (H, W, " << destBytes << ")"; + throw std::runtime_error(ss.str()); + } + const unsigned height = bufdest.shape[1]; + const unsigned width = bufdest.shape[2]; + if (bufsrc.shape[0] != height || bufsrc.shape[1] != width) { + std::stringstream ss; + ss << "src and dest must have the same number of pixels, but got HSV planes with dimensions (" << height << ", " << width << ")"; + ss << "and RGB array with dimensions (" << bufdest.shape[0] << ", " << bufdest.shape[1] << ")"; + throw std::runtime_error(ss.str()); + } + + T *h = static_cast(bufdest.ptr); + T *s = h + (height * width); + T *v = s + (height * width); + const unsigned char *rgb = static_cast(bufsrc.ptr); + fn(rgb, h, s, v, height * width); + + }, "Convert from HSV Planes (as a 3 x H x W array) to a an RGB/RGBA array (as an H x W x 3 or H x W x 4 array)", py::arg("rgb"), py::arg("hsv")); +} + } @@ -187,9 +314,24 @@ void bindings_vpImageConvert(py::class_ &pyImageConvert) SimpleConversionStruct("YUV444ToRGBa", &vpImageConvert::YUV444ToRGBa, 3, 4), SimpleConversionStruct("RGBToRGBa", static_cast(&vpImageConvert::RGBToRGBa), 3, 4), SimpleConversionStruct("RGBaToRGB", &vpImageConvert::RGBaToRGB, 4, 3), + SimpleConversionStruct("RGBaToGrey", static_cast(&vpImageConvert::RGBaToGrey), 4, 1), SimpleConversionStruct("GreyToRGB", &vpImageConvert::GreyToRGB, 1, 3), SimpleConversionStruct("GreyToRGBa", static_cast(&vpImageConvert::GreyToRGBa), 1, 4), SimpleConversionStruct("RGBToGrey", static_cast(&vpImageConvert::RGBToGrey), 3, 1), + SimpleConversionStruct("MONO16ToGrey", static_cast(&vpImageConvert::MONO16ToGrey), 2, 1), + SimpleConversionStruct("MONO16ToRGBa", static_cast(&vpImageConvert::MONO16ToRGBa), 2, 4) + + }; + for (auto &conversion: conversions) { + conversion.add_conversion_binding(pyImageConvert); + } + } + + // Simple conversions with flip + { + std::vector> conversions = { + SimpleConversionStruct("BGRToRGBa", static_cast(&vpImageConvert::BGRToRGBa), 3, 4), + SimpleConversionStruct("BGRaToRGBa", static_cast(&vpImageConvert::BGRaToRGBa), 4, 4) }; for (auto &conversion: conversions) { conversion.add_conversion_binding(pyImageConvert); @@ -202,12 +344,10 @@ void bindings_vpImageConvert(py::class_ &pyImageConvert) std::vector conversions = { Conv("YUYVToRGBa", &vpImageConvert::YUYVToRGBa, &size422, 4), Conv("YUYVToRGB", &vpImageConvert::YUYVToRGB, &size422, 3), - Conv("YV12ToRGBa", &vpImageConvert::YV12ToRGBa, &size420, 4), Conv("YV12ToRGB", &vpImageConvert::YV12ToRGB, &size420, 3), Conv("YUV420ToRGBa", &vpImageConvert::YUV420ToRGBa, &size420, 4), Conv("YUV420ToRGB", &vpImageConvert::YUV420ToRGB, &size420, 3), - Conv("YVU9ToRGBa", &vpImageConvert::YVU9ToRGBa, &size411, 4), Conv("YVU9ToRGB", &vpImageConvert::YVU9ToRGB, &size411, 3), }; @@ -237,6 +377,16 @@ void bindings_vpImageConvert(py::class_ &pyImageConvert) conversion.add_conversion_binding(pyImageConvert); } } + + add_hsv_to_rgb_or_rgba_binding(pyImageConvert, vpImageConvert::HSVToRGB, "HSVToRGB", 3); + add_hsv_to_rgb_or_rgba_binding(pyImageConvert, vpImageConvert::HSVToRGB, "HSVToRGB", 3); + add_hsv_to_rgb_or_rgba_binding(pyImageConvert, vpImageConvert::HSVToRGBa, "HSVToRGBa", 4); + add_hsv_to_rgb_or_rgba_binding(pyImageConvert, vpImageConvert::HSVToRGBa, "HSVToRGBa", 4); + + add_rgb_or_rgba_to_hsv_binding(pyImageConvert, vpImageConvert::RGBToHSV, "RGBToHSV", 3); + add_rgb_or_rgba_to_hsv_binding(pyImageConvert, vpImageConvert::RGBToHSV, "RGBToHSV", 3); + add_rgb_or_rgba_to_hsv_binding(pyImageConvert, vpImageConvert::RGBaToHSV, "RGBaToHSV", 4); + add_rgb_or_rgba_to_hsv_binding(pyImageConvert, vpImageConvert::RGBaToHSV, "RGBaToHSV", 4); } #endif diff --git a/modules/python/config/core.json b/modules/python/config/core.json index 591fdd9f8d..588eb0dbe7 100644 --- a/modules/python/config/core.json +++ b/modules/python/config/core.json @@ -13,6 +13,83 @@ "ignore": true } }, + "functions": [ + { + "static": false, + "signature": "void visp2eigen(const vpThetaUVector&, Eigen::AngleAxis&)", + "ignore": true + }, + { + "static": false, + "signature": "void visp2eigen(const vpQuaternionVector&, Eigen::Quaternion&)", + "ignore": true + }, + { + "static": false, + "signature": "void visp2eigen(const vpHomogeneousMatrix&, Eigen::MatrixBase&)", + "ignore": true + }, + { + "static": false, + "signature": "void visp2eigen(const vpMatrix&, Eigen::MatrixBase&)", + "ignore": true + }, + { + "static": false, + "signature": "void eigen2visp(const Eigen::AngleAxis&, vpThetaUVector&)", + "ignore": true + }, + { + "static": false, + "signature": "void eigen2visp(const Eigen::Quaternion&, vpQuaternionVector&)", + "ignore": true + }, + { + "static": true, + "signature": "unsigned long vp_mz_crc32(unsigned long, const unsigned char*, size_t)", + "ignore": true + }, + { + "static": false, + "signature": "std::vector create_npy_header(const std::vector&)", + "ignore": true + }, + { + "static": false, + "signature": "void parse_npy_header(FILE*, size_t&, std::vector&, bool&)", + "ignore": true + }, + { + "static": false, + "signature": "void parse_npy_header(unsigned char*, size_t&, std::vector&, bool&)", + "ignore": true + }, + { + "static": false, + "signature": "void parse_zip_footer(FILE*, uint16_t&, size_t&, size_t&)", + "ignore": true + }, + { + "static": false, + "signature": "void npy_save(std::string, const T*, const std::vector, std::string)", + "ignore": true + }, + { + "static": false, + "signature": "void npz_save(std::string, std::string, const T*, const std::vector&, std::string)", + "ignore": true + }, + { + "static": false, + "signature": "void npy_save(std::string, const std::vector, std::string)", + "ignore": true + }, + { + "static": false, + "signature": "void npz_save(std::string, std::string, const std::vector, std::string)", + "ignore": true + } + ], "classes": { "vpIoTools": { "ignored_attributes": ["separator"], @@ -260,11 +337,26 @@ "signature": "void RGBaToRGB(unsigned char*, unsigned char*, unsigned int)", "ignore": true }, + { + "static": true, + "signature": "void RGBaToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true + }, { "static": true, "signature": "void RGBToRGBa(unsigned char*, unsigned char*, unsigned int)", "ignore": true }, + { + "static": true, + "signature": "void RGBToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void RGBToGrey(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", + "ignore": true + }, { "static": true, "signature": "void RGBToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", @@ -409,6 +501,76 @@ "static": true, "signature": "void YCrCbToRGBa(unsigned char*, unsigned char*, unsigned int)", "ignore": true + }, + { + "static": true, + "signature": "void RGBaToHSV(const unsigned char*, unsigned char*, unsigned char*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void HSVToRGB(const double*, const double*, const double*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void HSVToRGB(const unsigned char*, const unsigned char*, const unsigned char*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void HSVToRGBa(const unsigned char*, const unsigned char*, const unsigned char*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void HSVToRGBa(const double*, const double*, const double*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void RGBToHSV(const unsigned char*, double*, double*, double*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void RGBToHSV(const unsigned char*, unsigned char*, unsigned char*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void RGBaToHSV(const unsigned char*, unsigned char*, unsigned char*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void RGBaToHSV(const unsigned char*, double*, double*, double*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void MONO16ToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void MONO16ToRGBa(unsigned char*, unsigned char*, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void BGRaToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", + "ignore": true + }, + { + "static": true, + "signature": "void BGRToGrey(unsigned char*, unsigned char*, unsigned int, unsigned int, bool, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void BGRToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", + "ignore": true } ] }, @@ -698,6 +860,110 @@ "param_is_output": [false, false, false, false, true, true] } ] + }, + "vpImageFilter": { + "methods": [ + { + "static": true, + "signature": "double derivativeFilterX(const vpImage&, unsigned int, unsigned int)", + "specializations": [ + ["TypeFilterable"] + ] + }, + { + "static": true, + "signature": "double derivativeFilterY(const vpImage&, unsigned int, unsigned int)", + "specializations": [ + ["TypeFilterable"] + ] + } + ] + }, + "vpImageMorphology": { + "methods": [ + { + "static": true, + "signature": "void dilatation(vpImage&, const int&)", + "specializations": [["TypeErodableDilatable"]] + }, + { + "static": true, + "signature": "void erosion(vpImage&, Type, Type, vpImageMorphology::vpConnexityType)", + "specializations": [["TypeErodableDilatable"]] + }, + { + "static": true, + "signature": "void erosion(vpImage&, const vpImageMorphology::vpConnexityType&)", + "specializations": [["TypeErodableDilatable"]] + }, + { + "static": true, + "signature": "void dilatation(vpImage&, Type, Type, vpImageMorphology::vpConnexityType)", + "specializations": [["TypeErodableDilatable"]] + }, + { + "static": true, + "signature": "void dilatation(vpImage&, const vpImageMorphology::vpConnexityType&)", + "specializations": [["TypeErodableDilatable"]] + }, + { + "static": true, + "signature": "void erosion(vpImage&, const int&)", + "specializations": [["TypeErodableDilatable"]] + } + ] + }, + "vpNetwork": { + "methods": [ + { + "static": false, + "signature": "int sendTo(T*, const unsigned int&, const unsigned int&)", + "ignore": true + }, + { + "static": false, + "signature": "int send(T*, const int unsigned&)", + "ignore": true + }, + { + "static": false, + "signature": "int receiveFrom(T*, const unsigned int&, const unsigned int&)", + "ignore": true + }, + { + "static": false, + "signature": "int receive(T*, const unsigned int&)", + "ignore": true + }, + { + "static": false, + "signature": "void addDecodingRequest(vpRequest*)", + "ignore": true + } + ] + }, + "vpUDPClient": { + "methods": [ + { + "static": false, + "signature": "int send(const void*, size_t)", + "ignore": true + }, + { + "static": false, + "signature": "int receive(void*, size_t, int)", + "ignore": true + } + ] + }, + "vpUniRand": { + "methods": [ + { + "static": true, + "signature": "std::vector shuffleVector(const std::vector&)", + "specializations": [["TypePythonScalar"]] + } + ] } } } diff --git a/modules/python/config/core_math.json b/modules/python/config/core_math.json index 2d60e81443..36a6d0bff0 100644 --- a/modules/python/config/core_math.json +++ b/modules/python/config/core_math.json @@ -46,6 +46,81 @@ true, true ] + }, + { + "static": true, + "signature": "void swap(Type&, Type&)", + "ignore": true + }, + { + "static": true, + "signature": "Tp saturate(unsigned char)", + "ignore": true + }, + { + "static": true, + "signature": "Tp saturate(char)", + "ignore": true + }, + { + "static": true, + "signature": "Tp saturate(unsigned short)", + "ignore": true + }, + { + "static": true, + "signature": "Tp saturate(short)", + "ignore": true + }, + { + "static": true, + "signature": "Tp saturate(unsigned)", + "ignore": true + }, + { + "static": true, + "signature": "Tp saturate(int)", + "ignore": true + }, + { + "static": true, + "signature": "Tp saturate(float)", + "ignore": true + }, + { + "static": true, + "signature": "Tp saturate(double)", + "ignore": true + }, + { + "static": true, + "signature": "std::vector linspace(T, T, unsigned int)", + "specializations": [["TypePythonScalar"]] + }, + { + "static": true, + "signature": "Type abs(const Type&)", + "specializations": [["TypePythonScalar"]] + }, + { + "static": true, + "signature": "void swap(Type&, Type&)", + "specializations": [["TypePythonScalar"]] + }, + { + "static": true, + "signature": "Type minimum(const Type&, const Type&)", + "specializations": [["TypePythonScalar"]] + }, + { + "static": true, + "signature": "Type maximum(const Type&, const Type&)", + "specializations": [["TypePythonScalar"]] + }, + { + "static": true, + "signature": "T clamp(const T&, const T&, const T&)", + "specializations": [["TypePythonScalar"]] } ] }, diff --git a/modules/python/generator/visp_python_bindgen/generator_config.py b/modules/python/generator/visp_python_bindgen/generator_config.py index d472d30f6a..39e92f454c 100644 --- a/modules/python/generator/visp_python_bindgen/generator_config.py +++ b/modules/python/generator/visp_python_bindgen/generator_config.py @@ -176,7 +176,6 @@ def update_from_main_config_file(path: Path) -> None: for module_name in modules_dict: headers = map(lambda s: Path(s), modules_dict[module_name].get('headers')) deps = modules_dict[module_name].get('dependencies') - # Include only headers that are in the VISP source directory headers = list(filter(lambda h: source_dir in h.parents, headers)) headers_log_str = '\n\t'.join([str(header) for header in headers]) diff --git a/modules/python/generator/visp_python_bindgen/header.py b/modules/python/generator/visp_python_bindgen/header.py index 2075e9b304..d87dcc2c7d 100644 --- a/modules/python/generator/visp_python_bindgen/header.py +++ b/modules/python/generator/visp_python_bindgen/header.py @@ -49,6 +49,8 @@ from visp_python_bindgen.doc_parser import * from visp_python_bindgen.header_utils import * from visp_python_bindgen.generator_config import GeneratorConfig +from visp_python_bindgen.template_expansion import expand_templates + from typing import TYPE_CHECKING if TYPE_CHECKING: @@ -414,6 +416,7 @@ def add_method_doc_to_pyargs(method: types.Method, py_arg_strs: List[str]) -> Li if method.template is not None and method_config.get('specializations') is not None: method_template_names = [t.name for t in method.template.params] specializations = method_config.get('specializations') + specializations = expand_templates(specializations) for method_spec in specializations: new_specs = owner_specs.copy() assert len(method_template_names) == len(method_spec) diff --git a/modules/python/generator/visp_python_bindgen/methods.py b/modules/python/generator/visp_python_bindgen/methods.py index aa097619ed..09ebaf0ef3 100644 --- a/modules/python/generator/visp_python_bindgen/methods.py +++ b/modules/python/generator/visp_python_bindgen/methods.py @@ -380,6 +380,7 @@ def define_lambda(capture: str, params: List[str], return_type: Optional[str], b ''' class NotGeneratedReason(Enum): UserIgnored = 'user_ignored', + Deleted = 'deleted', Access = 'access', Destructor = 'destructor', ReturnType = 'return_type' @@ -409,6 +410,7 @@ def get_bindable_methods_with_config(submodule: 'Submodule', methods: List[types # Order of predicates is important: The first predicate that matches will be the one shown in the log, and they do not all have the same importance filtering_predicates_and_motives = [ (lambda _, conf: conf['ignore'], NotGeneratedReason.UserIgnored), + (lambda m, _: m.deleted, NotGeneratedReason.Deleted), (lambda m, _: m.pure_virtual, NotGeneratedReason.PureVirtual), (lambda m, _: m.access is None or m.access != 'public', NotGeneratedReason.Access), (lambda m, _: m.destructor, NotGeneratedReason.Destructor), diff --git a/modules/python/generator/visp_python_bindgen/preprocessor.py b/modules/python/generator/visp_python_bindgen/preprocessor.py deleted file mode 100644 index 392913f187..0000000000 --- a/modules/python/generator/visp_python_bindgen/preprocessor.py +++ /dev/null @@ -1,201 +0,0 @@ - -############################################################################# -# -# ViSP, open source Visual Servoing Platform software. -# Copyright (C) 2005 - 2023 by Inria. All rights reserved. -# -# This software is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 2 of the License, or -# (at your option) any later version. -# See the file LICENSE.txt at the root directory of this source -# distribution for additional information about the GNU GPL. -# -# For using ViSP with software that can not be combined with the GNU -# GPL, please contact Inria about acquiring a ViSP Professional -# Edition License. -# -# See https://visp.inria.fr for more information. -# -# This software was developed at: -# Inria Rennes - Bretagne Atlantique -# Campus Universitaire de Beaulieu -# 35042 Rennes Cedex -# France -# -# If you have questions regarding the use of this file, please contact -# Inria at visp@inria.fr -# -# This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE -# WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. -# -# Description: -# ViSP Python bindings generator -# -############################################################################# - -# ''' -# Preprocessor, derived from the command line preprocesor provided at https://github.com/ned14/pcpp/blob/master/pcpp/pcmd.py - -# ''' -# from __future__ import generators, print_function, absolute_import, division - -# import sys, argparse, traceback, os, copy, io, re -# from pcpp.preprocessor import Preprocessor, OutputDirective, Action -# from visp_python_bindgen.generator_config import PreprocessorConfig - -# class CmdPreprocessor(Preprocessor): -# def __init__(self, config: PreprocessorConfig, input: str): -# if len(argv) < 2: -# argv = [argv[0], '--help'] -# argp = argparse.ArgumentParser(prog='pcpp', -# description= -# '''A pure universal Python C (pre-)preprocessor implementation very useful for -# pre-preprocessing header only C++ libraries into single file includes and -# other such build or packaging stage malarky.''', -# epilog= -# '''Note that so pcpp can stand in for other preprocessor tooling, it -# ignores any arguments it does not understand.''') -# argp.add_argument('-o', dest = 'output', metavar = 'path', type = argparse.FileType('wt'), default=sys.stdout, nargs = '?', help = 'Output to a file instead of stdout') -# argp.add_argument('-D', dest = 'defines', metavar = 'macro[=val]', nargs = 1, action = 'append', help = 'Predefine name as a macro [with value]') -# argp.add_argument('-U', dest = 'undefines', metavar = 'macro', nargs = 1, action = 'append', help = 'Pre-undefine name as a macro') -# argp.add_argument('-N', dest = 'nevers', metavar = 'macro', nargs = 1, action = 'append', help = 'Never define name as a macro, even if defined during the preprocessing.') -# argp.add_argument('-I', dest = 'includes', metavar = 'path', nargs = 1, action = 'append', help = "Path to search for unfound #include's") -# #argp.add_argument('--passthru', dest = 'passthru', action = 'store_true', help = 'Pass through everything unexecuted except for #include and include guards (which need to be the first thing in an include file') -# argp.add_argument('--passthru-defines', dest = 'passthru_defines', action = 'store_true', help = 'Pass through but still execute #defines and #undefs if not always removed by preprocessor logic') -# argp.add_argument('--passthru-unfound-includes', dest = 'passthru_unfound_includes', action = 'store_true', help = 'Pass through #includes not found without execution') -# argp.add_argument('--passthru-unknown-exprs', dest = 'passthru_undefined_exprs', action = 'store_true', help = 'Unknown macros in expressions cause preprocessor logic to be passed through instead of executed by treating unknown macros as 0L') -# argp.add_argument('--passthru-comments', dest = 'passthru_comments', action = 'store_true', help = 'Pass through comments unmodified') -# argp.add_argument('--passthru-magic-macros', dest = 'passthru_magic_macros', action = 'store_true', help = 'Pass through double underscore magic macros unmodified') -# argp.add_argument('--passthru-includes', dest = 'passthru_includes', metavar = '', default = None, nargs = 1, help = "Regular expression for which #includes to not expand. #includes, if found, are always executed") -# argp.add_argument('--line-directive', dest = 'line_directive', metavar = 'form', default = '#line', nargs = '?', help = "Form of line directive to use, defaults to #line, specify nothing to disable output of line directives") -# args = argp.parse_known_args(argv[1:]) -# #print(args) -# for arg in args[1]: -# print("NOTE: Argument %s not known, ignoring!" % arg, file = sys.stderr) - -# self.args = args[0] -# super(CmdPreprocessor, self).__init__() - -# # Override Preprocessor instance variables -# self.define("__PCPP_ALWAYS_FALSE__ 0") -# self.define("__PCPP_ALWAYS_TRUE__ 1") - -# self.auto_pragma_once_enabled = True -# self.line_directive = config.line_directive -# if self.line_directive is not None and self.line_directive.lower() in ('nothing', 'none', ''): -# self.line_directive = None -# self.passthru_includes = re.compile(config.passthrough_includes_regex) -# self.compress = 0 -# # Pass through magic macros -# if False: -# self.undef('__DATE__') -# self.undef('__TIME__') -# self.expand_linemacro = False -# self.expand_filemacro = False -# self.expand_countermacro = False - -# # My own instance variables -# self.bypass_ifpassthru = False -# self.potential_include_guard = None - -# for d in config.defines: -# if '=' not in d: -# d += '=1' -# d = d.replace('=', ' ', 1) -# self.define(d) -# # for d in config.undefines: -# # self.undef(d) -# self.nevers = config.never_defined -# if self.args.nevers: -# self.args.nevers = [x[0] for x in self.args.nevers] - -# for include in config.include_directories: -# self.add_path(include) - -# try: -# if len(self.args.inputs) == 1: -# self.parse(self.args.inputs[0]) -# else: -# input = '' -# for i in self.args.inputs: -# input += '#include "' + i.name + '"\n' -# self.parse(input) -# self.write(self.args.output) -# except: -# print(traceback.print_exc(10), file = sys.stderr) -# print("\nINTERNAL PREPROCESSOR ERROR AT AROUND %s:%d, FATALLY EXITING NOW\n" -# % (self.lastdirective.source, self.lastdirective.lineno), file = sys.stderr) -# sys.exit(-99) -# finally: -# for i in self.args.inputs: -# i.close() -# if self.args.output != sys.stdout: -# self.args.output.close() - -# def on_include_not_found(self,is_malformed,is_system_include,curdir,includepath): -# if self.args.passthru_unfound_includes: -# raise OutputDirective(Action.IgnoreAndPassThrough) -# return super(CmdPreprocessor, self).on_include_not_found(is_malformed,is_system_include,curdir,includepath) - -# def on_unknown_macro_in_defined_expr(self,tok): -# if self.args.undefines: -# if tok.value in self.args.undefines: -# return False -# if self.args.passthru_undefined_exprs: -# return None # Pass through as expanded as possible -# return super(CmdPreprocessor, self).on_unknown_macro_in_defined_expr(tok) - -# def on_unknown_macro_in_expr(self,ident): -# if self.args.undefines: -# if ident in self.args.undefines: -# return super(CmdPreprocessor, self).on_unknown_macro_in_expr(ident) -# if self.args.passthru_undefined_exprs: -# return None # Pass through as expanded as possible -# return super(CmdPreprocessor, self).on_unknown_macro_in_expr(ident) - -# def on_unknown_macro_function_in_expr(self,ident): -# if self.args.undefines: -# if ident in self.args.undefines: -# return super(CmdPreprocessor, self).on_unknown_macro_function_in_expr(ident) -# if self.args.passthru_undefined_exprs: -# return None # Pass through as expanded as possible -# return super(CmdPreprocessor, self).on_unknown_macro_function_in_expr(ident) - -# def on_directive_handle(self,directive,toks,ifpassthru,precedingtoks): -# if ifpassthru: -# if directive.value == 'if' or directive.value == 'elif' or directive == 'else' or directive.value == 'endif': -# self.bypass_ifpassthru = len([tok for tok in toks if tok.value == '__PCPP_ALWAYS_FALSE__' or tok.value == '__PCPP_ALWAYS_TRUE__']) > 0 -# if not self.bypass_ifpassthru and (directive.value == 'define' or directive.value == 'undef'): -# if toks[0].value != self.potential_include_guard: -# raise OutputDirective(Action.IgnoreAndPassThrough) # Don't execute anything with effects when inside an #if expr with undefined macro -# if (directive.value == 'define' or directive.value == 'undef') and self.args.nevers: -# if toks[0].value in self.args.nevers: -# raise OutputDirective(Action.IgnoreAndPassThrough) -# if self.args.passthru_defines: -# super(CmdPreprocessor, self).on_directive_handle(directive,toks,ifpassthru,precedingtoks) -# return None # Pass through where possible -# return super(CmdPreprocessor, self).on_directive_handle(directive,toks,ifpassthru,precedingtoks) - -# def on_directive_unknown(self,directive,toks,ifpassthru,precedingtoks): -# if ifpassthru: -# return None # Pass through -# return super(CmdPreprocessor, self).on_directive_unknown(directive,toks,ifpassthru,precedingtoks) - -# def on_potential_include_guard(self,macro): -# self.potential_include_guard = macro -# return super(CmdPreprocessor, self).on_potential_include_guard(macro) - -# def on_comment(self,tok): -# if self.args.passthru_comments: -# return True # Pass through -# return super(CmdPreprocessor, self).on_comment(tok) - -# def main(argv=None): -# if argv is None: -# argv = sys.argv -# p = CmdPreprocessor(argv) -# return p.return_code - -# if __name__ == "__main__": -# sys.exit(main(sys.argv)) diff --git a/modules/python/generator/visp_python_bindgen/template_expansion.py b/modules/python/generator/visp_python_bindgen/template_expansion.py new file mode 100644 index 0000000000..0af35c2c43 --- /dev/null +++ b/modules/python/generator/visp_python_bindgen/template_expansion.py @@ -0,0 +1,23 @@ +from typing import Dict, List +import itertools +TEMPLATE_EXPANSION_MAP: Dict[str, List[str]] = { + 'TypeReal': ['float', 'double'], + 'TypePythonScalar': ['int', 'double'], # Python itself doesn't make the distinction between int, uint, int16_t etc. + 'TypeFilterable': ['unsigned char', 'float', 'double'], + 'TypeErodableDilatable': ['unsigned char', 'float', 'double'], + + 'TypeBaseImagePixel': ['unsigned char', 'vpRGBa'] +} + +def expand_templates(specializations: List[List[str]]) -> List[List[str]]: + result = [] + for spec in specializations: + expanded_params = [] + for param in spec: + if param in TEMPLATE_EXPANSION_MAP: + expanded_params.append(TEMPLATE_EXPANSION_MAP[param]) + else: + expanded_params.append([param]) + # Cartesian product: compute all possible combinations when expansions are taken into account + result.extend(list(itertools.product(*expanded_params))) + return result diff --git a/modules/python/test/test_conversions.py b/modules/python/test/test_conversions.py new file mode 100644 index 0000000000..161ada5611 --- /dev/null +++ b/modules/python/test/test_conversions.py @@ -0,0 +1,64 @@ +from visp.core import ImageConvert +import numpy as np + +def test_hsv_to_rgb_rgba(): + h, w = 50, 50 + cases = [ + { + 'bytes': 3, + 'input_dtype': np.uint8, + 'fn': ImageConvert.HSVToRGB + }, + { + 'bytes': 3, + 'input_dtype': np.float64, + 'fn': ImageConvert.HSVToRGB + }, + { + 'bytes': 4, + 'input_dtype': np.uint8, + 'fn': ImageConvert.HSVToRGBa + }, + { + 'bytes': 4, + 'input_dtype': np.float64, + 'fn': ImageConvert.HSVToRGBa + } + ] + for case in cases: + hsv = np.zeros((3, h, w), dtype=case['input_dtype']) + rgb = np.ones((h, w, case['bytes']), dtype=np.uint8) + rgb_old = rgb.copy() + case['fn'](hsv, rgb) + assert not np.allclose(rgb, rgb_old) + +def test_rgb_rgba_to_hsv(): + h, w = 50, 50 + cases = [ + { + 'bytes': 3, + 'input_dtype': np.uint8, + 'fn': ImageConvert.RGBToHSV + }, + { + 'bytes': 3, + 'input_dtype': np.float64, + 'fn': ImageConvert.RGBToHSV + }, + { + 'bytes': 4, + 'input_dtype': np.uint8, + 'fn': ImageConvert.RGBaToHSV + }, + { + 'bytes': 4, + 'input_dtype': np.float64, + 'fn': ImageConvert.RGBaToHSV + } + ] + for case in cases: + hsv = np.zeros((3, h, w), dtype=case['input_dtype']) + rgb = np.ones((h, w, case['bytes']), dtype=np.uint8) + hsv_old = hsv.copy() + case['fn'](rgb, hsv) + assert not np.allclose(hsv, hsv_old) From 27c431bc4719eaa493238e7e8c082c2da71ca3c3 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 28 Feb 2024 13:14:36 +0100 Subject: [PATCH 065/164] more configuration for core module bindings --- modules/python/config/core.json | 44 +++++++++++++++++++++++++++++++++ 1 file changed, 44 insertions(+) diff --git a/modules/python/config/core.json b/modules/python/config/core.json index 588eb0dbe7..32b5811e9f 100644 --- a/modules/python/config/core.json +++ b/modules/python/config/core.json @@ -675,6 +675,21 @@ "static": true, "signature": "void displayCircle(const vpImage &, int, int, unsigned int, const vpColor &, bool, unsigned int)", "custom_name": "displayCircleStatic" + }, + { + "static": true, + "signature": "bool getKeyboardEvent(const vpImage&, std::string&, bool)", + "use_default_param_policy": false, + "param_is_input": [ + true, + false, + true + ], + "param_is_output": [ + false, + true, + false + ] } ] }, @@ -964,6 +979,35 @@ "specializations": [["TypePythonScalar"]] } ] + }, + "vpHistogram": { + "methods": [ + { + "static": false, + "signature": "unsigned getPeaks(std::list&)", + "use_default_param_policy": false, + "param_is_input": [false], + "param_is_output": [true] + }, + { + "static": false, + "signature": "unsigned getValey(std::list&)", + "use_default_param_policy": false, + "param_is_input": [false], + "param_is_output": [true] + }, + { + "static": false, + "signature": "unsigned sort(std::list&)", + "use_default_param_policy": false, + "param_is_input": [ + true + ], + "param_is_output": [ + true + ] + } + ] } } } From 2b8fc3f64a44b8eb952f9eaac3cf4fdfc514ec1c Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Wed, 28 Feb 2024 18:03:18 +0100 Subject: [PATCH 066/164] finish conversions, cleaning core module config --- .../include/core/image_conversions.hpp | 75 ++++++++++++++++- modules/python/config/core.json | 83 +++++++++++++++++++ .../doc/_templates/custom-class-template.rst | 2 +- modules/python/test/test_conversions.py | 20 +++++ 4 files changed, 177 insertions(+), 3 deletions(-) diff --git a/modules/python/bindings/include/core/image_conversions.hpp b/modules/python/bindings/include/core/image_conversions.hpp index 1aad963d82..5a8d3b9deb 100644 --- a/modules/python/bindings/include/core/image_conversions.hpp +++ b/modules/python/bindings/include/core/image_conversions.hpp @@ -40,6 +40,7 @@ #include #include + namespace { using ConversionFunction1D = void(*)(unsigned char *, unsigned char *, unsigned int); @@ -300,9 +301,41 @@ void add_rgb_or_rgba_to_hsv_binding(py::class_ &pyImageConvert, }, "Convert from HSV Planes (as a 3 x H x W array) to a an RGB/RGBA array (as an H x W x 3 or H x W x 4 array)", py::arg("rgb"), py::arg("hsv")); } -} +/* Demosaicing implem */ +template +void add_demosaic_to_rgba_fn(py::class_ &pyImageConvert, void (*fn)(const DataType *, DataType *, unsigned int, unsigned int, unsigned int), const char *name) +{ + pyImageConvert.def_static(name, [fn](py::array_t &src, + py::array_t &dest, + unsigned int num_threads) { + py::buffer_info bufsrc = src.request(), bufdest = dest.request(); + const unsigned destBytes = 4; + + if (bufsrc.ndim != 2 || bufdest.ndim != 3) { + throw std::runtime_error("Expected to have source array with two dimensions and destination RGBA array with 3."); + } + if (bufdest.shape[2] != destBytes) { + std::stringstream ss; + ss << "Target array should be a 3D array of shape (H, W, " << destBytes << ")"; + throw std::runtime_error(ss.str()); + } + const unsigned height = bufdest.shape[0]; + const unsigned width = bufdest.shape[1]; + if (bufsrc.shape[0] != height || bufsrc.shape[1] != width) { + std::stringstream ss; + ss << "src and dest must have the same number of pixels, but got source with dimensions (" << height << ", " << width << ")"; + ss << "and RGB array with dimensions (" << bufdest.shape[0] << ", " << bufdest.shape[1] << ")"; + throw std::runtime_error(ss.str()); + } + + const DataType *bayer = static_cast(bufsrc.ptr); + DataType *rgba = static_cast(bufdest.ptr); + fn(bayer, rgba, height, width, num_threads); + }, "Demosaic function implementation, see C++ documentation.", py::arg("bayer_data"), py::arg("rgba"), py::arg("num_threads") = 0); +} +} void bindings_vpImageConvert(py::class_ &pyImageConvert) { @@ -338,7 +371,7 @@ void bindings_vpImageConvert(py::class_ &pyImageConvert) } } - //YUV conversions + // YUV conversions { using Conv = ConversionFromYUVLike; std::vector conversions = { @@ -378,6 +411,7 @@ void bindings_vpImageConvert(py::class_ &pyImageConvert) } } + // HSV <-> RGB/a add_hsv_to_rgb_or_rgba_binding(pyImageConvert, vpImageConvert::HSVToRGB, "HSVToRGB", 3); add_hsv_to_rgb_or_rgba_binding(pyImageConvert, vpImageConvert::HSVToRGB, "HSVToRGB", 3); add_hsv_to_rgb_or_rgba_binding(pyImageConvert, vpImageConvert::HSVToRGBa, "HSVToRGBa", 4); @@ -387,6 +421,43 @@ void bindings_vpImageConvert(py::class_ &pyImageConvert) add_rgb_or_rgba_to_hsv_binding(pyImageConvert, vpImageConvert::RGBToHSV, "RGBToHSV", 3); add_rgb_or_rgba_to_hsv_binding(pyImageConvert, vpImageConvert::RGBaToHSV, "RGBaToHSV", 4); add_rgb_or_rgba_to_hsv_binding(pyImageConvert, vpImageConvert::RGBaToHSV, "RGBaToHSV", 4); + + + // uint8_t implems + { + using DemosaicFn = void (*)(const uint8_t *, uint8_t *, unsigned int, unsigned int, unsigned int); + std::vector> functions = { + {static_cast(&vpImageConvert::demosaicRGGBToRGBaMalvar), "demosaicRGGBToRGBaMalvar"}, + {static_cast(&vpImageConvert::demosaicGRBGToRGBaMalvar), "demosaicGRBGToRGBaMalvar"}, + {static_cast(&vpImageConvert::demosaicGBRGToRGBaMalvar), "demosaicGBRGToRGBaMalvar"}, + {static_cast(&vpImageConvert::demosaicBGGRToRGBaMalvar), "demosaicBGGRToRGBaMalvar"}, + {static_cast(&vpImageConvert::demosaicRGGBToRGBaBilinear), "demosaicRGGBToRGBaBilinear"}, + {static_cast(&vpImageConvert::demosaicGRBGToRGBaBilinear), "demosaicGRBGToRGBaBilinear"}, + {static_cast(&vpImageConvert::demosaicGBRGToRGBaBilinear), "demosaicGBRGToRGBaBilinear"}, + {static_cast(&vpImageConvert::demosaicBGGRToRGBaBilinear), "demosaicBGGRToRGBaBilinear"} + }; + for (const auto &pair: functions) { + add_demosaic_to_rgba_fn(pyImageConvert, pair.first, pair.second); + } + } + //UInt16_t implems + { + using DemosaicFn = void (*)(const uint16_t *, uint16_t *, unsigned int, unsigned int, unsigned int); + std::vector> functions = { + {static_cast(&vpImageConvert::demosaicRGGBToRGBaMalvar), "demosaicRGGBToRGBaMalvar"}, + {static_cast(&vpImageConvert::demosaicGRBGToRGBaMalvar), "demosaicGRBGToRGBaMalvar"}, + {static_cast(&vpImageConvert::demosaicGBRGToRGBaMalvar), "demosaicGBRGToRGBaMalvar"}, + {static_cast(&vpImageConvert::demosaicBGGRToRGBaMalvar), "demosaicBGGRToRGBaMalvar"}, + {static_cast(&vpImageConvert::demosaicRGGBToRGBaBilinear), "demosaicRGGBToRGBaBilinear"}, + {static_cast(&vpImageConvert::demosaicGRBGToRGBaBilinear), "demosaicGRBGToRGBaBilinear"}, + {static_cast(&vpImageConvert::demosaicGBRGToRGBaBilinear), "demosaicGBRGToRGBaBilinear"}, + {static_cast(&vpImageConvert::demosaicBGGRToRGBaBilinear), "demosaicBGGRToRGBaBilinear"} + }; + for (const auto &pair: functions) { + add_demosaic_to_rgba_fn(pyImageConvert, pair.first, pair.second); + } + } + } #endif diff --git a/modules/python/config/core.json b/modules/python/config/core.json index 32b5811e9f..f27121c4c9 100644 --- a/modules/python/config/core.json +++ b/modules/python/config/core.json @@ -571,6 +571,89 @@ "static": true, "signature": "void BGRToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", "ignore": true + }, + { + "static": true, + "signature": "void demosaicBGGRToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicBGGRToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicGBRGToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicGBRGToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicGRBGToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + + }, + { + "static": true, + "signature": "void demosaicGRBGToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicRGGBToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicRGGBToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicBGGRToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicBGGRToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicGBRGToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + + }, + { + "static": true, + "signature": "void demosaicGBRGToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + + }, + { + "static": true, + "signature": "void demosaicGRBGToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicGRBGToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicRGGBToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true + }, + { + "static": true, + "signature": "void demosaicRGGBToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true } ] }, diff --git a/modules/python/doc/_templates/custom-class-template.rst b/modules/python/doc/_templates/custom-class-template.rst index 96f82162f4..8f72e62d15 100644 --- a/modules/python/doc/_templates/custom-class-template.rst +++ b/modules/python/doc/_templates/custom-class-template.rst @@ -6,7 +6,7 @@ :members: :show-inheritance: :member-order: groupwise - :inherited-members: pybind11_builtins.pybind11_object + :inherited-members: pybind11_builtins.pybind11_object, pybind11_object :special-members: {% block methods %} diff --git a/modules/python/test/test_conversions.py b/modules/python/test/test_conversions.py index 161ada5611..922b3ffdca 100644 --- a/modules/python/test/test_conversions.py +++ b/modules/python/test/test_conversions.py @@ -62,3 +62,23 @@ def test_rgb_rgba_to_hsv(): hsv_old = hsv.copy() case['fn'](rgb, hsv) assert not np.allclose(hsv, hsv_old) + +def test_demosaic(): + h, w = 32, 32 + fns = [ + ImageConvert.demosaicRGGBToRGBaMalvar, + ImageConvert.demosaicGRBGToRGBaMalvar, + ImageConvert.demosaicGBRGToRGBaMalvar, + ImageConvert.demosaicBGGRToRGBaMalvar, + ImageConvert.demosaicRGGBToRGBaBilinear, + ImageConvert.demosaicGRBGToRGBaBilinear, + ImageConvert.demosaicGBRGToRGBaBilinear, + ImageConvert.demosaicBGGRToRGBaBilinear, + ] + for fn in fns: + for dtype in [np.uint8, np.uint16]: + bayer_data = np.ones((h, w), dtype=dtype) * 128 + rgba = np.empty((h, w, 4), dtype=dtype) + old_rgba = rgba.copy() + fn(bayer_data, rgba) + assert not np.allclose(rgba, old_rgba), f'Error when testing {fn}, with dtype {dtype}' From 09b861bd89ac525779c9f03be5e94a1911020d48 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Fri, 1 Mar 2024 15:13:23 +0100 Subject: [PATCH 067/164] [CORPS] Added new classes for detection of mean drift --- modules/core/include/visp3/core/vpHinkley.h | 8 +- .../visp3/core/vpStatisticalTestAbstract.h | 235 +++++++++++ .../visp3/core/vpStatisticalTestEWMA.h | 152 +++++++ .../visp3/core/vpStatisticalTestHinkley.h | 270 +++++++++++++ .../core/vpStatisticalTestMeanAdjustedCUSUM.h | 231 +++++++++++ .../visp3/core/vpStatisticalTestSigma.h | 142 +++++++ modules/core/src/math/misc/vpHinkley.cpp | 19 +- .../math/misc/vpStatisticalTestAbstract.cpp | 210 ++++++++++ .../src/math/misc/vpStatisticalTestEWMA.cpp | 129 ++++++ .../math/misc/vpStatisticalTestHinkley.cpp | 189 +++++++++ .../vpStatisticalTestMeanAdjustedCUSUM.cpp | 156 ++++++++ .../src/math/misc/vpStatisticalTestSigma.cpp | 107 +++++ tutorial/CMakeLists.txt | 1 + tutorial/mean-drift/CMakeLists.txt | 16 + tutorial/mean-drift/tutorial-meandrift.cpp | 371 ++++++++++++++++++ 15 files changed, 2225 insertions(+), 11 deletions(-) create mode 100644 modules/core/include/visp3/core/vpStatisticalTestAbstract.h create mode 100644 modules/core/include/visp3/core/vpStatisticalTestEWMA.h create mode 100644 modules/core/include/visp3/core/vpStatisticalTestHinkley.h create mode 100644 modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h create mode 100644 modules/core/include/visp3/core/vpStatisticalTestSigma.h create mode 100644 modules/core/src/math/misc/vpStatisticalTestAbstract.cpp create mode 100644 modules/core/src/math/misc/vpStatisticalTestEWMA.cpp create mode 100644 modules/core/src/math/misc/vpStatisticalTestHinkley.cpp create mode 100644 modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp create mode 100644 modules/core/src/math/misc/vpStatisticalTestSigma.cpp create mode 100644 tutorial/mean-drift/CMakeLists.txt create mode 100644 tutorial/mean-drift/tutorial-meandrift.cpp diff --git a/modules/core/include/visp3/core/vpHinkley.h b/modules/core/include/visp3/core/vpHinkley.h index d24760c2d6..6d9ee47e07 100644 --- a/modules/core/include/visp3/core/vpHinkley.h +++ b/modules/core/include/visp3/core/vpHinkley.h @@ -40,6 +40,7 @@ */ #include +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) /*! \class vpHinkley @@ -88,13 +89,14 @@ N_{k^{'}} = 0 \f$. */ -class VISP_EXPORT vpHinkley +class vp_deprecated vpHinkley { public: /*! \enum vpHinkleyJumpType Indicates if a jump is detected by the Hinkley test. */ - typedef enum { + typedef enum + { noJump, /*!< No jump is detected by the Hinkley test. */ downwardJump, /*!< A downward jump is detected by the Hinkley test. */ upwardJump /*!< An upward jump is detected by the Hinkley test. */ @@ -162,5 +164,5 @@ class VISP_EXPORT vpHinkley double Tk; double Nk; }; - +#endif #endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h new file mode 100644 index 0000000000..a365125c71 --- /dev/null +++ b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +#ifndef _vpStatisticalTestAbstract_h_ +#define _vpStatisticalTestAbstract_h_ + + +#include +#include +#include + +#include + +/** + * \ingroup group_core_math_tools + * \brief Base class for methods detecting the drift of the mean of a process. + */ +class VISP_EXPORT vpStatisticalTestAbstract +{ +public: + /** + * \brief Enum that indicates if a drift of the mean occured. + */ + typedef enum vpMeanDriftType + { + NO_MEAN_DRIFT = 0, /*!< No mean drift occured*/ + MEAN_DRIFT_DOWNWARD = 1, /*!< A downward drift of the mean occured.*/ + MEAN_DRIFT_UPWARD = 2 /*!< An upward drift of the mean occured.*/ + } vpMeanDriftType; + + /** + * \brief Cast a \b vpMeanDriftType into a string. + * + * \param[in] type The type of mean drift. + * \return std::string The corresponding message. + */ + static std::string vpMeanDriftTypeToString(const vpMeanDriftType &type); + + /** + * \brief Print the message corresponding to the type of mean drift. + * + * \param[in] type The type of mean drift. + */ + static void print(const vpMeanDriftType &type); + +protected: + bool m_areStatisticsComputed; /*!< Set to true once the mean and the standard deviation are available.*/ + float m_count; /*!< Current number of data used to compute the mean and the standard deviation.*/ + float m_limitDown; /*!< Upper limit for the test signal m_wt.*/ + float m_limitUp; /*!< Lower limit for the test signal m_wt*/ + float m_mean; /*!< Mean of the monitored signal.*/ + unsigned int m_nbSamplesForStatistics; /*!< Number of samples to use to compute the mean and the standard deviation.*/ + float *m_s; /*!< Array that keeps the samples used to compute the mean and standard deviation.*/ + float m_stdev; /*!< Standard deviation of the monitored signal.*/ + float m_stdevmin; /*!< Minimum allowed standard deviation of the monitored signal.*/ + float m_sumForMean; /*!< Sum of the samples used to compute the mean and standard deviation.*/ + + /** + * \brief Detects if a downward mean drift occured. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occured, \b vpMeanDriftType::NO_MEAN_DRIFT otherwise. + * + * \sa detectUpwardMeanShift() + */ + virtual vpMeanDriftType detectDownwardMeanShift() = 0; + + /** + * \brief Detects if a upward mean drift occured. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_UPWARD if an upward mean drift occured, \b vpMeanDriftType::NO_MEAN_DRIFT otherwise. + * + * \sa detectDownwardMeanShift() + */ + virtual vpMeanDriftType detectUpwardMeanShift() = 0; + + /** + * \brief Update \b m_s and if enough values are available, compute the mean, the standard + * deviation and the limits. + * + * \param[in] signal The new value of the signal to monitor. + * + * \return true if the statistics have been computed, false if data are missing. + */ + virtual bool updateStatistics(const float &signal); + + /** + * \brief Update the test signals. + * + * \param[in] signal The new value of the signal to monitor. + */ + virtual void updateTestSignals(const float &signal) = 0; +public: + /** + * \brief Construct a new vpStatisticalTestAbstract object. + */ + vpStatisticalTestAbstract(); + + /** + * \brief Construct by copy a new vpStatisticalTestAbstract object. + */ + vpStatisticalTestAbstract(const vpStatisticalTestAbstract &other); + + /** + * \brief Destroy the vpStatisticalTestAbstract object. + */ + virtual ~vpStatisticalTestAbstract(); + + /** + * \brief Get the upper and lower limits of the test signal. + * + * \param[out] limitDown The lower limit. + * \param[out] limitUp The upper limit. + */ + inline void getLimits(float &limitDown, float &limitUp) const + { + limitDown = m_limitDown; + limitUp = m_limitUp; + } + + /** + * \brief Get the mean used as reference. + * + * \return float The mean. + */ + inline float getMean() const + { + return m_mean; + } + + /** + * \brief Get the standard deviation used as reference. + * + * \return float The standard deviation. + */ + inline float getStdev() const + { + return m_stdev; + } + + /** + * \brief (Re)Initialize the algorithm. + */ + void init(); + + /** + * \brief Copy operator of a vpStatisticalTestAbstract. + * + * \param[in] other The vpStatisticalTestAbstract to copy. + * \return vpStatisticalTestAbstract& *this after copy. + */ + vpStatisticalTestAbstract &operator=(const vpStatisticalTestAbstract &other); + + /** + * \brief Set the minimum value of the standard deviation that is expected. + * The computed standard deviation cannot be lower this value if set. + * + * \param[in] stdevmin The minimum value of the standard deviation that is expected. + */ + void setMinStdev(const float &stdevmin) + { + m_stdevmin = stdevmin; + } + + /** + * \brief Set the number of samples required to compute the mean and standard deviation + * of the signal and allocate the memory accordingly. + * + * \param[in] nbSamples The number of samples we want to use. + */ + void setNbSamplesForStat(const unsigned int &nbSamples); + + /** + * \brief Test if a downward or an upward mean drift occured + * according to the new value of the signal. + * + * \param[in] signal The new value of the signal. + * \return vpMeanDriftType The type of mean drift that occured. + * + * \sa testDownwardMeanShift() testUpwardMeanShift() + */ + vpMeanDriftType testDownUpwardMeanShift(const float &signal); + + /** + * \brief Test if a downward mean drift occured + * according to the new value of the signal. + * + * \param[in] signal The new value of the signal. + * \return vpMeanDriftType The type of mean drift that occured. + * + * \sa testUpwardMeanShift() + */ + vpMeanDriftType testDownwardMeanShift(const float &signal); + + /** + * \brief Test if an upward mean drift occured + * according to the new value of the signal. + * + * \param[in] signal The new value of the signal. + * \return vpMeanDriftType The type of mean drift that occured. + * + * \sa testDownwardMeanShift() + */ + vpMeanDriftType testUpwardMeanShift(const float &signal); +}; + +#endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h new file mode 100644 index 0000000000..3bfa0346bf --- /dev/null +++ b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h @@ -0,0 +1,152 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +#ifndef _vpStatisticalTestEWMA_h_ +#define _vpStatisticalTestEWMA_h_ + +#include + +#include + +/** + * \ingroup group_core_math_tools + * \brief Class that permits to perform Exponentially Weighted Moving Average mean shift tests. + */ +class VISP_EXPORT vpStatisticalTestEWMA : public vpStatisticalTestAbstract +{ +protected: + float m_alpha; /*!< Forgetting factor: the higher, the more weight the current signal value has.*/ + float m_wt; /*!< Test signal such as m_wt = m_alpha * y(t) + ( 1 - m_alpha ) * m_wtprev .*/ + float m_wtprev; /*!< Previous value of the test signal.*/ + + /** + * \brief Compute the upper and lower limits of the test signal. + */ + virtual void computeDeltaAndLimits(); + + /** + * \brief Detects if a downward jump occured on the mean. + * + * \return downwardJump if a downward jump occured, noJump otherwise. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectDownwardMeanShift() override; +#else + virtual vpMeanDriftType detectDownwardMeanShift(); +#endif + +/** + * \brief Detects if a upward jump occured on the mean. + * + * \return upwardJump if a upward jump occured, noJump otherwise. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectUpwardMeanShift() override; +#else + virtual vpMeanDriftType detectUpwardMeanShift(); +#endif + + /** + * \brief Update m_s and if enough values are available, compute the mean, the standard + * deviation and the limits. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual bool updateStatistics(const float &signal) override; +#else + virtual bool updateStatistics(const float &signal); +#endif + + /** + * \brief Update the test signals. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual void updateTestSignals(const float &signal) override; +#else + virtual void updateTestSignals(const float &signal); +#endif + +public: + /** + * \brief Construct a new vpStatisticalTestEWMA object. + * + * \param[in] alpha The forgetting factor. + */ + vpStatisticalTestEWMA(const float &alpha = 0.1f); + + /** + * \brief Get the forgetting factor of the algorithm. + * + * \return float The forgetting factor. + */ + inline float getAlpha() const + { + return m_alpha; + } + + /** + * \brief Get the current value of the test signal. + * + * \return float The current value of the test signal. + */ + inline float getWt() const + { + return m_wt; + } + + /** + * \brief Initialize the EWMA algorithm. + * + * \param[in] alpha The forgetting factor. + */ + void init(const float &alpha); + + /** + * \brief Initialize the EWMA algorithm. + * + * \param[in] alpha The forgetting factor. + * \param[in] mean The expected mean of the signal to monitor. + * \param[in] stdev The expected standard deviation of the signal to monitor. + */ + void init(const float &alpha, const float &mean, const float &stdev); + + /** + * \brief Set the forgetting factor. + * + * \param[in] alpha The forgetting factor. + */ + void setAlpha(const float &alpha); +}; +#endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestHinkley.h b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h new file mode 100644 index 0000000000..0b34bee22b --- /dev/null +++ b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h @@ -0,0 +1,270 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +#ifndef _vpStatisticalTestHinkley_h_ +#define _vpStatisticalTestHinkley_h_ + +#include + +#include + +/** + * \ingroup group_core_math_tools + * \brief This class implements the Hinkley's cumulative sum test. + * + * The Hinkley's cumulative sum test is designed to detect drift in the mean + of an observed signal \f$ s(t) \f$. It is known to be robust (by + taking into account all the past of the observed quantity), + efficient, and inducing a very low computational load. The other + attractive features of this test are two-fold. First, it can + straightforwardly and accurately provide the drift instant. Secondly, + due to its formulation (cumulative sum test), it can simultaneously + handle both very abrupt and important changes, and gradual smaller + ones without adapting the involved thresholds. + + Two tests are performed in parallel to look for downwards or upwards + drifts in \f$ s(t) \f$, respectively defined by: + + \f[ S_k = \sum_{t=0}^{k} (s(t) - m_0 + \frac{\delta}{2}) \f] + \f[ M_k = \max_{0 \leq i \leq k} S_i\f] + \f[ T_k = \sum_{t=0}^{k} (s(t) - m_0 - \frac{\delta}{2}) \f] + \f[ N_k = \min_{0 \leq i \leq k} T_i\f] + + In which \f$m_o\f$ is computed on-line and corresponds to the mean + of the signal \f$ s(t) \f$ we want to detect a drift. \f$m_o\f$ is + re-initialized at zero after each drift detection. \f$\delta\f$ + denotes the drift minimal magnitude that we want to detect and + \f$\alpha\f$ is a predefined threshold. These values are set by + default to 0.2 in the default constructor vpHinkley(). To modify the + default values use setAlpha() and setDelta() or the + vpHinkley(double alpha, double delta) constructor. + + A downward drift is detected if \f$ M_k - S_k > \alpha \f$. + A upward drift is detected if \f$ T_k - N_k > \alpha \f$. + + To detect only downward drifts in \f$ s(t) \f$ use + testDownwardJump().To detect only upward drifts in \f$ s(t) \f$ use + testUpwardJump(). To detect both, downward and upward drifts use + testDownUpwardJump(). + + 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: + float m_dmin2; /*!< Half of \f$\delta\f$, the drift minimal magnitude that we want to detect.*/ + float m_alpha; /*!< The \f$\alpha\f$ threshold indicating that a mean drift occurs. */ + float m_Sk; /*!< Test signal for downward mean drift.*/ + float m_Mk; /*!< Maximum of the test signal for downward mean drift \f$S_k\f$ .*/ + float m_Tk; /*!< Test signal for upward mean drift.*/ + float m_Nk; /*!< Minimum of the test signal for upward mean drift \f$T_k\f$*/ + + /** + * \brief Compute the mean value \f$m_0\f$ of the signal. The mean value must be + * computed before the mean drift is estimated on-line. + * + * \param[in] signal The new value of the signal to monitor. + */ + void computeMean(double signal); + + /** + * \brief Compute \f$S_k = \sum_{t=0}^{k} (s(t) - m_0 + \frac{\delta}{2})\f$ + * + * \param[in] signal The new value of the signal to monitor. + */ + void computeSk(double signal); + + /** + * \brief Compute \f$M_k\f$, the maximum value of \f$S_k\f$. + */ + void computeMk(); + + /** + * \brief Compute \f$T_k = \sum_{t=0}^{k} (s(t) - m_0 - \frac{\delta}{2})\f$ + * + * \param[in] signal The new value of the signal to monitor. + */ + void computeTk(double signal); + + /** + * \brief Compute \f$N_k\f$, the minimum value of \f$T_k\f$. + */ + void computeNk(); + + /** + * \brief Detects if a downward mean drift occured. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occured, \b vpMeanDriftType::NO_MEAN_DRIFT otherwise. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectDownwardMeanShift() override; +#else + virtual vpMeanDriftType detectDownwardMeanShift(); +#endif + +/** + * \brief Detects if a upward mean drift occured. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_UPWARD if an upward mean drift occured, \b vpMeanDriftType::NO_MEAN_DRIFT otherwise. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectUpwardMeanShift() override; +#else + virtual vpMeanDriftType detectUpwardMeanShift(); +#endif + +/** + * \brief Update the test signals. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual void updateTestSignals(const float &signal) override; +#else + virtual void updateTestSignals(const float &signal); +#endif +public: + /** + * @brief Construct a new vpStatisticalTestHinkley object. + * Call init() to initialise the Hinkley's test and set \f$\alpha\f$ + * and \f$\delta\f$ to default values. + * + * By default \f$ \delta = 0.2 \f$ and \f$ \alpha = 0.2\f$. Use + * setDelta() and setAlpha() to modify these values. + */ + vpStatisticalTestHinkley(); + + /** + * \brief Call init() to initialise the Hinkley's test and set \f$\alpha\f$ + * and \f$\delta\f$ thresholds. + * \param[in] alpha : \f$\alpha\f$ threshold indicating that a mean drift occurs. + * \param[in] delta : \f$\delta\f$ denotes the drift minimal magnitude that + * we want to detect. + * \param[in] nbSamplesForInit : number of signal samples to initialize the mean of the signal. + * + * \sa setAlpha(), setDelta() + */ + vpStatisticalTestHinkley(const float &alpha, const float &delta, const unsigned int &nbSamplesForInit = 30); + + /** + * \brief Destroy the vpStatisticalTestHinkley object. + */ + virtual ~vpStatisticalTestHinkley(); + + /** + * \brief Get the \f$\alpha\f$ threshold indicating that a mean drift occurs. + * + * \return The \f$\alpha\f$ threshold. + */ + inline float getAlpha() const { return m_alpha; } + + /*! + * \brief Get the test signal for downward mean drift. + * + * \return The value of \f$S_k = \sum_{t=0}^{k} (s(t) - m_0 + \frac{\delta}{2})\f$ . + */ + inline float getSk() const { return m_Sk; } + + /*! + * \brief Get the maximum of the test signal for downward mean drift \f$S_k\f$ . + * + * \return The value of \f$M_k\f$, the maximum value of \f$S_k\f$. + */ + inline float getMk() const { return m_Mk; } + + /*! + * \brief Get the test signal for upward mean drift.. + * + * \return The value of \f$T_k = \sum_{t=0}^{k} (s(t) - m_0 - \frac{\delta}{2})\f$ . + + */ + inline float getTk() const { return m_Tk; } + + /*! + * \brief Get the minimum of the test signal for upward mean drift \f$T_k\f$ + * + * \return The value of \f$N_k\f$, the minimum value of \f$T_k\f$. + */ + inline float getNk() const { return m_Nk; } + + /** + * \brief Initialise the Hinkley's test by setting the mean signal value + * \f$m_0\f$ to zero as well as \f$S_k, M_k, T_k, N_k\f$. + */ + void init(); + + /** + * \brief Initialise the Hinkley's test by setting the mean signal value + * \f$m_0\f$ to the expected value and \f$S_k, M_k, T_k, N_k\f$ to 0. + * + * \param[in] mean The expected value of the mean. + */ + void init(const float &mean); + + /** + * \brief Call init() to initialise the Hinkley's test and set \f$\alpha\f$ + * and \f$\delta\f$ thresholds. + * + * \param[in] alpha The threshold indicating that a mean drift occurs. + * \param[in] delta The drift minimal magnitude that we want to detect. + * \param[in] nbSamplesForInit : number of signal samples to initialize the mean of the signal. + */ + void init(const float &alpha, const float &delta, const unsigned int &nbSamplesForInit); + + /** + * \brief Call init() to initialise the Hinkley's test, set \f$\alpha\f$ + * and \f$\delta\f$ thresholds, and the mean of the signal \f$m_0\f$. + * + * \param[in] alpha The threshold indicating that a mean drift occurs. + * \param[in] delta The drift minimal magnitude that we want to detect. + * \param[in] mean The expected value of the mean. + */ + void init(const float &alpha, const float &delta, const float &mean); + + /** + * \brief Set the drift minimal magnitude that we want to detect. + * + * \param[in] delta The drift magnitude. + */ + void setDelta(const float &delta); + + /** + * \brief The threshold indicating that a mean drift occurs. + * + * \param[in] alpha The threshold. + */ + void setAlpha(const float &alpha); +}; + +#endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h new file mode 100644 index 0000000000..2f514eee6d --- /dev/null +++ b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h @@ -0,0 +1,231 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +#ifndef _vpStatisticalTestMeanAdjustedCUSUM_h_ +#define _vpStatisticalTestMeanAdjustedCUSUM_h_ + +#include + +#include + +/** + * \ingroup group_core_math_tools + * \brief Class that permits to perform a mean adjusted Cumulative Sum test. + */ +class VISP_EXPORT vpStatisticalTestMeanAdjustedCUSUM : public vpStatisticalTestAbstract +{ +protected: + float m_delta; /*!< Slack of the CUSUM test, i.e. amplitude of mean shift we want to be able to detect.*/ + float m_h; /*!< Alarm factor that permits to determine the limit telling when a mean shift occurs: limit = m_h * m_stdev . + To have an Average Run Lenght of ~374 samples for a detection of 1 stdev, set it to 4.76f*/ + float m_half_delta; /*!< Half of the amplitude we want to detect.*/ + float m_k; /*!< Detection factor that permits to determine the slack: m_delta = m_k * m_stdev .*/ + float m_sminus; /*!< Test signal for downward mean shift: S_-(i) = max{0, S_-(i-1) - (y_i - m_mean) - m_delta/2}.*/ + float m_splus; /*!< Test signal for upward mean shift: S_+(i) = max{0, S_+(i-1) + (y_i - m_mean) - m_delta/2}.*/ + + /** + * \brief Compute the upper and lower limits of the test signal. + */ + virtual void computeDeltaAndLimits(); + +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectDownwardMeanShift() override; +#else + virtual vpMeanDriftType detectDownwardMeanShift(); +#endif + +/** + * \brief Detects if a upward jump occured on the mean. + * + * \return upwardJump if a upward jump occured, noJump otherwise. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectUpwardMeanShift() override; +#else + virtual vpMeanDriftType detectUpwardMeanShift(); +#endif + + /** + * \brief Update m_s and if enough values are available, compute the mean, the standard + * deviation and the limits. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual bool updateStatistics(const float &signal) override; +#else + virtual bool updateStatistics(const float &signal); +#endif + + /** + * \brief Update the test signals. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual void updateTestSignals(const float &signal) override; +#else + virtual void updateTestSignals(const float &signal); +#endif +public: + /** + * \brief Construct a new vpStatisticalTestMeanAdjustedCUSUM object. + * + * \param[in] h The alarm factor that permits to determine when the process is out of control from the standard + * deviation of the signal. + * \param[in] k The detection factor that permits to determine the slack of the CUSUM test, i.e. the + * minimum value of the jumps we want to detect, from the standard deviation of the signal. + * \param[in] nbPtsForStats The number of samples to use to compute the mean and the standard deviation of the signal + * to monitor. + */ + vpStatisticalTestMeanAdjustedCUSUM(const float &h = 4.f, const float &k = 1.f, const unsigned int &nbPtsForStats = 30); + + /** + * \brief Get the slack of the CUSUM test, + * i.e. amplitude of mean shift we want to be able to detect. + * + * \return float The slack of the CUSUM test. + */ + inline float getDelta() const + { + return m_delta; + } + + /** + * \brief Get the alarm factor. + * + * \return float The alarm factor. + */ + inline float getH() const + { + return m_h; + } + + /** + * \brief Get the detection factor. + * + * \return float The detection factor. + */ + inline float getK() const + { + return m_k; + } + + /** + * \brief Get the latest value of the test signal for downward jumps of the mean. + * + * \return float Its latest value. + */ + inline float getTestSignalMinus() const + { + return m_sminus; + } + + /** + * \brief Get the latest value of the test signal for upward jumps of the mean. + * + * \return float Its latest value. + */ + inline float getTestSignalPlus() const + { + return m_splus; + } + + /** + * \brief (Re)Initialize the mean adjusted CUSUM test. + * + * \param[in] h The alarm factor that permits to determine when the process is out of control from the standard + * deviation of the signal. + * \param[in] k The detection factor that permits to determine the slack of the CUSUM test, i.e. the + * minimum value of the jumps we want to detect, from the standard deviation of the signal. + * \param[in] nbPtsForStats The number of points to use to compute the mean and the standard deviation of the signal + */ + void init(const float &h, const float &k, const unsigned int &nbPtsForStats); + + /** + * \brief Initialize the mean adjusted CUSUM test. + * + * \param[in] delta The slack of the CUSUM test, i.e. the minimum value of the jumps we want to detect. + * \param[in] limitDown The lower limit of the CUSUM test, for the downward jumps. + * \param[in] limitUp The upper limit of the CUSUM test, for the upward jumps. + * \param[in] nbPtsForStats The number of points to use to compute the mean and the standard deviation of the signal + * to monitor. + */ + void init(const float &delta, const float &limitDown, const float &limitUp, const unsigned int &nbPtsForStats); + + /** + * \brief Initialize the mean adjusted CUSUM test. + * + * \param[in] h The alarm factor that permits to determine when the process is out of control from the standard + * deviation of the signal. + * \param[in] k The detection factor that permits to determine the slack of the CUSUM test, i.e. the + * minimum value of the jumps we want to detect, from the standard deviation of the signal. + * \param[in] mean The expected mean of the signal to monitor. + * \param[in] stdev The expected standard deviation of the signal to monitor. + */ + void init(const float &h, const float &k, const float &mean, const float &stdev); + + /** + * \brief Initialize the mean adjusted CUSUM test. + * + * \param[in] delta The slack of the CUSUM test, i.e. the minimum value of the jumps we want to detect. + * \param[in] limitDown The lower limit of the CUSUM test, for the downward jumps. + * \param[in] limitUp The upper limit of the CUSUM test, for the upward jumps. + * \param[in] mean The expected mean of the signal to monitor. + * \param[in] stdev The expected standard deviation of the signal to monitor. + */ + void init(const float &delta, const float &limitDown, const float &limitUp, const float &mean, const float &stdev); + + /** + * \brief Set the slack of the CUSUM test, i.e. the minimum value of the jumps we want to detect. + * + * \param[in] delta The slack of the CUSUM test. + */ + inline void setDelta(const float &delta) + { + m_delta = delta; + m_half_delta = 0.5f * delta; + } + + /** + * \brief Set the upward and downward jump limits. + * + * \param[in] limitDown The limit for the downward jumps. + * \param[in] limitUp The limit for the upward jumps. + */ + inline void setLimits(const float &limitDown, const float &limitUp) + { + m_limitDown = limitDown; + m_limitUp = limitUp; + } +}; +#endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestSigma.h b/modules/core/include/visp3/core/vpStatisticalTestSigma.h new file mode 100644 index 0000000000..72036c860e --- /dev/null +++ b/modules/core/include/visp3/core/vpStatisticalTestSigma.h @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +#ifndef _vpStatisticalTestSigma_h_ +#define _vpStatisticalTestSigma_h_ + +#include + +#include + +/** + * \ingroup group_core_math_tools + * \brief Class that permits a simple test comparing the current value to the + * standard deviation of the signal. + */ + +class VISP_EXPORT vpStatisticalTestSigma : public vpStatisticalTestAbstract +{ +protected: + float m_h; /*!< The alarm factor applied to the standard deviation to compute the limits.*/ + float m_s; /*!< The last value of the signal.*/ + + /** + * \brief Compute the upper and lower limits of the test signal. + */ + virtual void computeLimits(); + +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectDownwardMeanShift() override; +#else + virtual vpMeanDriftType detectDownwardMeanShift(); +#endif + +/** + * \brief Detects if a upward jump occured on the mean. + * + * \return upwardJump if a upward jump occured, noJump otherwise. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectUpwardMeanShift() override; +#else + virtual vpMeanDriftType detectUpwardMeanShift(); +#endif + + /** + * \brief Update m_s and if enough values are available, compute the mean, the standard + * deviation and the limits. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual bool updateStatistics(const float &signal) override; +#else + virtual bool updateStatistics(const float &signal); +#endif + + /** + * \brief Update the test signals. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual void updateTestSignals(const float &signal) override; +#else + virtual void updateTestSignals(const float &signal); +#endif +public: + /** + * \brief Construct a new vpStatisticalTestSigma object. + * + * \param[in] h The alarm factor applied to the standard deviation to compute the limits. + * \param[in] nbSamplesForStats The number of samples to compute the statistics of the signal. + */ + vpStatisticalTestSigma(const float &h = 3.f, const unsigned int &nbSamplesForStats = 30); + + /** + * \brief Construct a new vpStatisticalTestSigma object. + * + * \param[in] h The alarm factor applied to the standard deviation to compute the limits. + * \param[in] mean The expected mean of the signal. + * \param[in] stdev The expected standard deviation of the signal. + */ + vpStatisticalTestSigma(const float &h, const float &mean, const float &stdev); + + /** + * \brief Get the last value of the signal. + * + * \return float The signal. + */ + inline float getS() const + { + return m_s; + } + + /** + * \brief (Re)Initialize the test. + * + * \param[in] h The alarm factor applied to the standard deviation to compute the limits. + * \param[in] nbSamplesForStats The number of samples to compute the statistics of the signal. + */ + void init(const float &h = 3.f, const unsigned int &nbSamplesForStats = 30); + + /** + * \brief (Re)Initialize the test. + * + * \param[in] h The alarm factor applied to the standard deviation to compute the limits. + * \param[in] mean The expected mean of the signal. + * \param[in] stdev The expected standard deviation of the signal. + */ + void init(const float &h, const float &mean, const float &stdev); +}; + +#endif diff --git a/modules/core/src/math/misc/vpHinkley.cpp b/modules/core/src/math/misc/vpHinkley.cpp index 40b06647ef..fc534c3e7e 100644 --- a/modules/core/src/math/misc/vpHinkley.cpp +++ b/modules/core/src/math/misc/vpHinkley.cpp @@ -42,9 +42,9 @@ */ -#include #include -//#include +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +#include #include #include // std::fabs @@ -70,7 +70,7 @@ setDelta() and setAlpha() to modify these values. */ -vpHinkley::vpHinkley() : dmin2(0.1), alpha(0.2), nsignal(0), mean(0), Sk(0), Mk(0), Tk(0), Nk(0) {} +vpHinkley::vpHinkley() : dmin2(0.1), alpha(0.2), nsignal(0), mean(0), Sk(0), Mk(0), Tk(0), Nk(0) { } /*! @@ -90,8 +90,7 @@ vpHinkley::vpHinkley() : dmin2(0.1), alpha(0.2), nsignal(0), mean(0), Sk(0), Mk( vpHinkley::vpHinkley(double alpha_val, double delta_val) : dmin2(delta_val / 2.), alpha(alpha_val), nsignal(0), mean(0), Sk(0), Mk(0), Tk(0), Nk(0) -{ -} +{ } /*! @@ -119,7 +118,7 @@ void vpHinkley::init(double alpha_val, double delta_val) Destructor. */ -vpHinkley::~vpHinkley() {} +vpHinkley::~vpHinkley() { } /*! @@ -305,9 +304,9 @@ vpHinkley::vpHinkleyJumpType vpHinkley::testDownUpwardJump(double signal) computeNk(); vpCDEBUG(2) << "alpha: " << alpha << " dmin2: " << dmin2 << " signal: " << signal << " Sk: " << Sk << " Mk: " << Mk - << " Tk: " << Tk << " Nk: " << Nk << std::endl; + << " Tk: " << Tk << " Nk: " << Nk << std::endl; - // teste si les variables cumulees excedent le seuil +// teste si les variables cumulees excedent le seuil if ((Mk - Sk) > alpha) jump = downwardJump; else if ((Tk - Nk) > alpha) @@ -433,3 +432,7 @@ void vpHinkley::print(vpHinkley::vpHinkleyJumpType jump) break; } } +#elif !defined(VISP_BUILD_SHARED_LIBS) + // Work around to avoid warning: libvisp_core.a(vpHinkley.cpp.o) has no symbols +void dummy_vpRHinkley() { }; +#endif diff --git a/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp new file mode 100644 index 0000000000..591674dd77 --- /dev/null +++ b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp @@ -0,0 +1,210 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +/** +* +* \file vpStatisticalTestAbstract.cpp +* +* \brief Definition of the vpStatisticalTestAbstract base class. +*/ + +#include + +std::string vpStatisticalTestAbstract::vpMeanDriftTypeToString(const vpStatisticalTestAbstract::vpMeanDriftType &type) +{ + std::string name; + switch (type) { + case NO_MEAN_DRIFT: + name = " No jump"; + break; + case MEAN_DRIFT_DOWNWARD: + name = " Jump downward"; + break; + case MEAN_DRIFT_UPWARD: + name = " Jump upward"; + break; + default: + name = " Undefined jump"; + break; + } + return name; +} + +void vpStatisticalTestAbstract::print(const vpStatisticalTestAbstract::vpMeanDriftType &type) +{ + std::cout << vpMeanDriftTypeToString(type) << " detected" << std::endl; +} + +bool vpStatisticalTestAbstract::updateStatistics(const float &signal) +{ + m_s[static_cast(m_count)] = signal; + m_count += 1.f; + m_sumForMean += signal; + if (static_cast (m_count) >= m_nbSamplesForStatistics) { + // Computation of the mean + m_mean = m_sumForMean / m_count; + + // Computation of the stdev + float sumSquaredDiff = 0.f; + unsigned int count = static_cast(m_nbSamplesForStatistics); + for (unsigned int i = 0; i < count; ++i) { + sumSquaredDiff += (m_s[i] - m_mean) * (m_s[i] - m_mean); + } + float stdev = std::sqrt(sumSquaredDiff / m_count); + if (m_stdevmin < 0) { + m_stdev = stdev; + } + else { + m_stdev = std::max(m_stdev, m_stdevmin); + } + + m_areStatisticsComputed = true; + } + return m_areStatisticsComputed; +} + +vpStatisticalTestAbstract::vpStatisticalTestAbstract() + : m_areStatisticsComputed(false) + , m_count(0.f) + , m_limitDown(0.f) + , m_limitUp(0.f) + , m_mean(0.f) + , m_nbSamplesForStatistics(0) + , m_s(nullptr) + , m_stdev(0.f) + , m_stdevmin(-1.f) + , m_sumForMean(0.f) +{ } + +vpStatisticalTestAbstract::vpStatisticalTestAbstract(const vpStatisticalTestAbstract &other) +{ + *this = other; +} + +vpStatisticalTestAbstract::~vpStatisticalTestAbstract() +{ + if (m_s != nullptr) { + delete m_s; + m_s = nullptr; + } +} + +void vpStatisticalTestAbstract::init() +{ + m_areStatisticsComputed = false; + m_count = 0.f; + m_limitDown = 0.f; + m_limitUp = 0.f; + m_mean = 0.f; + m_nbSamplesForStatistics = 0; + if (m_s != nullptr) { + delete m_s; + m_s = nullptr; + } + m_stdev = 0.f; + m_sumForMean = 0.f; +} + +vpStatisticalTestAbstract &vpStatisticalTestAbstract::operator=(const vpStatisticalTestAbstract &other) +{ + m_areStatisticsComputed = other.m_areStatisticsComputed; + m_count = other.m_count; + m_limitDown = other.m_limitDown; + m_limitUp = other.m_limitUp; + m_mean = other.m_mean; + if (other.m_nbSamplesForStatistics > 0) { + setNbSamplesForStat(other.m_nbSamplesForStatistics); + } + else if (m_s != nullptr) { + m_nbSamplesForStatistics = 0; + delete m_s; + m_s = nullptr; + } + m_stdev = 0.f; + m_sumForMean = 0.f; + return *this; +} + +void vpStatisticalTestAbstract::setNbSamplesForStat(const unsigned int &nbSamples) +{ + m_nbSamplesForStatistics = nbSamples; + if (m_s != nullptr) { + delete m_s; + } + m_s = new float[nbSamples]; +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testDownUpwardMeanShift(const float &signal) +{ + if (m_areStatisticsComputed) { + updateTestSignals(signal); + vpMeanDriftType jumpDown = detectDownwardMeanShift(); + vpMeanDriftType jumpUp = detectUpwardMeanShift(); + if (jumpDown != NO_MEAN_DRIFT) { + return jumpDown; + } + else if (jumpUp != NO_MEAN_DRIFT) { + return jumpUp; + } + else { + return NO_MEAN_DRIFT; + } + } + else { + updateStatistics(signal); + return NO_MEAN_DRIFT; + } +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testDownwardMeanShift(const float &signal) +{ + if (m_areStatisticsComputed) { + updateTestSignals(signal); + return detectDownwardMeanShift(); + } + else { + updateStatistics(signal); + return NO_MEAN_DRIFT; + } +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testUpwardMeanShift(const float &signal) +{ + if (m_areStatisticsComputed) { + updateTestSignals(signal); + return detectUpwardMeanShift(); + } + else { + updateStatistics(signal); + return NO_MEAN_DRIFT; + } +} diff --git a/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp b/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp new file mode 100644 index 0000000000..d4dd6a5e28 --- /dev/null +++ b/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp @@ -0,0 +1,129 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +/** +* +* \file vpStatisticalTestEWMA.cpp +* +* \brief Definition of the vpStatisticalTestEWMA class that implements Exponentially Weighted Moving Average +* mean drift test. +*/ + +#include + +void vpStatisticalTestEWMA::computeDeltaAndLimits() +{ + float delta = 3.f * m_stdev * std::sqrt(m_alpha / (2.f - m_alpha)); + m_limitDown = m_mean - delta; + m_limitUp = m_mean + delta; +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestEWMA::detectDownwardMeanShift() +{ + if (m_wt <= m_limitDown) { + return MEAN_DRIFT_DOWNWARD; + } + else { + return NO_MEAN_DRIFT; + } +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestEWMA::detectUpwardMeanShift() +{ + if (m_wt >= m_limitUp) { + return MEAN_DRIFT_UPWARD; + } + else { + return NO_MEAN_DRIFT; + } +} + +bool vpStatisticalTestEWMA::updateStatistics(const float &signal) +{ + bool areStatsReady = vpStatisticalTestAbstract::updateStatistics(signal); + if (areStatsReady) { + // Computation of the limits + computeDeltaAndLimits(); + + // Initialize first value + m_wt = m_mean; + } + return areStatsReady; +} + +void vpStatisticalTestEWMA::updateTestSignals(const float &signal) +{ + // Update last value + m_wtprev = m_wt; +// w(t) = alpha * s(t) + (1 - alpha) * w(t- 1); + m_wt = m_wtprev + m_alpha * (signal - m_wtprev); +} + +vpStatisticalTestEWMA::vpStatisticalTestEWMA(const float &alpha) + : vpStatisticalTestAbstract() + , m_alpha(0.f) + , m_wt(0.f) + , m_wtprev(0.f) +{ + init(alpha); +} + +void vpStatisticalTestEWMA::init(const float &alpha) +{ + vpStatisticalTestAbstract::init(); + m_alpha = alpha; + unsigned int nbRequiredSamples = static_cast(std::ceil(3.f / m_alpha)); + setNbSamplesForStat(nbRequiredSamples); + m_wt = 0.f; + m_wtprev = 0.f; +} + +void vpStatisticalTestEWMA::init(const float &alpha, const float &mean, const float &stdev) +{ + vpStatisticalTestAbstract::init(); + m_alpha = alpha; + m_mean = mean; + unsigned int nbRequiredSamples = static_cast(std::ceil(3.f / m_alpha)); + setNbSamplesForStat(nbRequiredSamples); + m_stdev = stdev; + m_wt = mean; + m_wtprev = 0.f; + + // Computation of the limits + computeDeltaAndLimits(); + m_areStatisticsComputed = true; +} + +void vpStatisticalTestEWMA::setAlpha(const float &alpha) +{ + init(alpha); +} diff --git a/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp b/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp new file mode 100644 index 0000000000..b001d010b6 --- /dev/null +++ b/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp @@ -0,0 +1,189 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +#include + +/** +* +* \file vpStatisticalTestHinkley.cpp +* +* \brief Definition of the vpStatisticalTestHinkley class corresponding to the Hinkley's +* cumulative sum test. +*/ + +#include +#include + +#include // std::fabs +#include +#include // numeric_limits +#include +#include + +vpStatisticalTestHinkley::vpStatisticalTestHinkley() + : vpStatisticalTestAbstract() + , m_dmin2(0.1f) + , m_alpha(0.2f) + , m_Sk(0.f) + , m_Mk(0.f) + , m_Tk(0.f) + , m_Nk(0.f) +{ + init(); +} + +vpStatisticalTestHinkley::vpStatisticalTestHinkley(const float &alpha, const float &delta_val, const unsigned int &nbSamplesForInit) + : vpStatisticalTestAbstract() + , m_dmin2(delta_val / 2.f) + , m_alpha(alpha) + , m_Sk(0.f) + , m_Mk(0.f) + , m_Tk(0.f) + , m_Nk(0.f) +{ + init(alpha, delta_val, nbSamplesForInit); +} + +void vpStatisticalTestHinkley::init(const float &alpha, const float &delta_val, const unsigned int &nbSamplesForInit) +{ + init(); + setNbSamplesForStat(nbSamplesForInit); + setAlpha(alpha); + setDelta(delta_val); +} + +void vpStatisticalTestHinkley::init(const float &alpha, const float &delta_val, const float &mean) +{ + init(); + setAlpha(alpha); + setDelta(delta_val); + m_mean = mean; + m_areStatisticsComputed = true; +} + +vpStatisticalTestHinkley::~vpStatisticalTestHinkley() { } + +void vpStatisticalTestHinkley::init() +{ + vpStatisticalTestAbstract::init(); + setNbSamplesForStat(30); + setAlpha(m_alpha); + + m_Sk = 0.f; + m_Mk = 0.f; + + m_Tk = 0.f; + m_Nk = 0.f; +} + +void vpStatisticalTestHinkley::init(const float &mean) +{ + vpStatisticalTestHinkley::init(); + m_mean = mean; + m_areStatisticsComputed = true; +} + +void vpStatisticalTestHinkley::setDelta(const float &delta) { m_dmin2 = delta / 2.f; } + +void vpStatisticalTestHinkley::setAlpha(const float &alpha) +{ + this->m_alpha = alpha; + m_limitDown = m_alpha; + m_limitUp = m_alpha; +} + +void vpStatisticalTestHinkley::computeMean(double signal) +{ + // When the mean slowly increases or decreases, especially after an abrupt change of the mean, + // the means tends to drift. To reduce the drift of the mean + // it is updated with the current value of the signal only if + // a beginning of a mean drift is not detected, + // i.e. if ( ((m_Mk-m_Sk) == 0) && ((m_Tk-m_Nk) == 0) ) + if ((std::fabs(m_Mk - m_Sk) <= std::fabs(vpMath::maximum(m_Mk, m_Sk)) * std::numeric_limits::epsilon()) && + (std::fabs(m_Tk - m_Nk) <= std::fabs(vpMath::maximum(m_Tk, m_Nk)) * std::numeric_limits::epsilon())) { + m_mean = (m_mean * (m_count - 1) + signal) / (m_count); + } +} + +void vpStatisticalTestHinkley::computeSk(double signal) +{ + m_Sk += signal - m_mean + m_dmin2; +} + +void vpStatisticalTestHinkley::computeMk() +{ + if (m_Sk > m_Mk) { + m_Mk = m_Sk; + } +} + +void vpStatisticalTestHinkley::computeTk(double signal) +{ + m_Tk += signal - m_mean - m_dmin2; +} + +void vpStatisticalTestHinkley::computeNk() +{ + if (m_Tk < m_Nk) { + m_Nk = m_Tk; + } +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestHinkley::detectDownwardMeanShift() +{ + vpStatisticalTestAbstract::vpMeanDriftType shift = NO_MEAN_DRIFT; + if ((m_Mk - m_Sk) > m_alpha) { + shift = MEAN_DRIFT_DOWNWARD; + } + return shift; +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestHinkley::detectUpwardMeanShift() +{ + vpStatisticalTestAbstract::vpMeanDriftType shift = NO_MEAN_DRIFT; + if ((m_Tk - m_Nk) > m_alpha) { + shift = MEAN_DRIFT_UPWARD; + } + return shift; +} + +void vpStatisticalTestHinkley::updateTestSignals(const float &signal) +{ + computeSk(signal); + computeTk(signal); + + computeMk(); + computeNk(); + + ++m_count; + computeMean(signal); +} diff --git a/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp b/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp new file mode 100644 index 0000000000..a60cf77798 --- /dev/null +++ b/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp @@ -0,0 +1,156 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +/** +* +* \file vpStatisticalTestMeanAdjustedCUSUM.cpp +* +* \brief Definition of the vpStatisticalTestMeanAdjustedCUSUM class that implements mean adjusted Cumulative Sum +* mean drift test. +*/ + +#include + +void vpStatisticalTestMeanAdjustedCUSUM::computeDeltaAndLimits() +{ + setDelta(m_k * m_stdev); + float limitDown = m_h * m_stdev; + float limitUp = limitDown; + setLimits(limitDown, limitUp); +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestMeanAdjustedCUSUM::detectDownwardMeanShift() +{ + if (m_sminus >= m_limitDown) { + return MEAN_DRIFT_DOWNWARD; + } + else { + return NO_MEAN_DRIFT; + } +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestMeanAdjustedCUSUM::detectUpwardMeanShift() +{ + if (m_splus >= m_limitUp) { + return MEAN_DRIFT_UPWARD; + } + else { + return NO_MEAN_DRIFT; + } +} + +bool vpStatisticalTestMeanAdjustedCUSUM::updateStatistics(const float &signal) +{ + bool areStatsAvailable = vpStatisticalTestAbstract::updateStatistics(signal); + if (areStatsAvailable) { + // Computation of the limits + if ((m_limitDown < 0.f) && (m_limitUp < 0.f)) { + computeDeltaAndLimits(); + } + + // Initialize first values + m_sminus = 0.f; + m_splus = 0.f; + } + return areStatsAvailable; +} + +void vpStatisticalTestMeanAdjustedCUSUM::updateTestSignals(const float &signal) +{ + m_sminus = std::max(0.f, m_sminus - (signal - m_mean) - m_half_delta); + m_splus = std::max(0.f, m_splus + (signal - m_mean) - m_half_delta); +} + +vpStatisticalTestMeanAdjustedCUSUM::vpStatisticalTestMeanAdjustedCUSUM(const float &h, const float &k, const unsigned int &nbPtsForStats) + : vpStatisticalTestAbstract() + , m_delta(-1.f) + , m_h(h) + , m_half_delta(-1.f) + , m_k(k) + , m_sminus(0.f) + , m_splus(0.f) +{ + init(h, k, nbPtsForStats); +} + +void vpStatisticalTestMeanAdjustedCUSUM::init(const float &h, const float &k, const unsigned int &nbPtsForStats) +{ + vpStatisticalTestAbstract::init(); + setNbSamplesForStat(nbPtsForStats); + m_delta = -1.f; + m_half_delta = -1.f; + setLimits(-1.f, -1.f); // To compute automatically the limits once the signal statistics are available. + m_h = h; + m_k = k; + m_mean = 0.f; + m_sminus = 0.f; + m_splus = 0.f; + m_stdev = 0.f; +} + +void vpStatisticalTestMeanAdjustedCUSUM::init(const float &delta, const float &limitDown, const float &limitUp, const unsigned int &nbPtsForStats) +{ + vpStatisticalTestAbstract::init(); + setDelta(delta); + setLimits(limitDown, limitUp); + setNbSamplesForStat(nbPtsForStats); + m_sminus = 0.f; + m_splus = 0.f; +} + +void vpStatisticalTestMeanAdjustedCUSUM::init(const float &h, const float &k, const float &mean, const float &stdev) +{ + vpStatisticalTestAbstract::init(); + setLimits(-1.f, -1.f); // To compute automatically the limits once the signal statistics are available. + m_h = h; + m_k = k; + m_mean = mean; + m_sminus = 0.f; + m_splus = 0.f; + m_stdev = stdev; + // Compute delta and limits from m_h, m_k and m_stdev + computeDeltaAndLimits(); + m_areStatisticsComputed = true; +} + +void vpStatisticalTestMeanAdjustedCUSUM::init(const float &delta, const float &limitDown, const float &limitUp, const float &mean, const float &stdev) +{ + vpStatisticalTestAbstract::init(); + setDelta(delta); + setLimits(limitDown, limitUp); + m_mean = mean; + m_sminus = 0.f; + m_splus = 0.f; + m_stdev = stdev; + m_sumForMean = 0.f; + m_areStatisticsComputed = true; +} diff --git a/modules/core/src/math/misc/vpStatisticalTestSigma.cpp b/modules/core/src/math/misc/vpStatisticalTestSigma.cpp new file mode 100644 index 0000000000..65dd6a1d2b --- /dev/null +++ b/modules/core/src/math/misc/vpStatisticalTestSigma.cpp @@ -0,0 +1,107 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +#include + +void vpStatisticalTestSigma::computeLimits() +{ + float delta = m_h * m_stdev; + m_limitDown = m_mean - delta; + m_limitUp = m_mean + delta; +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestSigma::detectDownwardMeanShift() +{ + if (m_s <= m_limitDown) { + return vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD; + } + else { + return vpStatisticalTestAbstract::NO_MEAN_DRIFT; + } +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestSigma::detectUpwardMeanShift() +{ + if (m_s >= m_limitUp) { + return vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD; + } + else { + return vpStatisticalTestAbstract::NO_MEAN_DRIFT; + } +} + +bool vpStatisticalTestSigma::updateStatistics(const float &signal) +{ + bool areStatsAvailable = vpStatisticalTestAbstract::updateStatistics(signal); + if (areStatsAvailable) { + computeLimits(); + } + return areStatsAvailable; +} + +void vpStatisticalTestSigma::updateTestSignals(const float &signal) +{ + m_s = signal; +} + +vpStatisticalTestSigma::vpStatisticalTestSigma(const float &h, const unsigned int &nbSamplesForStats) + : vpStatisticalTestAbstract() + , m_h(h) +{ + init(h, nbSamplesForStats); +} + +vpStatisticalTestSigma::vpStatisticalTestSigma(const float &h, const float &mean, const float &stdev) + : vpStatisticalTestAbstract() + , m_h(h) +{ + init(h, mean, stdev); +} + +void vpStatisticalTestSigma::init(const float &h, const unsigned int &nbSamplesForStats) +{ + vpStatisticalTestAbstract::init(); + m_h = h; + setNbSamplesForStat(nbSamplesForStats); + m_s = 0; +} + +void vpStatisticalTestSigma::init(const float &h, const float &mean, const float &stdev) +{ + vpStatisticalTestAbstract::init(); + m_h = h; + m_mean = mean; + m_s = 0; + m_stdev = stdev; + computeLimits(); + m_areStatisticsComputed = true; +} diff --git a/tutorial/CMakeLists.txt b/tutorial/CMakeLists.txt index 7ede770bdd..ae1233344b 100644 --- a/tutorial/CMakeLists.txt +++ b/tutorial/CMakeLists.txt @@ -44,6 +44,7 @@ visp_add_subdirectory(imgproc/contrast-sharpening REQUIRED_DEPS visp_co visp_add_subdirectory(imgproc/count-coins REQUIRED_DEPS visp_core visp_io visp_gui visp_imgproc) visp_add_subdirectory(imgproc/flood-fill REQUIRED_DEPS visp_core visp_io visp_gui visp_imgproc) visp_add_subdirectory(imgproc/hough-transform REQUIRED_DEPS visp_core visp_gui visp_imgproc) +visp_add_subdirectory(mean-drift REQUIRED_DEPS visp_core visp_gui) visp_add_subdirectory(munkres REQUIRED_DEPS visp_core visp_gui) visp_add_subdirectory(robot/flir-ptu REQUIRED_DEPS visp_core visp_robot visp_sensor visp_vision visp_gui visp_vs visp_visual_features visp_detection) visp_add_subdirectory(robot/pioneer REQUIRED_DEPS visp_core visp_robot visp_vs visp_gui) diff --git a/tutorial/mean-drift/CMakeLists.txt b/tutorial/mean-drift/CMakeLists.txt new file mode 100644 index 0000000000..fed2f435fd --- /dev/null +++ b/tutorial/mean-drift/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 3.5) + +project(tutorial-meandrift) + +find_package(VISP REQUIRED visp_core visp_gui) + +set(tutorial_cpp) + +list(APPEND tutorial_cpp tutorial-meandrift.cpp) + +foreach(cpp ${tutorial_cpp}) + visp_add_target(${cpp}) + if(COMMAND visp_add_dependency) + visp_add_dependency(${cpp} "tutorials") + endif() +endforeach() diff --git a/tutorial/mean-drift/tutorial-meandrift.cpp b/tutorial/mean-drift/tutorial-meandrift.cpp new file mode 100644 index 0000000000..37f4aeb659 --- /dev/null +++ b/tutorial/mean-drift/tutorial-meandrift.cpp @@ -0,0 +1,371 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +//! \example tutorial-meandrift.cpp + +#include +#include +#include +#include +#include +#include +#include + +namespace TutorialMeanDrift +{ + /** + * \brief Structure that permits to choose which process test to use. + * + */ +typedef enum TypeTest +{ + HINLKEY_TYPE_TEST = 0, /*!< Use Hinkley to perform the tests.*/ + EWMA_TYPE_TEST = 1, /*!< Use Exponentially Weighted Moving Average to perform the tests.*/ + MEAN_ADJUSTED_CUSUM_TYPE_TEST = 2, /*!< Use mean adjusted Cumulative Sum to perform the tests.*/ + SIGMA_TYPE_TEST = 3, /*!< Simple test based on the comparisong with the standard deviation.*/ + COUNT_TYPE_TEST = 4, /*!< Number of different aavailable methods.*/ + UNKOWN_TYPE_TEST = COUNT_TYPE_TEST /*!< Unknown method.*/ +}TypeTest; + +/** + * \brief Permit to cast a \b TypeTest object into a string, for display purpose. + * + * \param[in] choice The \b TypeTest object we want to know the name. + * \return std::string The corresponding name. + */ +std::string typeTestToString(const TypeTest &type) +{ + std::string result; + switch (type) { + case HINLKEY_TYPE_TEST: + result = "hinkley"; + break; + case EWMA_TYPE_TEST: + result = "ewma"; + break; + case MEAN_ADJUSTED_CUSUM_TYPE_TEST: + result = "cusum"; + break; + case SIGMA_TYPE_TEST: + result = "sigma"; + break; + case UNKOWN_TYPE_TEST: + default: + result = "unknown-type-test"; + break; + } + return result; +} + +/** + * \brief Permit to cast a string into a \b TypeTest, to + * cast a command line argument. + * + * \param[in] name The name of the process test the user wants to use. + * \return TypeTest The corresponding \b TypeTest object. + */ +TypeTest typeTestFromString(const std::string &name) +{ + TypeTest result = UNKOWN_TYPE_TEST; + unsigned int count = static_cast(COUNT_TYPE_TEST); + unsigned int id = 0; + bool hasNotFound = true; + while ((id < count) && hasNotFound) { + TypeTest temp = static_cast(id); + if (typeTestToString(temp) == name) { + result = temp; + hasNotFound = false; + } + ++id; + } + return result; +} + +/** + * \brief Get the list of available \b TypeTest objects that are handled. + * + * \param[in] prefix The prefix that should be placed before the list. + * \param[in] sep The separator between each element of the list. + * \param[in] suffix The suffix that should terminate the list. + * \return std::string The list of handled type of process tests, presented as a string. + */ +std::string getAvailableTypeTest(const std::string &prefix = "<", const std::string &sep = " , ", + const std::string &suffix = ">") +{ + std::string msg(prefix); + unsigned int count = static_cast(COUNT_TYPE_TEST); + unsigned int lastId = count - 1; + for (unsigned int i = 0; i < lastId; i++) { + msg += typeTestToString(static_cast(i)) + sep; + } + msg += typeTestToString(static_cast(lastId)) + suffix; + return msg; +} + +/** + * \brief Structure that contains the parameters of the different algorithms. + */ +typedef struct ParametersForAlgo +{ + unsigned int m_global_nbsamples; /*!< Number of samples to compute the mean and stdev, common to all the algorithms.*/ + float m_cusum_h; /*!< Alarm factor for the mean adjusted CUSUM test.*/ + float m_cusum_k; /*!< Detection factor for the mean adjusted CUSUM test.*/ + float m_ewma_alpha; /*!< Forgetting factor for the EWMA test.*/ + float m_hinkley_alpha; /*!< Alarm threshold for the Hinkley's test. */ + float m_hinkley_delta; /*!< Detection threshold for the Hinkley's test. */ + float m_sigma_h; /*!< Alarm factor for the sigma test.*/ + + ParametersForAlgo() + : m_global_nbsamples(30) + , m_cusum_h(4.76f) + , m_cusum_k(1.f) + , m_ewma_alpha(0.1f) + , m_hinkley_alpha(4.76f) + , m_hinkley_delta(1.f) + , m_sigma_h(3.f) + { } +}ParametersForAlgo; +} + +int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanDrift::ParametersForAlgo parameters, + const float &mean, const float &mean_drift, const float &stdev) +{ + const float dt = 10.f; // Emulate a 10ms period + + vpPlot plotter(1); + plotter.initGraph(0, 1); + plotter.setTitle(0, "Evolution of the signal"); + plotter.setUnitX(0, "Frame ID"); + plotter.setUnitY(0, "No units"); + + unsigned int idFrame = 0; + vpStatisticalTestAbstract *p_test = nullptr; + switch (type) { + case TutorialMeanDrift::EWMA_TYPE_TEST: + p_test = new vpStatisticalTestEWMA(parameters.m_ewma_alpha); + break; + case TutorialMeanDrift::HINLKEY_TYPE_TEST: + p_test = new vpStatisticalTestHinkley(parameters.m_hinkley_alpha, parameters.m_hinkley_delta, parameters.m_global_nbsamples); + break; + case TutorialMeanDrift::MEAN_ADJUSTED_CUSUM_TYPE_TEST: + p_test = new vpStatisticalTestMeanAdjustedCUSUM(parameters.m_cusum_h, parameters.m_cusum_k, parameters.m_global_nbsamples); + break; + case TutorialMeanDrift::SIGMA_TYPE_TEST: + p_test = new vpStatisticalTestSigma(parameters.m_sigma_h, parameters.m_global_nbsamples); + break; + default: + throw(vpException(vpException::badValue, TutorialMeanDrift::typeTestToString(type) + " is not handled.")); + break; + } + + float signal; + std::cout << "Actual mean of the input signal: " << mean << std::endl; + std::cout << "Actual stdev of the input signal: " << stdev << std::endl; + std::cout << "Mean drift of the input signal: " << mean_drift << std::endl; + + // Initial computation of the mean and stdev of the input signal + for (unsigned int i = 0; i < parameters.m_global_nbsamples; ++i) { + vpGaussRand rndGen(stdev, mean, static_cast(idFrame) * dt); + signal = rndGen(); + p_test->testDownUpwardMeanShift(signal); + ++idFrame; + } + std::cout << "Estimated mean of the input signal: " << p_test->getMean() << std::endl; + std::cout << "Estimated stdev of the input signal: " << p_test->getStdev() << std::endl; + + float mean_eff = mean; + bool hasToRun = true; + vpStatisticalTestAbstract::vpMeanDriftType drift_type = vpStatisticalTestAbstract::NO_MEAN_DRIFT; + while (hasToRun) { + vpGaussRand rndGen(stdev, mean_eff, static_cast(idFrame) * dt); + signal = rndGen(); + plotter.plot(0, 0, idFrame - parameters.m_global_nbsamples, signal); + drift_type = p_test->testDownUpwardMeanShift(signal); + if (drift_type != vpStatisticalTestAbstract::NO_MEAN_DRIFT) { + hasToRun = false; + } + else { + mean_eff += mean_drift; + ++idFrame; + } + } + std::cout << "Test failed at frame: " << idFrame - parameters.m_global_nbsamples << std::endl; + std::cout << "Type of mean drift: " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift_type) << std::endl; + std::cout << "Last signal value: " << signal << std::endl; + if (type == TutorialMeanDrift::EWMA_TYPE_TEST) { + vpStatisticalTestEWMA *p_testEwma = dynamic_cast(p_test); + std::cout << "\tw(t) = " << p_testEwma->getWt() << std::endl; + } + else if (type == TutorialMeanDrift::MEAN_ADJUSTED_CUSUM_TYPE_TEST) { + vpStatisticalTestMeanAdjustedCUSUM *p_testCusum = dynamic_cast(p_test); + std::cout << "\tLower cusum = " << p_testCusum->getTestSignalMinus() << std::endl; + std::cout << "\tUpper cusum = " << p_testCusum->getTestSignalPlus() << std::endl; + } + float limitDown = 0.f, limitUp = 0.f; + p_test->getLimits(limitDown, limitUp); + std::cout << "\tLimit down = " << limitDown << std::endl; + std::cout << "\tLimit up = " << limitUp << std::endl; + std::cout << "End of test on synthetic data. Press enter to leave." << std::endl; + std::cin.get(); + return EXIT_SUCCESS; +} + +int main(int argc, char *argv[]) +{ + TutorialMeanDrift::TypeTest opt_typeTest = TutorialMeanDrift::EWMA_TYPE_TEST; + TutorialMeanDrift::ParametersForAlgo parameters; + float opt_mean = 6.f; + float opt_meandrift = 0.1f; + float opt_stdev = 1.f; + + int i = 1; + while (i < argc) { + if ((std::string(argv[i]) == "--test") && ((i + 1) < argc)) { + opt_typeTest = TutorialMeanDrift::typeTestFromString(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--nb-samples") && ((i + 1) < argc)) { + parameters.m_global_nbsamples = std::atoi(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--mean") && ((i + 1) < argc)) { + opt_mean = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--mean-drift") && ((i + 1) < argc)) { + opt_meandrift = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--stdev") && ((i + 1) < argc)) { + opt_stdev = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--cusum-h") && ((i + 1) < argc)) { + parameters.m_cusum_h = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--cusum-k") && ((i + 1) < argc)) { + parameters.m_cusum_k = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--ewma-alpha") && ((i + 1) < argc)) { + parameters.m_ewma_alpha = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--hinkley-alpha") && ((i + 1) < argc)) { + parameters.m_hinkley_alpha = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--hinkley-delta") && ((i + 1) < argc)) { + parameters.m_hinkley_delta = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--sigma-h") && ((i + 1) < argc)) { + parameters.m_sigma_h = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) { + std::cout << "\nSYNOPSIS " << std::endl + << argv[0] + << " [--test ]" + << " [--nb-samples ]" + << " [--mean ]" + << " [--mean-drift ]" + << " [--stdev ]" + << " [--cusum-h ]" + << " [--cusum-k ]" + << " [--ewma-alpha ]" + << " [--hinkley-alpha <]0; inf[>]" + << " [--hinkley-delta <]0; inf[>]" + << " [--sigma-h ]" + << " [--help,-h]" << std::endl; + std::cout << "\nOPTIONS " << std::endl + << " --test " << std::endl + << " Type of test to perform on the data." << std::endl + << " Available values: " << TutorialMeanDrift::getAvailableTypeTest() << std::endl + << std::endl + << " --nb-samples " << std::endl + << " Number of samples to compute the mean and standard deviation of the monitored signal." << std::endl + << " Default: " << parameters.m_global_nbsamples << std::endl + << std::endl + << " --mean " << std::endl + << " Mean of the signal." << std::endl + << " Default: " << opt_mean<< std::endl + << std::endl + << " --mean-drift " << std::endl + << " Mean drift for the synthetic data." << std::endl + << " Default: " << opt_meandrift << std::endl + << std::endl + << " --stdev " << std::endl + << " Standard deviation of the signal." << std::endl + << " Default: " << opt_stdev << std::endl + << std::endl + << " --cusum-h " << std::endl + << " The alarm factor that permits to the CUSUM test to determine when the process is out of control" << std::endl + << " from the standard deviation of the signal." << std::endl + << " Default: " << parameters.m_cusum_h << std::endl + << std::endl + << " --cusum-k " << std::endl + << " The factor that permits to determine the slack of the CUSUM test, " << std::endl + << " i.e. the minimum value of the jumps we want to detect, from the standard deviation of the signal." << std::endl + << " Default: " << parameters.m_cusum_k << std::endl + << std::endl + << " --ewma-alpha " << std::endl + << " Forgetting factor for the Exponential Weighted Moving Average (EWMA)." << std::endl + << " Default: " << parameters.m_ewma_alpha << std::endl + << std::endl + << " --hinkley-alpha " << std::endl + << " The alarm threshold indicating that a mean drift occurs for the Hinkley's test." << std::endl + << " Default: " << parameters.m_hinkley_alpha << std::endl + << std::endl + << " --hinkley-delta " << std::endl + << " Detection threshold indicating minimal magnitude we want to detect for the Hinkley's test." << std::endl + << " Default: " << parameters.m_hinkley_delta << std::endl + << std::endl + << " --sigma-h " << std::endl + << " The alarm factor of the sigma test." << std::endl + << " Default: " << parameters.m_sigma_h << std::endl + << std::endl + << " --help, -h" << std::endl + << " Display this helper message." << std::endl + << std::endl; + return EXIT_SUCCESS; + } + else { + std::cout << "\nERROR " << std::endl << " Unknown option " << argv[i] << std::endl; + return EXIT_FAILURE; + } + ++i; + } + + return testOnSynthetic(opt_typeTest, parameters, opt_mean, opt_meandrift, opt_stdev); +} From a7fd5790e819f818a27547d28369501a82b73ca3 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Mon, 4 Mar 2024 18:31:57 +0100 Subject: [PATCH 068/164] Rework SVD decomposition. Fix issue when m < n. Closes #1341 Improve SVD and pseudo inverse testing --- modules/core/src/math/matrix/vpMatrix.cpp | 3406 ++++++++--------- modules/core/src/math/matrix/vpMatrix_svd.cpp | 246 +- .../test/math/testMatrixPseudoInverse.cpp | 574 ++- modules/core/test/math/testSvd.cpp | 66 +- 4 files changed, 2226 insertions(+), 2066 deletions(-) diff --git a/modules/core/src/math/matrix/vpMatrix.cpp b/modules/core/src/math/matrix/vpMatrix.cpp index 74a8f69791..87b7cfbca6 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -30,8 +30,8 @@ * * Description: * Matrix manipulation. - * -*****************************************************************************/ + */ + /*! \file vpMatrix.cpp \brief Definition of the vpMatrix class @@ -126,7 +126,7 @@ void compute_pseudo_inverse(const vpMatrix &U, const vpColVector &sv, const vpMa rank_out = 0; - for (unsigned int i = 0; i < ncols; i++) { + for (unsigned int i = 0; i < sv.size(); i++) { if (sv[i] > maxsv * svThreshold) { rank_out++; } @@ -862,7 +862,7 @@ void vpMatrix::diag(const vpColVector &A) /*! Set the matrix as a diagonal matrix where each element on the diagonal is -set to \e val. Elements that are not on the diagonal are set to 0. + set to \e val. Elements that are not on the diagonal are set to 0. \param val : Value to set. @@ -899,7 +899,6 @@ void vpMatrix::diag(const double &val) } /*! - Create a diagonal matrix with the element of a vector \f$ DA_{ii} = A_i \f$. \param A : Vector which element will be put in the diagonal. @@ -1067,7 +1066,6 @@ void vpMatrix::mult2Matrices(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) (speed gain if used many times with the same result matrix size). \exception vpException::dimensionError If matrices are not 3-by-3 dimension. - */ void vpMatrix::mult2Matrices(const vpMatrix &A, const vpMatrix &B, vpRotationMatrix &C) { @@ -1104,7 +1102,6 @@ void vpMatrix::mult2Matrices(const vpMatrix &A, const vpMatrix &B, vpRotationMat (speed gain if used many times with the same result matrix size). \exception vpException::dimensionError If matrices are not 4-by-4 dimension. - */ void vpMatrix::mult2Matrices(const vpMatrix &A, const vpMatrix &B, vpHomogeneousMatrix &C) { @@ -2410,18 +2407,7 @@ vpMatrix vpMatrix::pseudoInverseLapack(double svThreshold) const vpMatrix U, V, Ap; vpColVector sv; - Ap.resize(ncols, nrows, false, false); - - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdLapack(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); @@ -2478,18 +2464,7 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, double svThreshold) con vpMatrix U, V; vpColVector sv; - Ap.resize(ncols, nrows, false, false); - - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdLapack(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); @@ -2550,27 +2525,13 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double int rank_out; vpMatrix U, V; - vpColVector sv_; Ap.resize(ncols, nrows, false, false); - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); - U.svdLapack(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); + U = *this; + U.svdLapack(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return static_cast(rank_out); } @@ -2688,25 +2649,18 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double unsigned int ncols = getCols(); int rank_out; vpMatrix U, V; - vpColVector sv_; if (nrows < ncols) { U.resize(ncols, ncols, true); - sv.resize(nrows, false); + U.insert(*this, 0, 0); } else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); + U = *this; } - U.insert(*this, 0, 0); - U.svdLapack(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, &imA, &imAt, &kerAt); + U.svdLapack(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, &imA, &imAt, &kerAt); return static_cast(rank_out); } @@ -2757,18 +2711,7 @@ vpMatrix vpMatrix::pseudoInverseLapack(int rank_in) const vpMatrix U, V, Ap; vpColVector sv; - Ap.resize(ncols, nrows, false, false); - - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdLapack(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); @@ -2832,18 +2775,7 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, int rank_in) const vpMatrix U, V; vpColVector sv; - Ap.resize(ncols, nrows, false, false); - - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdLapack(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); @@ -2910,29 +2842,14 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in) co unsigned int ncols = getCols(); int rank_out; double svThreshold = 1e-26; - vpMatrix U, V; - vpColVector sv_; Ap.resize(ncols, nrows, false, false); - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); - U.svdLapack(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); + U = *this; + U.svdLapack(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); return rank_out; } @@ -3056,25 +2973,18 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in, vp int rank_out; double svThreshold = 1e-26; vpMatrix U, V; - vpColVector sv_; if (nrows < ncols) { U.resize(ncols, ncols, true); - sv.resize(nrows, false); + U.insert(*this, 0, 0); } else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); + U = *this; } - U.insert(*this, 0, 0); - U.svdLapack(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, &imA, &imAt, &kerAt); + U.svdLapack(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, &imA, &imAt, &kerAt); return rank_out; } @@ -3122,22 +3032,10 @@ vpMatrix vpMatrix::pseudoInverseEigen3(double svThreshold) const unsigned int nrows = getRows(); unsigned int ncols = getCols(); int rank_out; - vpMatrix U, V, Ap; vpColVector sv; - Ap.resize(ncols, nrows, false, false); - - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdEigen3(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); @@ -3190,28 +3088,17 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, double svThreshold) con unsigned int nrows = getRows(); unsigned int ncols = getCols(); int rank_out; - vpMatrix U, V; vpColVector sv; - Ap.resize(ncols, nrows, false, false); - - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdEigen3(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return static_cast(rank_out); } + /*! Compute the Moore-Penros pseudo inverse \f$A^+\f$ of a m-by-n matrix \f$\bf A\f$ along with singular values and return the rank of the matrix using @@ -3264,29 +3151,14 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double unsigned int nrows = getRows(); unsigned int ncols = getCols(); int rank_out; - vpMatrix U, V; - vpColVector sv_; Ap.resize(ncols, nrows, false, false); - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); - U.svdEigen3(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); + U = *this; + U.svdEigen3(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return static_cast(rank_out); } @@ -3404,25 +3276,18 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double unsigned int ncols = getCols(); int rank_out; vpMatrix U, V; - vpColVector sv_; if (nrows < ncols) { U.resize(ncols, ncols, true); - sv.resize(nrows, false); + U.insert(*this, 0, 0); } else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); + U = *this; } - U.insert(*this, 0, 0); - U.svdEigen3(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, &imA, &imAt, &kerAt); + U.svdEigen3(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, &imA, &imAt, &kerAt); return static_cast(rank_out); } @@ -3469,22 +3334,10 @@ vpMatrix vpMatrix::pseudoInverseEigen3(int rank_in) const unsigned int ncols = getCols(); int rank_out; double svThreshold = 1e-26; - vpMatrix U, V, Ap; vpColVector sv; - Ap.resize(ncols, nrows, false, false); - - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdEigen3(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); @@ -3544,22 +3397,12 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, int rank_in) const unsigned int ncols = getCols(); int rank_out; double svThreshold = 1e-26; - vpMatrix U, V; vpColVector sv; Ap.resize(ncols, nrows, false, false); - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdEigen3(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); @@ -3626,29 +3469,14 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in) co unsigned int ncols = getCols(); int rank_out; double svThreshold = 1e-26; - vpMatrix U, V; - vpColVector sv_; Ap.resize(ncols, nrows, false, false); - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); - U.svdEigen3(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); + U = *this; + U.svdEigen3(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); return rank_out; } @@ -3772,25 +3600,17 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in, vp int rank_out; double svThreshold = 1e-26; vpMatrix U, V; - vpColVector sv_; if (nrows < ncols) { U.resize(ncols, ncols, true); - sv.resize(nrows, false); + U.insert(*this, 0, 0); } else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); + U = *this; } + U.svdEigen3(sv, V); - U.insert(*this, 0, 0); - U.svdEigen3(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, &imA, &imAt, &kerAt); - - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, &imA, &imAt, &kerAt); return rank_out; } @@ -3838,22 +3658,10 @@ vpMatrix vpMatrix::pseudoInverseOpenCV(double svThreshold) const unsigned int nrows = getRows(); unsigned int ncols = getCols(); int rank_out; - vpMatrix U, V, Ap; vpColVector sv; - Ap.resize(ncols, nrows, false, false); - - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdOpenCV(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); @@ -3906,22 +3714,12 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, double svThreshold) con unsigned int nrows = getRows(); unsigned int ncols = getCols(); int rank_out; - vpMatrix U, V; vpColVector sv; Ap.resize(ncols, nrows, false, false); - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdOpenCV(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); @@ -3980,29 +3778,14 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double unsigned int nrows = getRows(); unsigned int ncols = getCols(); int rank_out; - vpMatrix U, V; - vpColVector sv_; Ap.resize(ncols, nrows, false, false); - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); - U.svdOpenCV(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); + U = *this; + U.svdOpenCV(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, nullptr, nullptr, nullptr); return static_cast(rank_out); } @@ -4120,25 +3903,18 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double unsigned int ncols = getCols(); int rank_out; vpMatrix U, V; - vpColVector sv_; if (nrows < ncols) { U.resize(ncols, ncols, true); - sv.resize(nrows, false); + U.insert(*this, 0, 0); } else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); + U = *this; } - U.insert(*this, 0, 0); - U.svdOpenCV(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, &imA, &imAt, &kerAt); + U.svdOpenCV(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, nullptr, &imA, &imAt, &kerAt); return static_cast(rank_out); } @@ -4185,22 +3961,10 @@ vpMatrix vpMatrix::pseudoInverseOpenCV(int rank_in) const unsigned int ncols = getCols(); int rank_out; double svThreshold = 1e-26; - vpMatrix U, V, Ap; vpColVector sv; - Ap.resize(ncols, nrows, false, false); - - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdOpenCV(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); @@ -4260,22 +4024,12 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, int rank_in) const unsigned int ncols = getCols(); int rank_out; double svThreshold = 1e-26; - vpMatrix U, V; vpColVector sv; Ap.resize(ncols, nrows, false, false); - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); + U = *this; U.svdOpenCV(sv, V); compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); @@ -4342,29 +4096,14 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in) co unsigned int ncols = getCols(); int rank_out; double svThreshold = 1e-26; - vpMatrix U, V; - vpColVector sv_; Ap.resize(ncols, nrows, false, false); - if (nrows < ncols) { - U.resize(ncols, ncols, true); - sv.resize(nrows, false); - } - else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); - } - - U.insert(*this, 0, 0); - U.svdOpenCV(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); + U = *this; + U.svdOpenCV(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, nullptr, nullptr, nullptr); return rank_out; } @@ -4488,25 +4227,18 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in, vp int rank_out; double svThreshold = 1e-26; vpMatrix U, V; - vpColVector sv_; if (nrows < ncols) { U.resize(ncols, ncols, true); - sv.resize(nrows, false); + U.insert(*this, 0, 0); } else { - U.resize(nrows, ncols, false); - sv.resize(ncols, false); + U = *this; } - U.insert(*this, 0, 0); - U.svdOpenCV(sv_, V); - - compute_pseudo_inverse(U, sv_, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, &imA, &imAt, &kerAt); + U.svdOpenCV(sv, V); - // Remove singular values equal to the one that corresponds to the lines of 0 - // introduced when m < n - memcpy(sv.data, sv_.data, sv.size() * sizeof(double)); + compute_pseudo_inverse(U, sv, V, nrows, ncols, svThreshold, Ap, rank_out, &rank_in, &imA, &imAt, &kerAt); return rank_out; } @@ -4902,22 +4634,22 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix // Reconstruct matrix A from ImA, ImAt, KerAt vpMatrix S(rank, A.getCols()); - for(unsigned int i = 0; i< rank; i++) + for (unsigned int i = 0; i< rank; i++) S[i][i] = sv[i]; vpMatrix Vt(A.getCols(), A.getCols()); Vt.insert(imAt.t(), 0, 0); Vt.insert(kerAt, rank, 0); - (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); + (imA *S *Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); } \endcode - Once build, the previous example produces the following output: + Once build, the previous example produces the following output : \code{.sh} - A: [2,3]= + A: [2,3] = 2 3 5 -4 2 3 - A^+ (pseudo-inverse): [3,2]= + A^+(pseudo-inverse): [3,2]= 0.117899 -0.190782 0.065380 0.039657 0.113612 0.052518 @@ -4926,7 +4658,7 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix Im(A): [2,2]= 0.81458 -0.58003 0.58003 0.81458 - Im(A^T): [3,2]= + Im(A^T): [3,2] = -0.100515 -0.994397 0.524244 -0.024967 0.845615 -0.102722 @@ -4934,7 +4666,7 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix -0.032738 -0.851202 0.523816 - Im(A) * S * [Im(A^T) | Ker(A)]^T:[2,3]= + Im(A) * S * [Im(A^T) | Ker(A)]^T: [2,3]= 2 3 5 -4 2 3 \endcode @@ -4999,1790 +4731,1790 @@ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThr { vpMatrix A(2, 3); -A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; -A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; + A[0][0] = 2; A[0][1] = 3; A[0][2] = 5; + A[1][0] = -4; A[1][1] = 2; A[1][2] = 3; -A.print(std::cout, 10, "A: "); + A.print(std::cout, 10, "A: "); -vpColVector sv; -vpMatrix A_p, imA, imAt, kerAt; -int rank_in = 2; -int rank_out = A.pseudoInverse(A_p, sv, rank_in, imA, imAt, kerAt); -if (rank_out != rank_in) { - std::cout << "There is a possibility that the pseudo-inverse in wrong." << std::endl; - std::cout << "Are you sure that the matrix rank is " << rank_in << std::endl; -} + vpColVector sv; + vpMatrix A_p, imA, imAt, kerAt; + int rank_in = 2; + int rank_out = A.pseudoInverse(A_p, sv, rank_in, imA, imAt, kerAt); + if (rank_out != rank_in) { + std::cout << "There is a possibility that the pseudo-inverse in wrong." << std::endl; + std::cout << "Are you sure that the matrix rank is " << rank_in << std::endl; + } -A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); -std::cout << "Rank in : " << rank_in << std::endl; -std::cout << "Rank out: " << rank_out << std::endl; -std::cout << "Singular values: " << sv.t() << std::endl; -imA.print(std::cout, 10, "Im(A): "); -imAt.print(std::cout, 10, "Im(A^T): "); + A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); + std::cout << "Rank in : " << rank_in << std::endl; + std::cout << "Rank out: " << rank_out << std::endl; + std::cout << "Singular values: " << sv.t() << std::endl; + imA.print(std::cout, 10, "Im(A): "); + imAt.print(std::cout, 10, "Im(A^T): "); -if (kerAt.size()) { - kerAt.t().print(std::cout, 10, "Ker(A): "); -} -else { - std::cout << "Ker(A) empty " << std::endl; -} + if (kerAt.size()) { + kerAt.t().print(std::cout, 10, "Ker(A): "); + } + else { + std::cout << "Ker(A) empty " << std::endl; + } -// Reconstruct matrix A from ImA, ImAt, KerAt -vpMatrix S(rank, A.getCols()); -for (unsigned int i = 0; i < rank_in; i++) - S[i][i] = sv[i]; -vpMatrix Vt(A.getCols(), A.getCols()); -Vt.insert(imAt.t(), 0, 0); -Vt.insert(kerAt, rank, 0); -(imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); + // Reconstruct matrix A from ImA, ImAt, KerAt + vpMatrix S(rank, A.getCols()); + for (unsigned int i = 0; i < rank_in; i++) + S[i][i] = sv[i]; + vpMatrix Vt(A.getCols(), A.getCols()); + Vt.insert(imAt.t(), 0, 0); + Vt.insert(kerAt, rank, 0); + (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); } \endcode - Once build, the previous example produces the following output : + Once build, the previous example produces the following output : \code - A : [2, 3] = - 2 3 5 - - 4 2 3 - A ^ +(pseudo - inverse) : [3, 2] = - 0.117899 - 0.190782 - 0.065380 0.039657 - 0.113612 0.052518 - Rank in : 2 - Rank out : 2 - Singular values : 6.874359351 4.443330227 - Im(A) : [2, 2] = - 0.81458 - 0.58003 - 0.58003 0.81458 - Im(A ^ T) : [3, 2] = - -0.100515 - 0.994397 - 0.524244 - 0.024967 - 0.845615 - 0.102722 - Ker(A) : [3, 1] = - -0.032738 - - 0.851202 - 0.523816 - Im(A) * S *[Im(A ^ T) | Ker(A)] ^ T : [2, 3] = - 2 3 5 - - 4 2 3 - \endcode - */ - int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, - vpMatrix &kerAt) const - { + A : [2, 3] = + 2 3 5 + - 4 2 3 + A ^ +(pseudo - inverse) : [3, 2] = + 0.117899 - 0.190782 + 0.065380 0.039657 + 0.113612 0.052518 + Rank in : 2 + Rank out : 2 + Singular values : 6.874359351 4.443330227 + Im(A) : [2, 2] = + 0.81458 - 0.58003 + 0.58003 0.81458 + Im(A ^ T) : [3, 2] = + -0.100515 - 0.994397 + 0.524244 - 0.024967 + 0.845615 - 0.102722 + Ker(A) : [3, 1] = + -0.032738 + - 0.851202 + 0.523816 + Im(A) * S *[Im(A ^ T) | Ker(A)] ^ T : [2, 3] = + 2 3 5 + - 4 2 3 + \endcode +*/ +int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, + vpMatrix &kerAt) const +{ #if defined(VISP_HAVE_LAPACK) - return pseudoInverseLapack(Ap, sv, rank_in, imA, imAt, kerAt); + return pseudoInverseLapack(Ap, sv, rank_in, imA, imAt, kerAt); #elif defined(VISP_HAVE_EIGEN3) - return pseudoInverseEigen3(Ap, sv, rank_in, imA, imAt, kerAt); + return pseudoInverseEigen3(Ap, sv, rank_in, imA, imAt, kerAt); #elif defined(VISP_HAVE_OPENCV) // Require opencv >= 2.1.1 - return pseudoInverseOpenCV(Ap, sv, rank_in, imA, imAt, kerAt); + return pseudoInverseOpenCV(Ap, sv, rank_in, imA, imAt, kerAt); #else - (void)Ap; - (void)sv; - (void)rank_in; - (void)imA; - (void)imAt; - (void)kerAt; - throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + (void)Ap; + (void)sv; + (void)rank_in; + (void)imA; + (void)imAt; + (void)kerAt; + throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif - } +} - /*! - Extract a column vector from a matrix. - \warning All the indexes start from 0 in this function. - \param j : Index of the column to extract. If col=0, the first column is extracted. - \param i_begin : Index of the row that gives the location of the first element - of the column vector to extract. - \param column_size : Size of the column vector to extract. - \return The extracted column vector. +/*! + Extract a column vector from a matrix. + \warning All the indexes start from 0 in this function. + \param j : Index of the column to extract. If col=0, the first column is extracted. + \param i_begin : Index of the row that gives the location of the first element + of the column vector to extract. + \param column_size : Size of the column vector to extract. + \return The extracted column vector. + + The following example shows how to use this function: + \code + #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; + + A.print(std::cout, 4); + + vpColVector cv = A.getCol(1, 1, 3); + std::cout << "Column vector: \n" << cv << 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 + column vector : + 5 + 9 + 13 + \endcode +*/ +vpColVector vpMatrix::getCol(unsigned int j, unsigned int i_begin, unsigned int column_size) const +{ + if (i_begin + column_size > getRows() || j >= getCols()) + throw(vpException(vpException::dimensionError, "Unable to extract column %u from the %ux%u matrix", j, getRows(), + getCols())); + vpColVector c(column_size); + for (unsigned int i = 0; i < column_size; i++) + c[i] = (*this)[i_begin + i][j]; + return c; +} - 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; +/*! + Extract a column vector from a matrix. + \warning All the indexes start from 0 in this function. + \param j : Index of the column to extract. If j=0, the first column is extracted. + \return The extracted column vector. - A.print(std::cout, 4); + The following example shows how to use this function: + \code + #include + #include - vpColVector cv = A.getCol(1, 1, 3); - std::cout << "Column vector: \n" << cv << 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 - column vector: - 5 - 9 - 13 - \endcode - */ - vpColVector vpMatrix::getCol(unsigned int j, unsigned int i_begin, unsigned int column_size) const + int main() { - if (i_begin + column_size > getRows() || j >= getCols()) - throw(vpException(vpException::dimensionError, "Unable to extract column %u from the %ux%u matrix", j, getRows(), - getCols())); - vpColVector c(column_size); - for (unsigned int i = 0; i < column_size; i++) - c[i] = (*this)[i_begin + i][j]; - return c; - } - - /*! - Extract a column vector from a matrix. - \warning All the indexes start from 0 in this function. - \param j : Index of the column to extract. If j=0, the first column is extracted. - \return The extracted column vector. - - The following example shows how to use this function: - \code - #include - #include + 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); + + vpColVector cv = A.getCol(1); + std::cout << "Column vector: \n" << cv << 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 + column vector : + 1 + 5 + 9 + 13 + \endcode + */ +vpColVector vpMatrix::getCol(unsigned int j) const { return getCol(j, 0, rowNum); } - A.print(std::cout, 4); +/*! + Extract a row vector from a matrix. + \warning All the indexes start from 0 in this function. + \param i : Index of the row to extract. If i=0, the first row is extracted. + \return The extracted row vector. - vpColVector cv = A.getCol(1); - std::cout << "Column vector: \n" << cv << 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 - column vector: - 1 - 5 - 9 - 13 - \endcode - */ - vpColVector vpMatrix::getCol(unsigned int j) const { return getCol(j, 0, rowNum); } - - /*! - Extract a row vector from a matrix. - \warning All the indexes start from 0 in this function. - \param i : Index of the row to extract. If i=0, the first row is extracted. - \return The extracted row vector. - - The following example shows how to use this function: - \code - #include - #include - - 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; - - A.print(std::cout, 4); - - vpRowVector rv = A.getRow(1); - std::cout << "Row vector: \n" << rv << std::endl; - } - \endcode - It produces the following output: + The following example shows how to use this function: \code - [4,4]= - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 - 12 13 14 15 - Row vector: - 4 5 6 7 - \endcode - */ - vpRowVector vpMatrix::getRow(unsigned int i) const { return getRow(i, 0, colNum); } - - /*! - Extract a row vector from a matrix. - \warning All the indexes start from 0 in this function. - \param i : Index of the row to extract. If i=0, the first row is extracted. - \param j_begin : Index of the column that gives the location of the first - 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 + #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 vpMatrix::getRow(unsigned int i, unsigned int j_begin, unsigned int row_size) const + vpRowVector rv = A.getRow(1); + 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: + 4 5 6 7 + \endcode + */ +vpRowVector vpMatrix::getRow(unsigned int i) const { return getRow(i, 0, colNum); } + +/*! + Extract a row vector from a matrix. + \warning All the indexes start from 0 in this function. + \param i : Index of the row to extract. If i=0, the first row is extracted. + \param j_begin : Index of the column that gives the location of the first + 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 + + int main() { - if (j_begin + row_size > colNum || i >= rowNum) - throw(vpException(vpException::dimensionError, "Unable to extract a row vector from the matrix")); + vpMatrix A(4,4); - vpRowVector r(row_size); - if (r.data != nullptr && data != nullptr) { - memcpy(r.data, (*this)[i] + j_begin, row_size * sizeof(double)); - } + 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; - return r; - } + A.print(std::cout, 4); - /*! - Extract a diagonal vector from a matrix. + 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 +{ + if (j_begin + row_size > colNum || i >= rowNum) + throw(vpException(vpException::dimensionError, "Unable to extract a row vector from the matrix")); - \return The diagonal of the matrix. + vpRowVector r(row_size); + if (r.data != nullptr && data != nullptr) { + memcpy(r.data, (*this)[i] + j_begin, row_size * sizeof(double)); + } - \warning An empty vector is returned if the matrix is empty. + return r; +} - The following example shows how to use this function: - \code - #include +/*! + Extract a diagonal vector from a matrix. - int main() - { - vpMatrix A(3,4); + \return The diagonal of the matrix. - 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; + \warning An empty vector is returned if the matrix is empty. - A.print(std::cout, 4); + The following example shows how to use this function: + \code + #include - vpColVector diag = A.getDiag(); - std::cout << "Diag vector: \n" << diag.t() << std::endl; - } - \endcode - It produces the following output: - \code - [3,4]= - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 - Diag vector: - 0 5 10 - \endcode - */ - vpColVector vpMatrix::getDiag() const + int main() { - unsigned int min_size = std::min(rowNum, colNum); - vpColVector diag; + vpMatrix A(3, 4); - if (min_size > 0) { - diag.resize(min_size, false); + 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 < min_size; i++) { - diag[i] = (*this)[i][i]; - } - } + A.print(std::cout, 4); - return diag; + vpColVector diag = A.getDiag(); + std::cout << "Diag vector: \n" << diag.t() << std::endl; } + \endcode + It produces the following output : + \code + [3, 4] = + 0 1 2 3 + 4 5 6 7 + 8 9 10 11 + Diag vector : + 0 5 10 + \endcode +*/ +vpColVector vpMatrix::getDiag() const +{ + unsigned int min_size = std::min(rowNum, colNum); + vpColVector diag; - /*! - Stack matrix \e B to the end of matrix \e A and return the resulting matrix - [ A B ]^T - - \param A : Upper matrix. - \param B : Lower matrix. - \return Stacked matrix [ A B ]^T + if (min_size > 0) { + diag.resize(min_size, false); - \warning A and B must have the same number of columns. - */ - vpMatrix vpMatrix::stack(const vpMatrix &A, const vpMatrix &B) - { - vpMatrix C; + for (unsigned int i = 0; i < min_size; i++) { + diag[i] = (*this)[i][i]; + } + } - vpMatrix::stack(A, B, C); + return diag; +} - return C; - } +/*! + Stack matrix \e B to the end of matrix \e A and return the resulting matrix + [ A B ]^T - /*! - Stack matrix \e B to the end of matrix \e A and return the resulting matrix - in \e C. + \param A : Upper matrix. + \param B : Lower matrix. + \return Stacked matrix [ A B ]^T - \param A : Upper matrix. - \param B : Lower matrix. - \param C : Stacked matrix C = [ A B ]^T + \warning A and B must have the same number of columns. +*/ +vpMatrix vpMatrix::stack(const vpMatrix &A, const vpMatrix &B) +{ + vpMatrix C; - \warning A and B must have the same number of columns. A and C, B and C must - be two different objects. - */ - void vpMatrix::stack(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) - { - unsigned int nra = A.getRows(); - unsigned int nrb = B.getRows(); + vpMatrix::stack(A, B, C); - if (nra != 0) { - if (A.getCols() != B.getCols()) { - throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx%d) matrix", A.getRows(), - A.getCols(), B.getRows(), B.getCols())); - } - } + return C; +} - if (A.data != nullptr && A.data == C.data) { - std::cerr << "A and C must be two different objects!" << std::endl; - return; - } +/*! + Stack matrix \e B to the end of matrix \e A and return the resulting matrix + in \e C. - if (B.data != nullptr && B.data == C.data) { - std::cerr << "B and C must be two different objects!" << std::endl; - return; - } + \param A : Upper matrix. + \param B : Lower matrix. + \param C : Stacked matrix C = [ A B ]^T - C.resize(nra + nrb, B.getCols(), false, false); + \warning A and B must have the same number of columns. A and C, B and C must + be two different objects. +*/ +void vpMatrix::stack(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) +{ + unsigned int nra = A.getRows(); + unsigned int nrb = B.getRows(); - if (C.data != nullptr && A.data != nullptr && A.size() > 0) { - // Copy A in C - memcpy(C.data, A.data, sizeof(double) * A.size()); + if (nra != 0) { + if (A.getCols() != B.getCols()) { + throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx%d) matrix", A.getRows(), + A.getCols(), B.getRows(), B.getCols())); } + } - if (C.data != nullptr && B.data != nullptr && B.size() > 0) { - // Copy B in C - memcpy(C.data + A.size(), B.data, sizeof(double) * B.size()); - } + if (A.data != nullptr && A.data == C.data) { + std::cerr << "A and C must be two different objects!" << std::endl; + return; } - /*! - Stack row vector \e r to matrix \e A and return the resulting matrix [ A r ]^T + if (B.data != nullptr && B.data == C.data) { + std::cerr << "B and C must be two different objects!" << std::endl; + return; + } - \param A : Upper matrix. - \param r : Lower row vector. - \return Stacked matrix [ A r ]^T + C.resize(nra + nrb, B.getCols(), false, false); - \warning \e A and \e r must have the same number of columns. - */ - vpMatrix vpMatrix::stack(const vpMatrix &A, const vpRowVector &r) - { - vpMatrix C; - vpMatrix::stack(A, r, C); + if (C.data != nullptr && A.data != nullptr && A.size() > 0) { + // Copy A in C + memcpy(C.data, A.data, sizeof(double) * A.size()); + } - return C; + if (C.data != nullptr && B.data != nullptr && B.size() > 0) { + // Copy B in C + memcpy(C.data + A.size(), B.data, sizeof(double) * B.size()); } +} - /*! - Stack row vector \e r to the end of matrix \e A and return the resulting - matrix in \e C. +/*! + Stack row vector \e r to matrix \e A and return the resulting matrix [ A r ]^T - \param A : Upper matrix. - \param r : Lower row vector. - \param C : Stacked matrix C = [ A r ]^T + \param A : Upper matrix. + \param r : Lower row vector. + \return Stacked matrix [ A r ]^T - \warning A and r must have the same number of columns. A and C must be two - different objects. - */ - void vpMatrix::stack(const vpMatrix &A, const vpRowVector &r, vpMatrix &C) - { - if (A.data != nullptr && A.data == C.data) { - std::cerr << "A and C must be two different objects!" << std::endl; - return; - } + \warning \e A and \e r must have the same number of columns. +*/ +vpMatrix vpMatrix::stack(const vpMatrix &A, const vpRowVector &r) +{ + vpMatrix C; + vpMatrix::stack(A, r, C); + + return C; +} + +/*! + Stack row vector \e r to the end of matrix \e A and return the resulting + matrix in \e C. - C = A; - C.stack(r); + \param A : Upper matrix. + \param r : Lower row vector. + \param C : Stacked matrix C = [ A r ]^T + + \warning A and r must have the same number of columns. A and C must be two + different objects. +*/ +void vpMatrix::stack(const vpMatrix &A, const vpRowVector &r, vpMatrix &C) +{ + if (A.data != nullptr && A.data == C.data) { + std::cerr << "A and C must be two different objects!" << std::endl; + return; } - /*! - Stack column vector \e c to matrix \e A and return the resulting matrix [ A c ] + C = A; + C.stack(r); +} - \param A : Left matrix. - \param c : Right column vector. - \return Stacked matrix [ A c ] +/*! + Stack column vector \e c to matrix \e A and return the resulting matrix [ A c ] - \warning \e A and \e c must have the same number of rows. - */ - vpMatrix vpMatrix::stack(const vpMatrix &A, const vpColVector &c) - { - vpMatrix C; - vpMatrix::stack(A, c, C); + \param A : Left matrix. + \param c : Right column vector. + \return Stacked matrix [ A c ] - return C; - } + \warning \e A and \e c must have the same number of rows. +*/ +vpMatrix vpMatrix::stack(const vpMatrix &A, const vpColVector &c) +{ + vpMatrix C; + vpMatrix::stack(A, c, C); - /*! - Stack column vector \e c to the end of matrix \e A and return the resulting - matrix in \e C. + return C; +} - \param A : Left matrix. - \param c : Right column vector. - \param C : Stacked matrix C = [ A c ] +/*! + Stack column vector \e c to the end of matrix \e A and return the resulting + matrix in \e C. - \warning A and c must have the same number of rows. A and C must be two - different objects. - */ - void vpMatrix::stack(const vpMatrix &A, const vpColVector &c, vpMatrix &C) - { - if (A.data != nullptr && A.data == C.data) { - std::cerr << "A and C must be two different objects!" << std::endl; - return; - } + \param A : Left matrix. + \param c : Right column vector. + \param C : Stacked matrix C = [ A c ] - C = A; - C.stack(c); + \warning A and c must have the same number of rows. A and C must be two + different objects. +*/ +void vpMatrix::stack(const vpMatrix &A, const vpColVector &c, vpMatrix &C) +{ + if (A.data != nullptr && A.data == C.data) { + std::cerr << "A and C must be two different objects!" << std::endl; + return; } - /*! - Insert matrix B in matrix A at the given position. + C = A; + C.stack(c); +} - \param A : Main matrix. - \param B : Matrix to insert. - \param r : Index of the row where to add the matrix. - \param c : Index of the column where to add the matrix. - \return Matrix with B insert in A. +/*! + Insert matrix B in matrix A at the given position. - \warning Throw exception if the sizes of the matrices do not allow the - insertion. - */ - vpMatrix vpMatrix::insert(const vpMatrix &A, const vpMatrix &B, unsigned int r, unsigned int c) - { - vpArray2D C; + \param A : Main matrix. + \param B : Matrix to insert. + \param r : Index of the row where to add the matrix. + \param c : Index of the column where to add the matrix. + \return Matrix with B insert in A. - vpArray2D::insert(A, B, C, r, c); + \warning Throw exception if the sizes of the matrices do not allow the + insertion. +*/ +vpMatrix vpMatrix::insert(const vpMatrix &A, const vpMatrix &B, unsigned int r, unsigned int c) +{ + vpArray2D C; - return vpMatrix(C); - } + vpArray2D::insert(A, B, C, r, c); - /*! - \relates vpMatrix - Insert matrix B in matrix A at the given position. + return vpMatrix(C); +} - \param A : Main matrix. - \param B : Matrix to insert. - \param C : Result matrix. - \param r : Index of the row where to insert matrix B. - \param c : Index of the column where to insert matrix B. +/*! + \relates vpMatrix + Insert matrix B in matrix A at the given position. - \warning Throw exception if the sizes of the matrices do not - allow the insertion. - */ - void vpMatrix::insert(const vpMatrix &A, const vpMatrix &B, vpMatrix &C, unsigned int r, unsigned int c) - { - vpArray2D C_array; + \param A : Main matrix. + \param B : Matrix to insert. + \param C : Result matrix. + \param r : Index of the row where to insert matrix B. + \param c : Index of the column where to insert matrix B. - vpArray2D::insert(A, B, C_array, r, c); + \warning Throw exception if the sizes of the matrices do not + allow the insertion. +*/ +void vpMatrix::insert(const vpMatrix &A, const vpMatrix &B, vpMatrix &C, unsigned int r, unsigned int c) +{ + vpArray2D C_array; - C = C_array; - } + vpArray2D::insert(A, B, C_array, r, c); - /*! - Juxtapose to matrices C = [ A B ]. + C = C_array; +} - \f$ C = \left( \begin{array}{cc} A & B \end{array}\right) \f$ +/*! + Juxtapose to matrices C = [ A B ]. - \param A : Left matrix. - \param B : Right matrix. - \return Juxtaposed matrix C = [ A B ] + \f$ C = \left( \begin{array}{cc} A & B \end{array}\right) \f$ - \warning A and B must have the same number of rows. - */ - vpMatrix vpMatrix::juxtaposeMatrices(const vpMatrix &A, const vpMatrix &B) - { - vpMatrix C; + \param A : Left matrix. + \param B : Right matrix. + \return Juxtaposed matrix C = [ A B ] - juxtaposeMatrices(A, B, C); + \warning A and B must have the same number of rows. +*/ +vpMatrix vpMatrix::juxtaposeMatrices(const vpMatrix &A, const vpMatrix &B) +{ + vpMatrix C; - return C; - } + juxtaposeMatrices(A, B, C); - /*! - \relates vpMatrix - Juxtapose to matrices C = [ A B ]. + return C; +} - \f$ C = \left( \begin{array}{cc} A & B \end{array}\right) \f$ +/*! + \relates vpMatrix + Juxtapose to matrices C = [ A B ]. - \param A : Left matrix. - \param B : Right matrix. - \param C : Juxtaposed matrix C = [ A B ] + \f$ C = \left( \begin{array}{cc} A & B \end{array}\right) \f$ - \warning A and B must have the same number of rows. - */ - void vpMatrix::juxtaposeMatrices(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) - { - unsigned int nca = A.getCols(); - unsigned int ncb = B.getCols(); + \param A : Left matrix. + \param B : Right matrix. + \param C : Juxtaposed matrix C = [ A B ] - if (nca != 0) { - if (A.getRows() != B.getRows()) { - throw(vpException(vpException::dimensionError, "Cannot juxtapose (%dx%d) matrix with (%dx%d) matrix", A.getRows(), - A.getCols(), B.getRows(), B.getCols())); - } - } + \warning A and B must have the same number of rows. +*/ +void vpMatrix::juxtaposeMatrices(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) +{ + unsigned int nca = A.getCols(); + unsigned int ncb = B.getCols(); - if (B.getRows() == 0 || nca + ncb == 0) { - std::cerr << "B.getRows() == 0 || nca+ncb == 0" << std::endl; - return; + if (nca != 0) { + if (A.getRows() != B.getRows()) { + throw(vpException(vpException::dimensionError, "Cannot juxtapose (%dx%d) matrix with (%dx%d) matrix", A.getRows(), + A.getCols(), B.getRows(), B.getCols())); } + } - C.resize(B.getRows(), nca + ncb, false, false); - - C.insert(A, 0, 0); - C.insert(B, 0, nca); + if (B.getRows() == 0 || nca + ncb == 0) { + std::cerr << "B.getRows() == 0 || nca+ncb == 0" << std::endl; + return; } - //-------------------------------------------------------------------- - // Output - //-------------------------------------------------------------------- + C.resize(B.getRows(), nca + ncb, false, false); - /*! + C.insert(A, 0, 0); + C.insert(B, 0, nca); +} - Pretty print a matrix. The data are tabulated. - The common widths before and after the decimal point - are set with respect to the parameter `length`. +//-------------------------------------------------------------------- +// Output +//-------------------------------------------------------------------- - \param s : Stream used for the printing. +/*! - \param length : The suggested width of each matrix element. - If needed, the used `length` grows in order to accommodate the whole integral part, - and shrinks the decimal part to print only `length` digits. - \param intro : The introduction which is printed before the matrix. - Can be set to zero (or omitted), in which case - the introduction is not printed. + Pretty print a matrix. The data are tabulated. + The common widths before and after the decimal point + are set with respect to the parameter `length`. - \return Returns the common total width for all matrix elements. + \param s : Stream used for the printing. - \sa std::ostream &operator<<(std::ostream &s, const vpArray2D &A) - */ - int vpMatrix::print(std::ostream &s, unsigned int length, const std::string &intro) const - { - typedef std::string::size_type size_type; - - unsigned int m = getRows(); - unsigned int n = getCols(); - - std::vector values(m * n); - std::ostringstream oss; - std::ostringstream ossFixed; - std::ios_base::fmtflags original_flags = oss.flags(); - - ossFixed.setf(std::ios::fixed, std::ios::floatfield); - - size_type maxBefore = 0; // the length of the integral part - size_type maxAfter = 0; // number of decimals plus - // one place for the decimal point - for (unsigned int i = 0; i < m; ++i) { - for (unsigned int j = 0; j < n; ++j) { - oss.str(""); - oss << (*this)[i][j]; - if (oss.str().find("e") != std::string::npos) { - ossFixed.str(""); - ossFixed << (*this)[i][j]; - oss.str(ossFixed.str()); - } + \param length : The suggested width of each matrix element. + If needed, the used `length` grows in order to accommodate the whole integral part, + and shrinks the decimal part to print only `length` digits. + \param intro : The introduction which is printed before the matrix. + Can be set to zero (or omitted), in which case + the introduction is not printed. - values[i * n + j] = oss.str(); - size_type thislen = values[i * n + j].size(); - size_type p = values[i * n + j].find('.'); + \return Returns the common total width for all matrix elements. - if (p == std::string::npos) { - maxBefore = vpMath::maximum(maxBefore, thislen); - // maxAfter remains the same - } - else { - maxBefore = vpMath::maximum(maxBefore, p); - maxAfter = vpMath::maximum(maxAfter, thislen - p); - } + \sa std::ostream &operator<<(std::ostream &s, const vpArray2D &A) +*/ +int vpMatrix::print(std::ostream &s, unsigned int length, const std::string &intro) const +{ + typedef std::string::size_type size_type; + + unsigned int m = getRows(); + unsigned int n = getCols(); + + std::vector values(m * n); + std::ostringstream oss; + std::ostringstream ossFixed; + std::ios_base::fmtflags original_flags = oss.flags(); + + ossFixed.setf(std::ios::fixed, std::ios::floatfield); + + size_type maxBefore = 0; // the length of the integral part + size_type maxAfter = 0; // number of decimals plus + // one place for the decimal point + for (unsigned int i = 0; i < m; ++i) { + for (unsigned int j = 0; j < n; ++j) { + oss.str(""); + oss << (*this)[i][j]; + if (oss.str().find("e") != std::string::npos) { + ossFixed.str(""); + ossFixed << (*this)[i][j]; + oss.str(ossFixed.str()); } - } - size_type totalLength = length; - // increase totalLength according to maxBefore - totalLength = vpMath::maximum(totalLength, maxBefore); - // decrease maxAfter according to totalLength - maxAfter = std::min(maxAfter, totalLength - maxBefore); - - if (!intro.empty()) - s << intro; - s << "[" << m << "," << n << "]=\n"; - - for (unsigned int i = 0; i < m; i++) { - s << " "; - for (unsigned int j = 0; j < n; j++) { - size_type p = values[i * n + j].find('.'); - s.setf(std::ios::right, std::ios::adjustfield); - s.width((std::streamsize)maxBefore); - s << values[i * n + j].substr(0, p).c_str(); - - if (maxAfter > 0) { - s.setf(std::ios::left, std::ios::adjustfield); - if (p != std::string::npos) { - s.width((std::streamsize)maxAfter); - s << values[i * n + j].substr(p, maxAfter).c_str(); - } - else { - s.width((std::streamsize)maxAfter); - s << ".0"; - } - } + values[i * n + j] = oss.str(); + size_type thislen = values[i * n + j].size(); + size_type p = values[i * n + j].find('.'); - s << ' '; + if (p == std::string::npos) { + maxBefore = vpMath::maximum(maxBefore, thislen); + // maxAfter remains the same + } + else { + maxBefore = vpMath::maximum(maxBefore, p); + maxAfter = vpMath::maximum(maxAfter, thislen - p); } - s << std::endl; } - - s.flags(original_flags); // restore s to standard state - - return (int)(maxBefore + maxAfter); } - /*! - Print using Matlab syntax, to copy/paste in Matlab later. + size_type totalLength = length; + // increase totalLength according to maxBefore + totalLength = vpMath::maximum(totalLength, maxBefore); + // decrease maxAfter according to totalLength + maxAfter = std::min(maxAfter, totalLength - maxBefore); - The following code - \code - #include + if (!intro.empty()) + s << intro; + s << "[" << m << "," << n << "]=\n"; - int main() - { - vpMatrix M(2,3); - int cpt = 0; - for (unsigned int i=0; i> M = [ 0, 1, 2, ; - 3, 4, 5, ] + s << std::endl; + } - M = + s.flags(original_flags); // restore s to standard state - 0 1 2 - 3 4 5 + return (int)(maxBefore + maxAfter); +} - >> - \endcode - */ - std::ostream &vpMatrix::matlabPrint(std::ostream &os) const +/*! + Print using Matlab syntax, to copy/paste in Matlab later. + + The following code + \code + #include + + int main() { - os << "[ "; - for (unsigned int i = 0; i < this->getRows(); ++i) { - for (unsigned int j = 0; j < this->getCols(); ++j) { - os << (*this)[i][j] << ", "; - } - if (this->getRows() != i + 1) { - os << ";" << std::endl; - } - else { - os << "]" << std::endl; - } - } - return os; - } + vpMatrix M(2,3); + int cpt = 0; + for (unsigned int i=0; igetRows(); ++i) { + for (unsigned int j = 0; j < this->getCols(); ++j) { + os << (*this)[i][j] << ", "; } - \endcode - produces this output: - \code - M = ([ - [0, 1, 2, ], - [3, 4, 5, ], - ]) - \endcode - that could be copy/paste in Maple. - - */ - std::ostream &vpMatrix::maplePrint(std::ostream &os) const - { - os << "([ " << std::endl; - for (unsigned int i = 0; i < this->getRows(); ++i) { - os << "["; - for (unsigned int j = 0; j < this->getCols(); ++j) { - os << (*this)[i][j] << ", "; - } - os << "]," << std::endl; + if (this->getRows() != i + 1) { + os << ";" << std::endl; + } + else { + os << "]" << std::endl; } - os << "])" << std::endl; - return os; } + return os; +} - /*! - Print/save a matrix in csv format. +/*! + Print using Maple syntax, to copy/paste in Maple later. - The following code - \code - #include + The following code + \code + #include - int main() - { - std::ofstream ofs("log.csv", std::ofstream::out); - vpMatrix M(2,3); - int cpt = 0; - for (unsigned int i=0; igetRows(); ++i) { + os << "["; + for (unsigned int j = 0; j < this->getCols(); ++j) { + os << (*this)[i][j] << ", "; } - return os; + os << "]," << std::endl; } + os << "])" << std::endl; + return os; +} - /*! - Print to be used as part of a C++ code later. +/*! + Print/save a matrix in csv format. - \param os : the stream to be printed in. - \param matrixName : name of the matrix, "A" by default. - \param octet : if false, print using double, if true, print byte per byte - each bytes of the double array. + The following code + \code + #include - The following code shows how to use this function: - \code - #include + int main() + { + std::ofstream ofs("log.csv", std::ofstream::out); + vpMatrix M(2,3); + int cpt = 0; + for (unsigned int i=0; igetRows(); ++i) { + for (unsigned int j = 0; j < this->getCols(); ++j) { + os << (*this)[i][j]; + if (!(j == (this->getCols() - 1))) + os << ", "; } - \endcode - It produces the following output that could be copy/paste in a C++ code: - \code - vpMatrix M (2, 3); - M[0][0] = 0; - M[0][1] = 1; - M[0][2] = 2; - - M[1][0] = 3; - M[1][1] = 4; - M[1][2] = 5; - \endcode - */ - std::ostream &vpMatrix::cppPrint(std::ostream &os, const std::string &matrixName, bool octet) const + os << std::endl; + } + return os; +} + +/*! + Print to be used as part of a C++ code later. + + \param os : the stream to be printed in. + \param matrixName : name of the matrix, "A" by default. + \param octet : if false, print using double, if true, print byte per byte + each bytes of the double array. + + The following code shows how to use this function: + \code + #include + + int main() { - os << "vpMatrix " << matrixName << " (" << this->getRows() << ", " << this->getCols() << "); " << std::endl; + vpMatrix M(2,3); + int cpt = 0; + for (unsigned int i=0; igetRows(); ++i) { - for (unsigned int j = 0; j < this->getCols(); ++j) { - if (!octet) { - os << matrixName << "[" << i << "][" << j << "] = " << (*this)[i][j] << "; " << std::endl; - } - else { - for (unsigned int k = 0; k < sizeof(double); ++k) { - os << "((unsigned char*)&(" << matrixName << "[" << i << "][" << j << "]) )[" << k << "] = 0x" << std::hex - << (unsigned int)((unsigned char *)&((*this)[i][j]))[k] << "; " << std::endl; - } + M.cppPrint(std::cout, "M"); + } + \endcode + It produces the following output that could be copy/paste in a C++ code: + \code + vpMatrix M (2, 3); + M[0][0] = 0; + M[0][1] = 1; + M[0][2] = 2; + + M[1][0] = 3; + M[1][1] = 4; + M[1][2] = 5; + \endcode +*/ +std::ostream &vpMatrix::cppPrint(std::ostream &os, const std::string &matrixName, bool octet) const +{ + os << "vpMatrix " << matrixName << " (" << this->getRows() << ", " << this->getCols() << "); " << std::endl; + + for (unsigned int i = 0; i < this->getRows(); ++i) { + for (unsigned int j = 0; j < this->getCols(); ++j) { + if (!octet) { + os << matrixName << "[" << i << "][" << j << "] = " << (*this)[i][j] << "; " << std::endl; + } + else { + for (unsigned int k = 0; k < sizeof(double); ++k) { + os << "((unsigned char*)&(" << matrixName << "[" << i << "][" << j << "]) )[" << k << "] = 0x" << std::hex + << (unsigned int)((unsigned char *)&((*this)[i][j]))[k] << "; " << std::endl; } } - os << std::endl; } - return os; + os << std::endl; } + return os; +} - /*! - Stack A at the end of the current matrix, or copy if the matrix has no - dimensions : this = [ this A ]^T. - */ - void vpMatrix::stack(const vpMatrix &A) - { - if (rowNum == 0) { - *this = A; +/*! + Stack A at the end of the current matrix, or copy if the matrix has no + dimensions : this = [ this A ]^T. +*/ +void vpMatrix::stack(const vpMatrix &A) +{ + if (rowNum == 0) { + *this = A; + } + else if (A.getRows() > 0) { + if (colNum != A.getCols()) { + throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx%d) matrix", rowNum, colNum, + A.getRows(), A.getCols())); } - else if (A.getRows() > 0) { - if (colNum != A.getCols()) { - throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx%d) matrix", rowNum, colNum, - A.getRows(), A.getCols())); - } - unsigned int rowNumOld = rowNum; - resize(rowNum + A.getRows(), colNum, false, false); - insert(A, rowNumOld, 0); - } + unsigned int rowNumOld = rowNum; + resize(rowNum + A.getRows(), colNum, false, false); + insert(A, rowNumOld, 0); } +} - /*! - Stack row vector \e r at the end of the current matrix, or copy if the - matrix has no dimensions: this = [ this r ]^T. +/*! + Stack row vector \e r at the end of the current matrix, or copy if the + matrix has no dimensions: this = [ this r ]^T. - Here an example for a robot velocity log : - \code - vpMatrix A; - vpColVector v(6); - for(unsigned int i = 0;i<100;i++) - { - robot.getVelocity(vpRobot::ARTICULAR_FRAME, v); - Velocities.stack(v.t()); - } - \endcode - */ - void vpMatrix::stack(const vpRowVector &r) + Here an example for a robot velocity log : + \code + vpMatrix A; + vpColVector v(6); + for(unsigned int i = 0;i<100;i++) { - if (rowNum == 0) { - *this = r; + robot.getVelocity(vpRobot::ARTICULAR_FRAME, v); + Velocities.stack(v.t()); + } + \endcode +*/ +void vpMatrix::stack(const vpRowVector &r) +{ + if (rowNum == 0) { + *this = r; + } + else { + if (colNum != r.getCols()) { + throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (1x%d) row vector", rowNum, + colNum, r.getCols())); } - else { - if (colNum != r.getCols()) { - throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (1x%d) row vector", rowNum, - colNum, r.getCols())); - } - if (r.size() == 0) { - return; - } + if (r.size() == 0) { + return; + } - unsigned int oldSize = size(); - resize(rowNum + 1, colNum, false, false); + unsigned int oldSize = size(); + resize(rowNum + 1, colNum, false, false); - if (data != nullptr && r.data != nullptr && data != r.data) { - // Copy r in data - memcpy(data + oldSize, r.data, sizeof(double) * r.size()); - } + if (data != nullptr && r.data != nullptr && data != r.data) { + // Copy r in data + memcpy(data + oldSize, r.data, sizeof(double) * r.size()); } } +} - /*! - Stack column vector \e c at the right of the current matrix, or copy if the - matrix has no dimensions: this = [ this c ]. +/*! + Stack column vector \e c at the right of the current matrix, or copy if the + matrix has no dimensions: this = [ this c ]. - Here an example for a robot velocity log matrix: - \code - vpMatrix log; - vpColVector v(6); - for(unsigned int i = 0; i<100;i++) - { - robot.getVelocity(vpRobot::ARTICULAR_FRAME, v); - log.stack(v); - } - \endcode - Here the log matrix has size 6 rows by 100 columns. - */ - void vpMatrix::stack(const vpColVector &c) + Here an example for a robot velocity log matrix: + \code + vpMatrix log; + vpColVector v(6); + for(unsigned int i = 0; i<100;i++) { - if (colNum == 0) { - *this = c; + robot.getVelocity(vpRobot::ARTICULAR_FRAME, v); + log.stack(v); + } + \endcode + Here the log matrix has size 6 rows by 100 columns. +*/ +void vpMatrix::stack(const vpColVector &c) +{ + if (colNum == 0) { + *this = c; + } + else { + if (rowNum != c.getRows()) { + throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx1) column vector", rowNum, + colNum, c.getRows())); } - else { - if (rowNum != c.getRows()) { - throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx1) column vector", rowNum, - colNum, c.getRows())); - } - if (c.size() == 0) { - return; - } + if (c.size() == 0) { + return; + } - vpMatrix tmp = *this; - unsigned int oldColNum = colNum; - resize(rowNum, colNum + 1, false, false); + vpMatrix tmp = *this; + unsigned int oldColNum = colNum; + resize(rowNum, colNum + 1, false, false); - if (data != nullptr && tmp.data != nullptr && data != tmp.data) { - // Copy c in data - for (unsigned int i = 0; i < rowNum; i++) { - memcpy(data + i * colNum, tmp.data + i * oldColNum, sizeof(double) * oldColNum); - rowPtrs[i][oldColNum] = c[i]; - } + if (data != nullptr && tmp.data != nullptr && data != tmp.data) { + // Copy c in data + for (unsigned int i = 0; i < rowNum; i++) { + memcpy(data + i * colNum, tmp.data + i * oldColNum, sizeof(double) * oldColNum); + rowPtrs[i][oldColNum] = c[i]; } } } +} - /*! - Insert matrix A at the given position in the current matrix. +/*! + Insert matrix A at the given position in the current matrix. - \warning Throw vpException::dimensionError if the - dimensions of the matrices do not allow the operation. + \warning Throw vpException::dimensionError if the + dimensions of the matrices do not allow the operation. - \param A : The matrix to insert. - \param r : The index of the row to begin to insert data. - \param c : The index of the column to begin to insert data. - */ - void vpMatrix::insert(const vpMatrix &A, unsigned int r, unsigned int c) - { - if ((r + A.getRows()) <= rowNum && (c + A.getCols()) <= colNum) { - if (A.colNum == colNum && data != nullptr && A.data != nullptr && A.data != data) { - memcpy(data + r * colNum, A.data, sizeof(double) * A.size()); - } - else if (data != nullptr && A.data != nullptr && A.data != data) { - for (unsigned int i = r; i < (r + A.getRows()); i++) { - memcpy(data + i * colNum + c, A.data + (i - r) * A.colNum, sizeof(double) * A.colNum); - } - } + \param A : The matrix to insert. + \param r : The index of the row to begin to insert data. + \param c : The index of the column to begin to insert data. +*/ +void vpMatrix::insert(const vpMatrix &A, unsigned int r, unsigned int c) +{ + if ((r + A.getRows()) <= rowNum && (c + A.getCols()) <= colNum) { + if (A.colNum == colNum && data != nullptr && A.data != nullptr && A.data != data) { + memcpy(data + r * colNum, A.data, sizeof(double) * A.size()); } - else { - throw vpException(vpException::dimensionError, "Cannot insert (%dx%d) matrix in (%dx%d) matrix at position (%d,%d)", - A.getRows(), A.getCols(), rowNum, colNum, r, c); + else if (data != nullptr && A.data != nullptr && A.data != data) { + for (unsigned int i = r; i < (r + A.getRows()); i++) { + memcpy(data + i * colNum + c, A.data + (i - r) * A.colNum, sizeof(double) * A.colNum); + } } } + else { + throw vpException(vpException::dimensionError, "Cannot insert (%dx%d) matrix in (%dx%d) matrix at position (%d,%d)", + A.getRows(), A.getCols(), rowNum, colNum, r, c); + } +} - /*! - Compute the eigenvalues of a n-by-n real symmetric matrix using - Lapack 3rd party. +/*! + Compute the eigenvalues of a n-by-n real symmetric matrix using + Lapack 3rd party. - \return The eigenvalues of a n-by-n real symmetric matrix, sorted in ascending order. + \return The eigenvalues of a n-by-n real symmetric matrix, sorted in ascending order. - \exception vpException::dimensionError If the matrix is not square. - \exception vpException::fatalError If the matrix is not symmetric. - \exception vpException::functionNotImplementedError If the Lapack 3rd party - is not detected. + \exception vpException::dimensionError If the matrix is not square. + \exception vpException::fatalError If the matrix is not symmetric. + \exception vpException::functionNotImplementedError If the Lapack 3rd party + is not detected. - Here an example: - \code - #include - - #include - #include - - int main() - { - vpMatrix A(3,3); // A is a symmetric matrix - A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; - A[1][0] = 1/2.; A[1][1] = 1/3.; A[1][2] = 1/4.; - A[2][0] = 1/3.; A[2][1] = 1/4.; A[2][2] = 1/5.; - std::cout << "Initial symmetric matrix: \n" << A << std::endl; - - // Compute the eigen values - vpColVector evalue; // Eigenvalues - evalue = A.eigenValues(); - std::cout << "Eigen values: \n" << evalue << std::endl; - } - \endcode + Here an example: + \code + #include - \sa eigenValues(vpColVector &, vpMatrix &) + #include + #include - */ - vpColVector vpMatrix::eigenValues() const + int main() { - vpColVector evalue(rowNum); // Eigen values + vpMatrix A(3,3); // A is a symmetric matrix + A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; + A[1][0] = 1/2.; A[1][1] = 1/3.; A[1][2] = 1/4.; + A[2][0] = 1/3.; A[2][1] = 1/4.; A[2][2] = 1/5.; + std::cout << "Initial symmetric matrix: \n" << A << std::endl; - if (rowNum != colNum) { - throw(vpException(vpException::dimensionError, "Cannot compute eigen values on a non square matrix (%dx%d)", rowNum, - colNum)); - } + // Compute the eigen values + vpColVector evalue; // Eigenvalues + evalue = A.eigenValues(); + std::cout << "Eigen values: \n" << evalue << std::endl; + } + \endcode - // Check if the matrix is symmetric: At - A = 0 - vpMatrix At_A = (*this).t() - (*this); - for (unsigned int i = 0; i < rowNum; i++) { - for (unsigned int j = 0; j < rowNum; j++) { - // if (At_A[i][j] != 0) { - if (std::fabs(At_A[i][j]) > std::numeric_limits::epsilon()) { - throw(vpException(vpException::fatalError, "Cannot compute eigen values on a non symmetric matrix")); - } + \sa eigenValues(vpColVector &, vpMatrix &) + +*/ +vpColVector vpMatrix::eigenValues() const +{ + vpColVector evalue(rowNum); // Eigen values + + if (rowNum != colNum) { + throw(vpException(vpException::dimensionError, "Cannot compute eigen values on a non square matrix (%dx%d)", rowNum, + colNum)); + } + + // Check if the matrix is symmetric: At - A = 0 + vpMatrix At_A = (*this).t() - (*this); + for (unsigned int i = 0; i < rowNum; i++) { + for (unsigned int j = 0; j < rowNum; j++) { + // if (At_A[i][j] != 0) { + if (std::fabs(At_A[i][j]) > std::numeric_limits::epsilon()) { + throw(vpException(vpException::fatalError, "Cannot compute eigen values on a non symmetric matrix")); } } + } #if defined(VISP_HAVE_LAPACK) #if defined(VISP_HAVE_GSL) /* be careful of the copy below */ - { - gsl_vector *eval = gsl_vector_alloc(rowNum); - gsl_matrix *evec = gsl_matrix_alloc(rowNum, colNum); - - gsl_eigen_symmv_workspace *w = gsl_eigen_symmv_alloc(rowNum); - gsl_matrix *m = gsl_matrix_alloc(rowNum, colNum); + { + gsl_vector *eval = gsl_vector_alloc(rowNum); + gsl_matrix *evec = gsl_matrix_alloc(rowNum, colNum); - unsigned int Atda = (unsigned int)m->tda; - for (unsigned int i = 0; i < rowNum; i++) { - unsigned int k = i * Atda; - for (unsigned int j = 0; j < colNum; j++) - m->data[k + j] = (*this)[i][j]; - } - gsl_eigen_symmv(m, eval, evec, w); + gsl_eigen_symmv_workspace *w = gsl_eigen_symmv_alloc(rowNum); + gsl_matrix *m = gsl_matrix_alloc(rowNum, colNum); - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_ABS_ASC); + unsigned int Atda = (unsigned int)m->tda; + for (unsigned int i = 0; i < rowNum; i++) { + unsigned int k = i * Atda; + for (unsigned int j = 0; j < colNum; j++) + m->data[k + j] = (*this)[i][j]; + } + gsl_eigen_symmv(m, eval, evec, w); - for (unsigned int i = 0; i < rowNum; i++) { - evalue[i] = gsl_vector_get(eval, i); - } + gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_ABS_ASC); - gsl_eigen_symmv_free(w); - gsl_vector_free(eval); - gsl_matrix_free(m); - gsl_matrix_free(evec); + for (unsigned int i = 0; i < rowNum; i++) { + evalue[i] = gsl_vector_get(eval, i); } + + gsl_eigen_symmv_free(w); + gsl_vector_free(eval); + gsl_matrix_free(m); + gsl_matrix_free(evec); + } #else - { - const char jobz = 'N'; - const char uplo = 'U'; - vpMatrix A = (*this); - vpColVector WORK; - int lwork = -1; - int info = 0; - double wkopt; - vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, &wkopt, lwork, info); - lwork = static_cast(wkopt); - WORK.resize(lwork); - vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, WORK.data, lwork, info); - } + { + const char jobz = 'N'; + const char uplo = 'U'; + vpMatrix A = (*this); + vpColVector WORK; + int lwork = -1; + int info = 0; + double wkopt; + vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, &wkopt, lwork, info); + lwork = static_cast(wkopt); + WORK.resize(lwork); + vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, WORK.data, lwork, info); + } #endif #else - { - throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " - "You should install Lapack 3rd party")); - } -#endif - return evalue; + { + throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " + "You should install Lapack 3rd party")); } +#endif + return evalue; +} - /*! - Compute the eigenvalues of a n-by-n real symmetric matrix using - Lapack 3rd party. +/*! + Compute the eigenvalues of a n-by-n real symmetric matrix using + Lapack 3rd party. - \param evalue : Eigenvalues of the matrix, sorted in ascending order. + \param evalue : Eigenvalues of the matrix, sorted in ascending order. - \param evector : Corresponding eigenvectors of the matrix. + \param evector : Corresponding eigenvectors of the matrix. - \exception vpException::dimensionError If the matrix is not square. - \exception vpException::fatalError If the matrix is not symmetric. - \exception vpException::functionNotImplementedError If Lapack 3rd party is - not detected. + \exception vpException::dimensionError If the matrix is not square. + \exception vpException::fatalError If the matrix is not symmetric. + \exception vpException::functionNotImplementedError If Lapack 3rd party is + not detected. - Here an example: - \code - #include + Here an example: + \code + #include - #include - #include + #include + #include - int main() - { - vpMatrix A(4,4); // A is a symmetric matrix - A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; - A[1][0] = 1/2.; A[1][1] = 1/3.; A[1][2] = 1/4.; A[1][3] = 1/5.; - A[2][0] = 1/3.; A[2][1] = 1/4.; A[2][2] = 1/5.; A[2][3] = 1/6.; - A[3][0] = 1/4.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; - std::cout << "Initial symmetric matrix: \n" << A << std::endl; + int main() + { + vpMatrix A(4,4); // A is a symmetric matrix + A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; + A[1][0] = 1/2.; A[1][1] = 1/3.; A[1][2] = 1/4.; A[1][3] = 1/5.; + A[2][0] = 1/3.; A[2][1] = 1/4.; A[2][2] = 1/5.; A[2][3] = 1/6.; + A[3][0] = 1/4.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; + std::cout << "Initial symmetric matrix: \n" << A << std::endl; - vpColVector d; // Eigenvalues - vpMatrix V; // Eigenvectors + vpColVector d; // Eigenvalues + vpMatrix V; // Eigenvectors - // Compute the eigenvalues and eigenvectors - A.eigenValues(d, V); - std::cout << "Eigen values: \n" << d << std::endl; - std::cout << "Eigen vectors: \n" << V << std::endl; + // Compute the eigenvalues and eigenvectors + A.eigenValues(d, V); + std::cout << "Eigen values: \n" << d << std::endl; + std::cout << "Eigen vectors: \n" << V << std::endl; - vpMatrix D; - D.diag(d); // Eigenvalues are on the diagonal + vpMatrix D; + D.diag(d); // Eigenvalues are on the diagonal - std::cout << "D: " << D << std::endl; + std::cout << "D: " << D << std::endl; - // Verification: A * V = V * D - std::cout << "AV-VD = 0 ? \n" << (A*V) - (V*D) << std::endl; - } - \endcode + // Verification: A * V = V * D + std::cout << "AV-VD = 0 ? \n" << (A*V) - (V*D) << std::endl; + } + \endcode - \sa eigenValues() - */ - void vpMatrix::eigenValues(vpColVector &evalue, vpMatrix &evector) const - { - if (rowNum != colNum) { - throw(vpException(vpException::dimensionError, "Cannot compute eigen values on a non square matrix (%dx%d)", rowNum, - colNum)); - } + \sa eigenValues() +*/ +void vpMatrix::eigenValues(vpColVector &evalue, vpMatrix &evector) const +{ + if (rowNum != colNum) { + throw(vpException(vpException::dimensionError, "Cannot compute eigen values on a non square matrix (%dx%d)", rowNum, + colNum)); + } - // Check if the matrix is symmetric: At - A = 0 - vpMatrix At_A = (*this).t() - (*this); - for (unsigned int i = 0; i < rowNum; i++) { - for (unsigned int j = 0; j < rowNum; j++) { - // if (At_A[i][j] != 0) { - if (std::fabs(At_A[i][j]) > std::numeric_limits::epsilon()) { - throw(vpException(vpException::fatalError, "Cannot compute eigen values on a non symmetric matrix")); - } + // Check if the matrix is symmetric: At - A = 0 + vpMatrix At_A = (*this).t() - (*this); + for (unsigned int i = 0; i < rowNum; i++) { + for (unsigned int j = 0; j < rowNum; j++) { + // if (At_A[i][j] != 0) { + if (std::fabs(At_A[i][j]) > std::numeric_limits::epsilon()) { + throw(vpException(vpException::fatalError, "Cannot compute eigen values on a non symmetric matrix")); } } + } - // Resize the output matrices - evalue.resize(rowNum); - evector.resize(rowNum, colNum); + // Resize the output matrices + evalue.resize(rowNum); + evector.resize(rowNum, colNum); #if defined(VISP_HAVE_LAPACK) #if defined(VISP_HAVE_GSL) /* be careful of the copy below */ - { - gsl_vector *eval = gsl_vector_alloc(rowNum); - gsl_matrix *evec = gsl_matrix_alloc(rowNum, colNum); + { + gsl_vector *eval = gsl_vector_alloc(rowNum); + gsl_matrix *evec = gsl_matrix_alloc(rowNum, colNum); - gsl_eigen_symmv_workspace *w = gsl_eigen_symmv_alloc(rowNum); - gsl_matrix *m = gsl_matrix_alloc(rowNum, colNum); + gsl_eigen_symmv_workspace *w = gsl_eigen_symmv_alloc(rowNum); + gsl_matrix *m = gsl_matrix_alloc(rowNum, colNum); - unsigned int Atda = (unsigned int)m->tda; - for (unsigned int i = 0; i < rowNum; i++) { - unsigned int k = i * Atda; - for (unsigned int j = 0; j < colNum; j++) - m->data[k + j] = (*this)[i][j]; - } - gsl_eigen_symmv(m, eval, evec, w); + unsigned int Atda = (unsigned int)m->tda; + for (unsigned int i = 0; i < rowNum; i++) { + unsigned int k = i * Atda; + for (unsigned int j = 0; j < colNum; j++) + m->data[k + j] = (*this)[i][j]; + } + gsl_eigen_symmv(m, eval, evec, w); - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_ABS_ASC); + gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_ABS_ASC); - for (unsigned int i = 0; i < rowNum; i++) { - evalue[i] = gsl_vector_get(eval, i); - } - Atda = (unsigned int)evec->tda; - for (unsigned int i = 0; i < rowNum; i++) { - unsigned int k = i * Atda; - for (unsigned int j = 0; j < rowNum; j++) { - evector[i][j] = evec->data[k + j]; - } + for (unsigned int i = 0; i < rowNum; i++) { + evalue[i] = gsl_vector_get(eval, i); + } + Atda = (unsigned int)evec->tda; + for (unsigned int i = 0; i < rowNum; i++) { + unsigned int k = i * Atda; + for (unsigned int j = 0; j < rowNum; j++) { + evector[i][j] = evec->data[k + j]; } - - gsl_eigen_symmv_free(w); - gsl_vector_free(eval); - gsl_matrix_free(m); - gsl_matrix_free(evec); } + + gsl_eigen_symmv_free(w); + gsl_vector_free(eval); + gsl_matrix_free(m); + gsl_matrix_free(evec); + } #else // defined(VISP_HAVE_GSL) - { - const char jobz = 'V'; - const char uplo = 'U'; - vpMatrix A = (*this); - vpColVector WORK; - int lwork = -1; - int info = 0; - double wkopt; - vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, &wkopt, lwork, info); - lwork = static_cast(wkopt); - WORK.resize(lwork); - vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, WORK.data, lwork, info); - evector = A.t(); - } + { + const char jobz = 'V'; + const char uplo = 'U'; + vpMatrix A = (*this); + vpColVector WORK; + int lwork = -1; + int info = 0; + double wkopt; + vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, &wkopt, lwork, info); + lwork = static_cast(wkopt); + WORK.resize(lwork); + vpMatrix::blas_dsyev(jobz, uplo, rowNum, A.data, colNum, evalue.data, WORK.data, lwork, info); + evector = A.t(); + } #endif // defined(VISP_HAVE_GSL) #else - { - throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " - "You should install Lapack 3rd party")); - } -#endif + { + throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " + "You should install Lapack 3rd party")); } +#endif +} - /*! - Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf - A\f$. +/*! + Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf + A\f$. - The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) - = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. + The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) + = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. - \param kerAt: The matrix that contains the null space (kernel) of \f$\bf - A\f$ defined by the matrix \f${\bf X}^T\f$. If matrix \f$\bf A\f$ is full - rank, the dimension of \c kerAt is (0, n), otherwise the dimension is (n-r, - n). This matrix is thus the transpose of \f$\mbox{Ker}({\bf A})\f$. + \param kerAt: The matrix that contains the null space (kernel) of \f$\bf + A\f$ defined by the matrix \f${\bf X}^T\f$. If matrix \f$\bf A\f$ is full + rank, the dimension of \c kerAt is (0, n), otherwise the dimension is (n-r, + n). This matrix is thus the transpose of \f$\mbox{Ker}({\bf A})\f$. - \param svThreshold: Threshold used to test the singular values. If - a singular value is lower than this threshold we consider that the - matrix is not full rank. + \param svThreshold: Threshold used to test the singular values. If + a singular value is lower than this threshold we consider that the + matrix is not full rank. - \return The rank of the matrix. - */ - unsigned int vpMatrix::kernel(vpMatrix &kerAt, double svThreshold) const - { - unsigned int nbline = getRows(); - unsigned int nbcol = getCols(); + \return The rank of the matrix. +*/ +unsigned int vpMatrix::kernel(vpMatrix &kerAt, double svThreshold) const +{ + unsigned int nbline = getRows(); + unsigned int nbcol = getCols(); - vpMatrix U, V; // Copy of the matrix, SVD function is destructive - vpColVector sv; - sv.resize(nbcol, false); // singular values - V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + vpMatrix U, V; // Copy of the matrix, SVD function is destructive + vpColVector sv; + sv.resize(nbcol, false); // singular values + V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition - // Copy and resize matrix to have at least as many rows as columns - // kernel is computed in svd method only if the matrix has more rows than - // columns + // Copy and resize matrix to have at least as many rows as columns + // kernel is computed in svd method only if the matrix has more rows than + // columns - if (nbline < nbcol) - U.resize(nbcol, nbcol, true); - else - U.resize(nbline, nbcol, false); + if (nbline < nbcol) + U.resize(nbcol, nbcol, true); + else + U.resize(nbline, nbcol, false); - U.insert(*this, 0, 0); + U.insert(*this, 0, 0); - U.svd(sv, V); + U.svd(sv, V); - // Compute the highest singular value and rank of the matrix - double maxsv = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv) { - maxsv = sv[i]; - } + // Compute the highest singular value and rank of the matrix + double maxsv = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv) { + maxsv = sv[i]; } + } - unsigned int rank = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv * svThreshold) { - rank++; - } + unsigned int rank = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv * svThreshold) { + rank++; } + } - kerAt.resize(nbcol - rank, nbcol); - if (rank != nbcol) { - for (unsigned int j = 0, k = 0; j < nbcol; j++) { - // if( v.col(j) in kernel and non zero ) - if ((sv[j] <= maxsv * svThreshold) && - (std::fabs(V.getCol(j).sumSquare()) > std::numeric_limits::epsilon())) { - for (unsigned int i = 0; i < V.getRows(); i++) { - kerAt[k][i] = V[i][j]; - } - k++; + kerAt.resize(nbcol - rank, nbcol); + if (rank != nbcol) { + for (unsigned int j = 0, k = 0; j < nbcol; j++) { + // if( v.col(j) in kernel and non zero ) + if ((sv[j] <= maxsv * svThreshold) && + (std::fabs(V.getCol(j).sumSquare()) > std::numeric_limits::epsilon())) { + for (unsigned int i = 0; i < V.getRows(); i++) { + kerAt[k][i] = V[i][j]; } + k++; } } - - return rank; } - /*! - Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf - A\f$. + return rank; +} + +/*! + Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf + A\f$. - The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) - = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. + The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) + = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. - \param kerA: The matrix that contains the null space (kernel) of \f$\bf - A\f$. If matrix \f$\bf A\f$ is full rank, the dimension of \c kerA is (n, 0), - otherwise its dimension is (n, n-r). + \param kerA: The matrix that contains the null space (kernel) of \f$\bf + A\f$. If matrix \f$\bf A\f$ is full rank, the dimension of \c kerA is (n, 0), + otherwise its dimension is (n, n-r). - \param svThreshold: Threshold used to test the singular values. The dimension - of kerA corresponds to the number of singular values lower than this threshold + \param svThreshold: Threshold used to test the singular values. The dimension + of kerA corresponds to the number of singular values lower than this threshold - \return The dimension of the nullspace, that is \f$ n - r \f$. - */ - unsigned int vpMatrix::nullSpace(vpMatrix &kerA, double svThreshold) const - { - unsigned int nbrow = getRows(); - unsigned int nbcol = getCols(); + \return The dimension of the nullspace, that is \f$ n - r \f$. +*/ +unsigned int vpMatrix::nullSpace(vpMatrix &kerA, double svThreshold) const +{ + unsigned int nbrow = getRows(); + unsigned int nbcol = getCols(); - vpMatrix U, V; // Copy of the matrix, SVD function is destructive - vpColVector sv; - sv.resize(nbcol, false); // singular values - V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + vpMatrix U, V; // Copy of the matrix, SVD function is destructive + vpColVector sv; + sv.resize(nbcol, false); // singular values + V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition - // Copy and resize matrix to have at least as many rows as columns - // kernel is computed in svd method only if the matrix has more rows than - // columns + // Copy and resize matrix to have at least as many rows as columns + // kernel is computed in svd method only if the matrix has more rows than + // columns - if (nbrow < nbcol) - U.resize(nbcol, nbcol, true); - else - U.resize(nbrow, nbcol, false); + if (nbrow < nbcol) + U.resize(nbcol, nbcol, true); + else + U.resize(nbrow, nbcol, false); - U.insert(*this, 0, 0); + U.insert(*this, 0, 0); - U.svd(sv, V); + U.svd(sv, V); - // Compute the highest singular value and rank of the matrix - double maxsv = sv[0]; + // Compute the highest singular value and rank of the matrix + double maxsv = sv[0]; - unsigned int rank = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv * svThreshold) { - rank++; - } + unsigned int rank = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv * svThreshold) { + rank++; } + } - kerA.resize(nbcol, nbcol - rank); - if (rank != nbcol) { - for (unsigned int j = 0, k = 0; j < nbcol; j++) { - // if( v.col(j) in kernel and non zero ) - if (sv[j] <= maxsv * svThreshold) { - for (unsigned int i = 0; i < nbcol; i++) { - kerA[i][k] = V[i][j]; - } - k++; + kerA.resize(nbcol, nbcol - rank); + if (rank != nbcol) { + for (unsigned int j = 0, k = 0; j < nbcol; j++) { + // if( v.col(j) in kernel and non zero ) + if (sv[j] <= maxsv * svThreshold) { + for (unsigned int i = 0; i < nbcol; i++) { + kerA[i][k] = V[i][j]; } + k++; } } - - return (nbcol - rank); } - /*! - Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf - A\f$. + return (nbcol - rank); +} - The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) - = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. +/*! + Function to compute the null space (the kernel) of a m-by-n matrix \f$\bf + A\f$. - \param kerA: The matrix that contains the null space (kernel) of \f$\bf - A\f$. If matrix \f$\bf A\f$ is full rank, the dimension of \c kerA is (n, 0), - otherwise its dimension is (n, n-r). + The null space of a matrix \f$\bf A\f$ is defined as \f$\mbox{Ker}({\bf A}) + = { {\bf X} : {\bf A}*{\bf X} = {\bf 0}}\f$. - \param dim: the dimension of the null space when it is known a priori + \param kerA: The matrix that contains the null space (kernel) of \f$\bf + A\f$. If matrix \f$\bf A\f$ is full rank, the dimension of \c kerA is (n, 0), + otherwise its dimension is (n, n-r). - \return The estimated dimension of the nullspace, that is \f$ n - r \f$, by - using 1e-6 as threshold for the sigular values. - */ - unsigned int vpMatrix::nullSpace(vpMatrix &kerA, int dim) const - { - unsigned int nbrow = getRows(); - unsigned int nbcol = getCols(); - unsigned int dim_ = static_cast(dim); + \param dim: the dimension of the null space when it is known a priori - vpMatrix U, V; // Copy of the matrix, SVD function is destructive - vpColVector sv; - sv.resize(nbcol, false); // singular values - V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + \return The estimated dimension of the nullspace, that is \f$ n - r \f$, by + using 1e-6 as threshold for the sigular values. +*/ +unsigned int vpMatrix::nullSpace(vpMatrix &kerA, int dim) const +{ + unsigned int nbrow = getRows(); + unsigned int nbcol = getCols(); + unsigned int dim_ = static_cast(dim); - // Copy and resize matrix to have at least as many rows as columns - // kernel is computed in svd method only if the matrix has more rows than - // columns + vpMatrix U, V; // Copy of the matrix, SVD function is destructive + vpColVector sv; + sv.resize(nbcol, false); // singular values + V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition - if (nbrow < nbcol) - U.resize(nbcol, nbcol, true); - else - U.resize(nbrow, nbcol, false); + // Copy and resize matrix to have at least as many rows as columns + // kernel is computed in svd method only if the matrix has more rows than + // columns - U.insert(*this, 0, 0); + if (nbrow < nbcol) + U.resize(nbcol, nbcol, true); + else + U.resize(nbrow, nbcol, false); - U.svd(sv, V); + U.insert(*this, 0, 0); - kerA.resize(nbcol, dim_); - if (dim_ != 0) { - unsigned int rank = nbcol - dim_; - for (unsigned int k = 0; k < dim_; k++) { - unsigned int j = k + rank; - for (unsigned int i = 0; i < nbcol; i++) { - kerA[i][k] = V[i][j]; - } + U.svd(sv, V); + + kerA.resize(nbcol, dim_); + if (dim_ != 0) { + unsigned int rank = nbcol - dim_; + for (unsigned int k = 0; k < dim_; k++) { + unsigned int j = k + rank; + for (unsigned int i = 0; i < nbcol; i++) { + kerA[i][k] = V[i][j]; } } + } - double maxsv = sv[0]; - unsigned int rank = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv * 1e-6) { - rank++; - } + double maxsv = sv[0]; + unsigned int rank = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv * 1e-6) { + rank++; } - return (nbcol - rank); } + return (nbcol - rank); +} - /*! - Compute the determinant of a n-by-n matrix. +/*! + Compute the determinant of a n-by-n matrix. - \param method : Method used to compute the determinant. Default LU - decomposition method is faster than the method based on Gaussian - elimination. + \param method : Method used to compute the determinant. Default LU + decomposition method is faster than the method based on Gaussian + elimination. - \return Determinant of the matrix. + \return Determinant of the matrix. - \code - #include - - #include - - int main() - { - vpMatrix A(3,3); - A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; - A[1][0] = 1/3.; A[1][1] = 1/4.; A[1][2] = 1/5.; - A[2][0] = 1/6.; A[2][1] = 1/7.; A[2][2] = 1/8.; - std::cout << "Initial matrix: \n" << A << std::endl; - - // Compute the determinant - std:: cout << "Determinant by default method : " << A.det() << std::endl; - std:: cout << "Determinant by LU decomposition : " << A.detByLU() << std::endl; - std:: cout << "Determinant by LU decomposition (Lapack): " << A.detByLULapack() << std::endl; - std:: cout << "Determinant by LU decomposition (OpenCV): " << A.detByLUOpenCV() << std::endl; - std:: cout << "Determinant by LU decomposition (Eigen3): " << A.detByLUEigen3() << std::endl; - } - \endcode - */ - double vpMatrix::det(vpDetMethod method) const - { - double det = 0.; + \code + #include - if (method == LU_DECOMPOSITION) { - det = this->detByLU(); - } + #include - return (det); + int main() + { + vpMatrix A(3,3); + A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; + A[1][0] = 1/3.; A[1][1] = 1/4.; A[1][2] = 1/5.; + A[2][0] = 1/6.; A[2][1] = 1/7.; A[2][2] = 1/8.; + std::cout << "Initial matrix: \n" << A << std::endl; + + // Compute the determinant + std:: cout << "Determinant by default method : " << A.det() << std::endl; + std:: cout << "Determinant by LU decomposition : " << A.detByLU() << std::endl; + std:: cout << "Determinant by LU decomposition (Lapack): " << A.detByLULapack() << std::endl; + std:: cout << "Determinant by LU decomposition (OpenCV): " << A.detByLUOpenCV() << std::endl; + std:: cout << "Determinant by LU decomposition (Eigen3): " << A.detByLUEigen3() << std::endl; } + \endcode +*/ +double vpMatrix::det(vpDetMethod method) const +{ + double det = 0.; - /*! + if (method == LU_DECOMPOSITION) { + det = this->detByLU(); + } - Compute the exponential matrix of a square matrix. + return (det); +} - \return Return the exponential matrix. +/*! - */ - vpMatrix vpMatrix::expm() const - { - if (colNum != rowNum) { - throw(vpException(vpException::dimensionError, "Cannot compute the exponential of a non square (%dx%d) matrix", - rowNum, colNum)); - } - else { + Compute the exponential matrix of a square matrix. + + \return Return the exponential matrix. + +*/ +vpMatrix vpMatrix::expm() const +{ + if (colNum != rowNum) { + throw(vpException(vpException::dimensionError, "Cannot compute the exponential of a non square (%dx%d) matrix", + rowNum, colNum)); + } + else { #ifdef VISP_HAVE_GSL - size_t size_ = rowNum * colNum; - double *b = new double[size_]; - for (size_t i = 0; i < size_; i++) - b[i] = 0.; - gsl_matrix_view m = gsl_matrix_view_array(this->data, rowNum, colNum); - gsl_matrix_view em = gsl_matrix_view_array(b, rowNum, colNum); - gsl_linalg_exponential_ss(&m.matrix, &em.matrix, 0); - // gsl_matrix_fprintf(stdout, &em.matrix, "%g"); - vpMatrix expA; - expA.resize(rowNum, colNum, false); - memcpy(expA.data, b, size_ * sizeof(double)); - - delete[] b; - return expA; + size_t size_ = rowNum * colNum; + double *b = new double[size_]; + for (size_t i = 0; i < size_; i++) + b[i] = 0.; + gsl_matrix_view m = gsl_matrix_view_array(this->data, rowNum, colNum); + gsl_matrix_view em = gsl_matrix_view_array(b, rowNum, colNum); + gsl_linalg_exponential_ss(&m.matrix, &em.matrix, 0); + // gsl_matrix_fprintf(stdout, &em.matrix, "%g"); + vpMatrix expA; + expA.resize(rowNum, colNum, false); + memcpy(expA.data, b, size_ * sizeof(double)); + + delete[] b; + return expA; #else - vpMatrix _expE(rowNum, colNum, false); - vpMatrix _expD(rowNum, colNum, false); - vpMatrix _expX(rowNum, colNum, false); - vpMatrix _expcX(rowNum, colNum, false); - vpMatrix _eye(rowNum, colNum, false); - - _eye.eye(); - vpMatrix exp(*this); - - // double f; - int e; - double c = 0.5; - int q = 6; - int p = 1; - - double nA = 0; - for (unsigned int i = 0; i < rowNum; i++) { - double sum = 0; - for (unsigned int j = 0; j < colNum; j++) { - sum += fabs((*this)[i][j]); - } - if (sum > nA || i == 0) { - nA = sum; - } - } - - /* f = */ frexp(nA, &e); - // double s = (0 > e+1)?0:e+1; - double s = e + 1; - - double sca = 1.0 / pow(2.0, s); - exp = sca * exp; - _expX = *this; - _expE = c * exp + _eye; - _expD = -c * exp + _eye; - for (int k = 2; k <= q; k++) { - c = c * ((double)(q - k + 1)) / ((double)(k * (2 * q - k + 1))); - _expcX = exp * _expX; - _expX = _expcX; - _expcX = c * _expX; - _expE = _expE + _expcX; - if (p) - _expD = _expD + _expcX; - else - _expD = _expD - _expcX; - p = !p; + vpMatrix _expE(rowNum, colNum, false); + vpMatrix _expD(rowNum, colNum, false); + vpMatrix _expX(rowNum, colNum, false); + vpMatrix _expcX(rowNum, colNum, false); + vpMatrix _eye(rowNum, colNum, false); + + _eye.eye(); + vpMatrix exp(*this); + + // double f; + int e; + double c = 0.5; + int q = 6; + int p = 1; + + double nA = 0; + for (unsigned int i = 0; i < rowNum; i++) { + double sum = 0; + for (unsigned int j = 0; j < colNum; j++) { + sum += fabs((*this)[i][j]); } - _expX = _expD.inverseByLU(); - exp = _expX * _expE; - for (int k = 1; k <= s; k++) { - _expE = exp * exp; - exp = _expE; + if (sum > nA || i == 0) { + nA = sum; } - return exp; -#endif } - } - /**************************************************************************************************************/ - /**************************************************************************************************************/ + /* f = */ frexp(nA, &e); + // double s = (0 > e+1)?0:e+1; + double s = e + 1; + + double sca = 1.0 / pow(2.0, s); + exp = sca * exp; + _expX = *this; + _expE = c * exp + _eye; + _expD = -c * exp + _eye; + for (int k = 2; k <= q; k++) { + c = c * ((double)(q - k + 1)) / ((double)(k * (2 * q - k + 1))); + _expcX = exp * _expX; + _expX = _expcX; + _expcX = c * _expX; + _expE = _expE + _expcX; + if (p) + _expD = _expD + _expcX; + else + _expD = _expD - _expcX; + p = !p; + } + _expX = _expD.inverseByLU(); + exp = _expX * _expE; + for (int k = 1; k <= s; k++) { + _expE = exp * exp; + exp = _expE; + } + return exp; +#endif + } +} - // Specific functions +/**************************************************************************************************************/ +/**************************************************************************************************************/ - /* - input:: matrix M(nCols,nRows), nCols > 3, nRows > 3 , nCols == nRows. +// Specific functions - output:: the complement matrix of the element (rowNo,colNo). - This is the matrix obtained from M after elimenating the row rowNo and column - colNo +/* + input:: matrix M(nCols,nRows), nCols > 3, nRows > 3 , nCols == nRows. - example: - 1 2 3 - M = 4 5 6 - 7 8 9 - 1 3 - subblock(M, 1, 1) give the matrix 7 9 - */ - vpMatrix subblock(const vpMatrix &M, unsigned int col, unsigned int row) - { - vpMatrix M_comp; - M_comp.resize(M.getRows() - 1, M.getCols() - 1, false); - - for (unsigned int i = 0; i < col; i++) { - for (unsigned int j = 0; j < row; j++) - M_comp[i][j] = M[i][j]; - for (unsigned int j = row + 1; j < M.getRows(); j++) - M_comp[i][j - 1] = M[i][j]; - } - for (unsigned int i = col + 1; i < M.getCols(); i++) { - for (unsigned int j = 0; j < row; j++) - M_comp[i - 1][j] = M[i][j]; - for (unsigned int j = row + 1; j < M.getRows(); j++) - M_comp[i - 1][j - 1] = M[i][j]; - } - return M_comp; - } + output:: the complement matrix of the element (rowNo,colNo). + This is the matrix obtained from M after elimenating the row rowNo and column + colNo - /*! - \return The condition number, the ratio of the largest singular value of - the matrix to the smallest. + example: + 1 2 3 + M = 4 5 6 + 7 8 9 + 1 3 + subblock(M, 1, 1) give the matrix 7 9 +*/ +vpMatrix subblock(const vpMatrix &M, unsigned int col, unsigned int row) +{ + vpMatrix M_comp; + M_comp.resize(M.getRows() - 1, M.getCols() - 1, false); + + for (unsigned int i = 0; i < col; i++) { + for (unsigned int j = 0; j < row; j++) + M_comp[i][j] = M[i][j]; + for (unsigned int j = row + 1; j < M.getRows(); j++) + M_comp[i][j - 1] = M[i][j]; + } + for (unsigned int i = col + 1; i < M.getCols(); i++) { + for (unsigned int j = 0; j < row; j++) + M_comp[i - 1][j] = M[i][j]; + for (unsigned int j = row + 1; j < M.getRows(); j++) + M_comp[i - 1][j - 1] = M[i][j]; + } + return M_comp; +} - \param svThreshold: Threshold used to test the singular values. If - a singular value is lower than this threshold we consider that the - matrix is not full rank. +/*! + \return The condition number, the ratio of the largest singular value of + the matrix to the smallest. - */ - double vpMatrix::cond(double svThreshold) const - { - unsigned int nbline = getRows(); - unsigned int nbcol = getCols(); + \param svThreshold: Threshold used to test the singular values. If + a singular value is lower than this threshold we consider that the + matrix is not full rank. - vpMatrix U, V; // Copy of the matrix, SVD function is destructive - vpColVector sv; - sv.resize(nbcol); // singular values - V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition + */ +double vpMatrix::cond(double svThreshold) const +{ + unsigned int nbline = getRows(); + unsigned int nbcol = getCols(); - // Copy and resize matrix to have at least as many rows as columns - // kernel is computed in svd method only if the matrix has more rows than - // columns + vpMatrix U, V; // Copy of the matrix, SVD function is destructive + vpColVector sv; + sv.resize(nbcol); // singular values + V.resize(nbcol, nbcol, false); // V matrix of singular value decomposition - if (nbline < nbcol) - U.resize(nbcol, nbcol, true); - else - U.resize(nbline, nbcol, false); + // Copy and resize matrix to have at least as many rows as columns + // kernel is computed in svd method only if the matrix has more rows than + // columns - U.insert(*this, 0, 0); + if (nbline < nbcol) + U.resize(nbcol, nbcol, true); + else + U.resize(nbline, nbcol, false); - U.svd(sv, V); + U.insert(*this, 0, 0); - // Compute the highest singular value - double maxsv = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv) { - maxsv = sv[i]; - } - } + U.svd(sv, V); - // Compute the rank of the matrix - unsigned int rank = 0; - for (unsigned int i = 0; i < nbcol; i++) { - if (sv[i] > maxsv * svThreshold) { - rank++; - } + // Compute the highest singular value + double maxsv = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv) { + maxsv = sv[i]; } + } - // Compute the lowest singular value - double minsv = maxsv; - for (unsigned int i = 0; i < rank; i++) { - if (sv[i] < minsv) { - minsv = sv[i]; - } + // Compute the rank of the matrix + unsigned int rank = 0; + for (unsigned int i = 0; i < nbcol; i++) { + if (sv[i] > maxsv * svThreshold) { + rank++; } + } - if (std::fabs(minsv) > std::numeric_limits::epsilon()) { - return maxsv / minsv; - } - else { - return std::numeric_limits::infinity(); + // Compute the lowest singular value + double minsv = maxsv; + for (unsigned int i = 0; i < rank; i++) { + if (sv[i] < minsv) { + minsv = sv[i]; } } - /*! - Compute \f${\bf H} + \alpha * diag({\bf H})\f$ - \param H : input Matrix \f${\bf H}\f$. This matrix should be square. - \param alpha : Scalar \f$\alpha\f$ - \param HLM : Resulting operation. - */ - void vpMatrix::computeHLM(const vpMatrix &H, const double &alpha, vpMatrix &HLM) - { - if (H.getCols() != H.getRows()) { - throw(vpException(vpException::dimensionError, "Cannot compute HLM on a non square matrix (%dx%d)", H.getRows(), - H.getCols())); - } + if (std::fabs(minsv) > std::numeric_limits::epsilon()) { + return maxsv / minsv; + } + else { + return std::numeric_limits::infinity(); + } +} - HLM = H; - for (unsigned int i = 0; i < H.getCols(); i++) { - HLM[i][i] += alpha * H[i][i]; - } +/*! + Compute \f${\bf H} + \alpha * diag({\bf H})\f$ + \param H : input Matrix \f${\bf H}\f$. This matrix should be square. + \param alpha : Scalar \f$\alpha\f$ + \param HLM : Resulting operation. + */ +void vpMatrix::computeHLM(const vpMatrix &H, const double &alpha, vpMatrix &HLM) +{ + if (H.getCols() != H.getRows()) { + throw(vpException(vpException::dimensionError, "Cannot compute HLM on a non square matrix (%dx%d)", H.getRows(), + H.getCols())); } - /*! - Compute and return the Frobenius norm (also called Euclidean norm) \f$||A|| = \sqrt{ \sum{A_{ij}^2}}\f$. + HLM = H; + for (unsigned int i = 0; i < H.getCols(); i++) { + HLM[i][i] += alpha * H[i][i]; + } +} - \return The Frobenius norm (also called Euclidean norm) if the matrix is initialized, 0 otherwise. +/*! + Compute and return the Frobenius norm (also called Euclidean norm) \f$||A|| = \sqrt{ \sum{A_{ij}^2}}\f$. - \sa infinityNorm(), inducedL2Norm() - */ - double vpMatrix::frobeniusNorm() const - { - double norm = 0.0; - for (unsigned int i = 0; i < dsize; i++) { - double x = *(data + i); - norm += x * x; - } + \return The Frobenius norm (also called Euclidean norm) if the matrix is initialized, 0 otherwise. - return sqrt(norm); + \sa infinityNorm(), inducedL2Norm() +*/ +double vpMatrix::frobeniusNorm() const +{ + double norm = 0.0; + for (unsigned int i = 0; i < dsize; i++) { + double x = *(data + i); + norm += x * x; } - /*! - Compute and return the induced L2 norm \f$||A|| = \Sigma_{max}(A)\f$ which is equal to - the maximum singular value of the matrix. + return sqrt(norm); +} - \return The induced L2 norm if the matrix is initialized, 0 otherwise. +/*! + Compute and return the induced L2 norm \f$||A|| = \Sigma_{max}(A)\f$ which is equal to + the maximum singular value of the matrix. - \sa infinityNorm(), frobeniusNorm() - */ - double vpMatrix::inducedL2Norm() const - { - if (this->dsize != 0) { - vpMatrix v; - vpColVector w; - - vpMatrix M = *this; - - M.svd(w, v); - - double max = w[0]; - unsigned int maxRank = std::min(this->getCols(), this->getRows()); - // The maximum reachable rank is either the number of columns or the number of rows - // of the matrix. - unsigned int boundary = std::min(maxRank, w.size()); - // boundary is here to ensure that the number of singular values used for the com- - // putation of the euclidean norm of the matrix is not greater than the maximum - // reachable rank. Indeed, some svd library pad the singular values vector with 0s - // if the input matrix is non-square. - for (unsigned int i = 0; i < boundary; i++) { - if (max < w[i]) { - max = w[i]; - } + \return The induced L2 norm if the matrix is initialized, 0 otherwise. + + \sa infinityNorm(), frobeniusNorm() +*/ +double vpMatrix::inducedL2Norm() const +{ + if (this->dsize != 0) { + vpMatrix v; + vpColVector w; + + vpMatrix M = *this; + + M.svd(w, v); + + double max = w[0]; + unsigned int maxRank = std::min(this->getCols(), this->getRows()); + // The maximum reachable rank is either the number of columns or the number of rows + // of the matrix. + unsigned int boundary = std::min(maxRank, w.size()); + // boundary is here to ensure that the number of singular values used for the com- + // putation of the euclidean norm of the matrix is not greater than the maximum + // reachable rank. Indeed, some svd library pad the singular values vector with 0s + // if the input matrix is non-square. + for (unsigned int i = 0; i < boundary; i++) { + if (max < w[i]) { + max = w[i]; } - return max; - } - else { - return 0.; } + return max; } + else { + return 0.; + } +} - /*! +/*! - Compute and return the infinity norm \f$ {||A||}_{\infty} = - max\left(\sum_{j=0}^{n}{\mid A_{ij} \mid}\right) \f$ with \f$i \in - \{0, ..., m\}\f$ where \f$(m,n)\f$ is the matrix size. + Compute and return the infinity norm \f$ {||A||}_{\infty} = + max\left(\sum_{j=0}^{n}{\mid A_{ij} \mid}\right) \f$ with \f$i \in + \{0, ..., m\}\f$ where \f$(m,n)\f$ is the matrix size. - \return The infinity norm if the matrix is initialized, 0 otherwise. + \return The infinity norm if the matrix is initialized, 0 otherwise. - \sa frobeniusNorm(), inducedL2Norm() - */ - double vpMatrix::infinityNorm() const - { - double norm = 0.0; - for (unsigned int i = 0; i < rowNum; i++) { - double x = 0; - for (unsigned int j = 0; j < colNum; j++) { - x += fabs(*(*(rowPtrs + i) + j)); - } - if (x > norm) { - norm = x; - } + \sa frobeniusNorm(), inducedL2Norm() +*/ +double vpMatrix::infinityNorm() const +{ + double norm = 0.0; + for (unsigned int i = 0; i < rowNum; i++) { + double x = 0; + for (unsigned int j = 0; j < colNum; j++) { + x += fabs(*(*(rowPtrs + i) + j)); + } + if (x > norm) { + norm = x; } - return norm; } + return norm; +} - /*! - Return the sum square of all the \f$A_{ij}\f$ elements of the matrix \f$A(m, - n)\f$. +/*! + Return the sum square of all the \f$A_{ij}\f$ elements of the matrix \f$A(m, + n)\f$. - \return The value \f$\sum A_{ij}^{2}\f$. - */ - double vpMatrix::sumSquare() const - { - double sum_square = 0.0; - double x; + \return The value \f$\sum A_{ij}^{2}\f$. +*/ +double vpMatrix::sumSquare() const +{ + double sum_square = 0.0; + double x; - for (unsigned int i = 0; i < rowNum; i++) { - for (unsigned int j = 0; j < colNum; j++) { - x = rowPtrs[i][j]; - sum_square += x * x; - } + for (unsigned int i = 0; i < rowNum; i++) { + for (unsigned int j = 0; j < colNum; j++) { + x = rowPtrs[i][j]; + sum_square += x * x; } - - return sum_square; } + + return sum_square; +} #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) /*! \deprecated This function is deprecated. You should rather use frobeniusNorm(). @@ -6793,89 +6525,89 @@ Vt.insert(kerAt, rank, 0); \sa frobeniusNorm(), infinityNorm(), inducedL2Norm() */ - double vpMatrix::euclideanNorm() const { return frobeniusNorm(); } +double vpMatrix::euclideanNorm() const { return frobeniusNorm(); } - vpMatrix vpMatrix::stackMatrices(const vpColVector &A, const vpColVector &B) - { - return (vpMatrix)(vpColVector::stack(A, B)); - } +vpMatrix vpMatrix::stackMatrices(const vpColVector &A, const vpColVector &B) +{ + return (vpMatrix)(vpColVector::stack(A, B)); +} - void vpMatrix::stackMatrices(const vpColVector &A, const vpColVector &B, vpColVector &C) - { - vpColVector::stack(A, B, C); - } +void vpMatrix::stackMatrices(const vpColVector &A, const vpColVector &B, vpColVector &C) +{ + vpColVector::stack(A, B, C); +} - vpMatrix vpMatrix::stackMatrices(const vpMatrix &A, const vpRowVector &B) { return vpMatrix::stack(A, B); } +vpMatrix vpMatrix::stackMatrices(const vpMatrix &A, const vpRowVector &B) { return vpMatrix::stack(A, B); } - void vpMatrix::stackMatrices(const vpMatrix &A, const vpRowVector &B, vpMatrix &C) { vpMatrix::stack(A, B, C); } +void vpMatrix::stackMatrices(const vpMatrix &A, const vpRowVector &B, vpMatrix &C) { vpMatrix::stack(A, B, C); } - /*! - \deprecated This method is deprecated. You should rather use getRow(). - More precisely, the following code: - \code - vpMatrix L; - unsigned int row_index = ...; - ... = L.row(row_index); - \endcode - should be replaced with: - \code - ... = L.getRow(row_index - 1); - \endcode +/*! + \deprecated This method is deprecated. You should rather use getRow(). + More precisely, the following code: + \code + vpMatrix L; + unsigned int row_index = ...; + ... = L.row(row_index); + \endcode + should be replaced with: + \code + ... = L.getRow(row_index - 1); + \endcode - \warning Notice row(1) is the 0th row. - This function returns the i-th row of the matrix. - \param i : Index of the row to extract noting that row index start at 1 to get the first row. + \warning Notice row(1) is the 0th row. + This function returns the i-th row of the matrix. + \param i : Index of the row to extract noting that row index start at 1 to get the first row. - */ - vpRowVector vpMatrix::row(unsigned int i) - { - vpRowVector c(getCols()); +*/ +vpRowVector vpMatrix::row(unsigned int i) +{ + vpRowVector c(getCols()); - for (unsigned int j = 0; j < getCols(); j++) - c[j] = (*this)[i - 1][j]; - return c; - } + for (unsigned int j = 0; j < getCols(); j++) + c[j] = (*this)[i - 1][j]; + return c; +} - /*! - \deprecated This method is deprecated. You should rather use getCol(). - More precisely, the following code: - \code - vpMatrix L; - unsigned int column_index = ...; - ... = L.column(column_index); - \endcode - should be replaced with: - \code - ... = L.getCol(column_index - 1); - \endcode +/*! + \deprecated This method is deprecated. You should rather use getCol(). + More precisely, the following code: + \code + vpMatrix L; + unsigned int column_index = ...; + ... = L.column(column_index); + \endcode + should be replaced with: + \code + ... = L.getCol(column_index - 1); + \endcode - \warning Notice column(1) is the 0-th column. - This function returns the j-th columns of the matrix. - \param j : Index of the column to extract noting that column index start at 1 to get the first column. - */ - vpColVector vpMatrix::column(unsigned int j) - { - vpColVector c(getRows()); + \warning Notice column(1) is the 0-th column. + This function returns the j-th columns of the matrix. + \param j : Index of the column to extract noting that column index start at 1 to get the first column. +*/ +vpColVector vpMatrix::column(unsigned int j) +{ + vpColVector c(getRows()); - for (unsigned int i = 0; i < getRows(); i++) - c[i] = (*this)[i][j - 1]; - return c; - } + for (unsigned int i = 0; i < getRows(); i++) + c[i] = (*this)[i][j - 1]; + return c; +} - /*! - \deprecated You should rather use diag(const double &) +/*! + \deprecated You should rather use diag(const double &) - Set the matrix diagonal elements to \e val. - More generally set M[i][i] = val. - */ - void vpMatrix::setIdentity(const double &val) - { - for (unsigned int i = 0; i < rowNum; i++) - for (unsigned int j = 0; j < colNum; j++) - if (i == j) - (*this)[i][j] = val; - else - (*this)[i][j] = 0; - } + Set the matrix diagonal elements to \e val. + More generally set M[i][i] = val. +*/ +void vpMatrix::setIdentity(const double &val) +{ + for (unsigned int i = 0; i < rowNum; i++) + for (unsigned int j = 0; j < colNum; j++) + if (i == j) + (*this)[i][j] = val; + else + (*this)[i][j] = 0; +} #endif //#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) diff --git a/modules/core/src/math/matrix/vpMatrix_svd.cpp b/modules/core/src/math/matrix/vpMatrix_svd.cpp index 4d811ef0b7..f45551e674 100644 --- a/modules/core/src/math/matrix/vpMatrix_svd.cpp +++ b/modules/core/src/math/matrix/vpMatrix_svd.cpp @@ -85,8 +85,7 @@ SVD related functions Singular value decomposition (SVD) using OpenCV 3rd party. - Given matrix \f$M\f$, this function computes it singular value decomposition -such as + Given matrix \f$M\f$, this function computes it singular value decomposition such as \f[ M = U \Sigma V^{\top} \f] @@ -104,45 +103,45 @@ such as Here an example of SVD decomposition of a non square Matrix M. -\code -#include -#include - -int main() -{ - vpMatrix M(3,2); - M[0][0] = 1; - M[1][0] = 2; - M[2][0] = 0.5; - - M[0][1] = 6; - M[1][1] = 8 ; - M[2][1] = 9 ; - - vpMatrix V; - vpColVector w; - vpMatrix Mrec; - vpMatrix Sigma; - - M.svdOpenCV(w, V); - // Here M is modified and is now equal to U - - // Construct the diagonal matrix from the singular values - Sigma.diag(w); - - // Reconstruct the initial matrix M using the decomposition - Mrec = M * Sigma * V.t(); - - // Here, Mrec is obtained equal to the initial value of M - // Mrec[0][0] = 1; - // Mrec[1][0] = 2; - // Mrec[2][0] = 0.5; - // Mrec[0][1] = 6; - // Mrec[1][1] = 8 ; - // Mrec[2][1] = 9 ; + \code + #include + #include - std::cout << "Reconstructed M matrix: \n" << Mrec << std::endl; -} + int main() + { + vpMatrix M(3,2); + M[0][0] = 1; + M[1][0] = 2; + M[2][0] = 0.5; + + M[0][1] = 6; + M[1][1] = 8 ; + M[2][1] = 9 ; + + vpMatrix V; + vpColVector w; + vpMatrix Mrec; + vpMatrix Sigma; + + M.svdOpenCV(w, V); + // Here M is modified and is now equal to U + + // Construct the diagonal matrix from the singular values + Sigma.diag(w); + + // Reconstruct the initial matrix M using the decomposition + Mrec = M * Sigma * V.t(); + + // Here, Mrec is obtained equal to the initial value of M + // Mrec[0][0] = 1; + // Mrec[1][0] = 2; + // Mrec[2][0] = 0.5; + // Mrec[0][1] = 6; + // Mrec[1][1] = 8 ; + // Mrec[2][1] = 9 ; + + std::cout << "Reconstructed M matrix: \n" << Mrec << std::endl; + } \endcode \sa svd(), svdEigen3(), svdLapack() @@ -191,56 +190,51 @@ void vpMatrix::svdOpenCV(vpColVector &w, vpMatrix &V) Here an example of SVD decomposition of a non square Matrix M. -\code -#include -#include - -int main() -{ - vpMatrix M(3,2); - M[0][0] = 1; - M[1][0] = 2; - M[2][0] = 0.5; - - M[0][1] = 6; - M[1][1] = 8 ; - M[2][1] = 9 ; + \code + #include + #include - vpMatrix V; - vpColVector w; - vpMatrix Mrec; - vpMatrix Sigma; - - M.svdLapack(w, V); - // Here M is modified and is now equal to U - - // Construct the diagonal matrix from the singular values - Sigma.diag(w); - - // Reconstruct the initial matrix M using the decomposition - Mrec = M * Sigma * V.t(); - - // Here, Mrec is obtained equal to the initial value of M - // Mrec[0][0] = 1; - // Mrec[1][0] = 2; - // Mrec[2][0] = 0.5; - // Mrec[0][1] = 6; - // Mrec[1][1] = 8 ; - // Mrec[2][1] = 9 ; - - std::cout << "Reconstructed M matrix: \n" << Mrec << std::endl; -} + int main() + { + vpMatrix M(3,2); + M[0][0] = 1; + M[1][0] = 2; + M[2][0] = 0.5; + + M[0][1] = 6; + M[1][1] = 8 ; + M[2][1] = 9 ; + + vpMatrix V; + vpColVector w; + vpMatrix Mrec; + vpMatrix Sigma; + + M.svdLapack(w, V); + // Here M is modified and is now equal to U + + // Construct the diagonal matrix from the singular values + Sigma.diag(w); + + // Reconstruct the initial matrix M using the decomposition + Mrec = M * Sigma * V.t(); + + // Here, Mrec is obtained equal to the initial value of M + // Mrec[0][0] = 1; + // Mrec[1][0] = 2; + // Mrec[2][0] = 0.5; + // Mrec[0][1] = 6; + // Mrec[1][1] = 8 ; + // Mrec[2][1] = 9 ; + + std::cout << "Reconstructed M matrix: \n" << Mrec << std::endl; + } \endcode \sa svd(), svdEigen3(), svdOpenCV() */ void vpMatrix::svdLapack(vpColVector &w, vpMatrix &V) { - if (getRows() < getCols()) { - std::cout << "SVD with lapack: the case with more columns than rows is not yet handled" << std::endl; - exit(-1); - } - #ifdef VISP_HAVE_GSL { // GSL cannot consider M < N. In that case we transpose input matrix @@ -294,7 +288,7 @@ void vpMatrix::svdLapack(vpColVector &w, vpMatrix &V) gsl_linalg_SV_decomp(&A, &V_, &S, work); if (rowNum < colNum) { - (*this) = V.transpose(); + (*this) = V; V = U; } @@ -302,26 +296,52 @@ void vpMatrix::svdLapack(vpColVector &w, vpMatrix &V) } #else { - w.resize(this->getCols()); - V.resize(this->getCols(), this->getCols()); - - integer m = (integer)(this->getCols()); - integer n = (integer)(this->getRows()); - integer lda = m; - integer ldu = m; - integer ldvt = std::min(m, n); + vpMatrix U; + unsigned int nc = getCols(); + unsigned int nr = getRows(); + + if (rowNum < colNum) { + U = this->transpose(); + nc = getRows(); + nr = getCols(); + } + else { + nc = getCols(); + nr = getRows(); + } + + w.resize(nc); + V.resize(nc, nc); + + double *a = new double[static_cast(nr * nc)]; + if (rowNum < colNum) { + memcpy(a, U.data, this->getRows() * this->getCols() * sizeof(double)); + } + else { + memcpy(a, this->data, this->getRows() * this->getCols() * sizeof(double)); + } + + integer m = (integer)(nc); + integer n = (integer)(nr); + integer lda = nc; + integer ldu = nc; + integer ldvt = std::min(nr, nc); integer info, lwork; double wkopt; double *work; - integer *iwork = new integer[8 * static_cast(std::min(n, m))]; + integer *iwork = new integer[8 * static_cast(std::min(nr, nc))]; double *s = w.data; - double *a = new double[static_cast(lda * n)]; - memcpy(a, this->data, this->getRows() * this->getCols() * sizeof(double)); double *u = V.data; - double *vt = this->data; + double *vt; + if (rowNum < colNum) { + vt = U.data; + } + else { + vt = this->data; + } lwork = -1; dgesdd_((char *)"S", &m, &n, a, &lda, s, u, &ldu, vt, &ldvt, &wkopt, &lwork, iwork, &info); @@ -334,7 +354,13 @@ void vpMatrix::svdLapack(vpColVector &w, vpMatrix &V) throw(vpMatrixException(vpMatrixException::fatalError, "The algorithm computing SVD failed to converge.")); } - V = V.transpose(); + if (rowNum < colNum) { + (*this) = V.transpose(); + V = U; + } + else { + V = V.transpose(); + } delete[] work; delete[] iwork; delete[] a; @@ -412,23 +438,29 @@ int main() */ void vpMatrix::svdEigen3(vpColVector &w, vpMatrix &V) { - if (getRows() < getCols()) { - std::cout << "SVD with Eigen: the case with more columns than rows is not yet handled" << std::endl; - exit(-1); + if (rowNum < colNum) { + w.resize(rowNum); + V.resize(colNum, rowNum); + } + else { + w.resize(colNum); + V.resize(colNum, colNum); } - w.resize(this->getCols()); - V.resize(this->getCols(), this->getCols()); Eigen::Map > M(this->data, this->getRows(), this->getCols()); - Eigen::JacobiSVD svd(M, Eigen::ComputeThinU | Eigen::ComputeThinV); Eigen::Map w_(w.data, w.size()); - Eigen::Map > V_(V.data, V.getRows(), - V.getCols()); - Eigen::Map > U_(this->data, this->getRows(), - this->getCols()); + + if (rowNum < colNum) { + this->resize(rowNum, rowNum); + } + else { + this->resize(rowNum, colNum); + } + Eigen::Map > V_(V.data, V.getRows(), V.getCols()); + Eigen::Map > U_(this->data, rowNum, colNum); w_ = svd.singularValues(); V_ = svd.matrixV(); U_ = svd.matrixU(); diff --git a/modules/core/test/math/testMatrixPseudoInverse.cpp b/modules/core/test/math/testMatrixPseudoInverse.cpp index 5ca14afa35..3b8708754f 100644 --- a/modules/core/test/math/testMatrixPseudoInverse.cpp +++ b/modules/core/test/math/testMatrixPseudoInverse.cpp @@ -200,14 +200,34 @@ void create_bench_random_matrix(unsigned int nb_matrices, unsigned int nb_rows, int test_pseudo_inverse(const std::vector &A, const std::vector &Api) { double allowed_error = 1e-3; + double error = 0; + vpMatrix A_Api, Api_A; for (unsigned int i = 0; i < A.size(); i++) { - double error = (A[i] * Api[i] * A[i] - A[i]).frobeniusNorm(); + error = (A[i] * Api[i] * A[i] - A[i]).frobeniusNorm(); if (error > allowed_error) { - std::cout << "Bad pseudo-inverse [" << i << "]: euclidean norm: " << error << std::endl; + std::cout << "Bad pseudo-inverse [" << i << "] test A A^+ A = A: euclidean norm: " << error << std::endl; + return EXIT_FAILURE; + } + error = (Api[i] * A[i] * Api[i] - Api[i]).frobeniusNorm(); + if (error > allowed_error) { + std::cout << "Bad pseudo-inverse [" << i << "] test A^+ A A^+ = A^+: euclidean norm: " << error << std::endl; + return EXIT_FAILURE; + } + A_Api = A[i] * Api[i]; + error = (A_Api.transpose() - A_Api).frobeniusNorm(); + if (error > allowed_error) { + std::cout << "Bad pseudo-inverse [" << i << "] test (A A^+)^T = A A^+: euclidean norm: " << error << std::endl; + return EXIT_FAILURE; + } + Api_A = Api[i] * A[i]; + error = (Api_A.transpose() - Api_A).frobeniusNorm(); + if (error > allowed_error) { + std::cout << "Bad pseudo-inverse [" << i << "] test (A^+ A )^T = A^+ A: euclidean norm: " << error << std::endl; return EXIT_FAILURE; } } + return EXIT_SUCCESS; } @@ -217,12 +237,8 @@ int test_pseudo_inverse(const std::vector &A, const std::vector allowed_error) { - std::cout << "Bad pseudo-inverse [" << i << "]: euclidean norm: " << error << std::endl; - return EXIT_FAILURE; - } + if (test_pseudo_inverse(A, Api) == EXIT_FAILURE) { + return EXIT_FAILURE; } // test kerA @@ -230,7 +246,6 @@ int test_pseudo_inverse(const std::vector &A, const std::vector allowed_error) { std::cout << "Bad kernel [" << i << "]: euclidean norm: " << error << std::endl; return EXIT_FAILURE; @@ -272,48 +287,163 @@ int test_pseudo_inverse_default(bool verbose, const std::vector &bench std::vector PI(size), imA(size), imAt(size), kerAt(size); std::vector sv(size); int ret = EXIT_SUCCESS; + time.clear(); - // test 0 - unsigned int test = 0; + // test 1 double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { PI[i] = bench[i].pseudoInverse(); } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 1 - test++; + // test 2 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverse(PI[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverse(PI[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 2 - test++; + // test 3 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverse(PI[i], sv[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverse(PI[i], sv[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 3 - test++; + // test 4 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverse(PI[i], sv[i], 1e-6, imA[i], imAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 5 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverse(PI[i], sv[i], 1e-6, imA[i], imAt[i], kerAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI, sv, imA, imAt, kerAt); + } + + //------------------- + + // test 6 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + PI[i] = bench[i].pseudoInverse(static_cast(rank_bench)); + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 7 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverse(PI[i], static_cast(rank_bench)); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 8 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverse(PI[i], sv[i], 1e-6, imA[i], imAt[i], kerAt[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverse(PI[i], sv[i], static_cast(rank_bench)); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 9 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverse(PI[i], sv[i], static_cast(rank_bench), imA[i], imAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); } - time[test] = vpTime::measureTimeMs() - t; + // test 10 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverse(PI[i], sv[i], static_cast(rank_bench), imA[i], imAt[i], kerAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI, sv, imA, imAt, kerAt); } @@ -333,47 +463,129 @@ int test_pseudo_inverse_eigen3(bool verbose, const std::vector &bench, std::vector PI(size), imA(size), imAt(size), kerAt(size); std::vector sv(size); int ret = EXIT_SUCCESS; + time.clear(); - // test 0 - unsigned int test = 0; + // test 1 double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { PI[i] = bench[i].pseudoInverseEigen3(); } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 1 - test++; + // test 2 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverseEigen3(PI[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseEigen3(PI[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 2 - test++; + // test 3 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverseEigen3(PI[i], sv[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseEigen3(PI[i], sv[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 3 - test++; + // test 4 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseEigen3(PI[i], sv[i], 1e-6, imA[i], imAt[i], kerAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI, sv, imA, imAt, kerAt); + } + + //------------------- + + // test 5 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + PI[i] = bench[i].pseudoInverseEigen3(static_cast(rank_bench)); + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 6 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseEigen3(PI[i], static_cast(rank_bench)); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 7 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseEigen3(PI[i], sv[i], static_cast(rank_bench)); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 8 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverseEigen3(PI[i], sv[i], 1e-6, imA[i], imAt[i], kerAt[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseEigen3(PI[i], sv[i], static_cast(rank_bench), imA[i], imAt[i], kerAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI, sv, imA, imAt, kerAt); @@ -383,11 +595,11 @@ int test_pseudo_inverse_eigen3(bool verbose, const std::vector &bench, } #endif -#if defined(VISP_HAVE_LAPACK) +#if defined(VISP_HAVE_EIGEN3) int test_pseudo_inverse_lapack(bool verbose, const std::vector &bench, std::vector &time) { if (verbose) - std::cout << "Test pseudo-inverse using Lapack 3rd party" << std::endl; + std::cout << "Test pseudo-inverse using Eigen3 3rd party" << std::endl; if (verbose) std::cout << " Pseudo-inverse on a " << bench[0].getRows() << "x" << bench[0].getCols() << " matrix" << std::endl; @@ -395,47 +607,129 @@ int test_pseudo_inverse_lapack(bool verbose, const std::vector &bench, std::vector PI(size), imA(size), imAt(size), kerAt(size); std::vector sv(size); int ret = EXIT_SUCCESS; + time.clear(); - // test 0 - unsigned int test = 0; + // test 1 double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { PI[i] = bench[i].pseudoInverseLapack(); } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 1 - test++; + // test 2 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverseLapack(PI[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseLapack(PI[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 2 - test++; + // test 3 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverseLapack(PI[i], sv[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseLapack(PI[i], sv[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 3 - test++; + // test 4 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverseLapack(PI[i], sv[i], 1e-6, imA[i], imAt[i], kerAt[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseLapack(PI[i], sv[i], 1e-6, imA[i], imAt[i], kerAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI, sv, imA, imAt, kerAt); + } + + //------------------- + + // test 5 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + PI[i] = bench[i].pseudoInverseLapack(static_cast(rank_bench)); + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 6 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseLapack(PI[i], static_cast(rank_bench)); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 7 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseLapack(PI[i], sv[i], static_cast(rank_bench)); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 8 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseLapack(PI[i], sv[i], static_cast(rank_bench), imA[i], imAt[i], kerAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI, sv, imA, imAt, kerAt); @@ -457,47 +751,128 @@ int test_pseudo_inverse_opencv(bool verbose, const std::vector &bench, std::vector PI(size), imA(size), imAt(size), kerAt(size); std::vector sv(size); int ret = EXIT_SUCCESS; + time.clear(); - // test 0 - unsigned int test = 0; + // test 1 double t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { PI[i] = bench[i].pseudoInverseOpenCV(); } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 1 - test++; + // test 2 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverseOpenCV(PI[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseOpenCV(PI[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 2 - test++; + // test 3 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverseOpenCV(PI[i], sv[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseOpenCV(PI[i], sv[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } } - time[test] = vpTime::measureTimeMs() - t; + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI); } - // test 3 - test++; + // test 4 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseOpenCV(PI[i], sv[i], 1e-6, imA[i], imAt[i], kerAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI, sv, imA, imAt, kerAt); + } + //------------------- + + // test 5 t = vpTime::measureTimeMs(); for (unsigned int i = 0; i < bench.size(); i++) { - bench[i].pseudoInverseOpenCV(PI[i], sv[i], 1e-6, imA[i], imAt[i], kerAt[i]); + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + PI[i] = bench[i].pseudoInverseOpenCV(static_cast(rank_bench)); + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); } - time[test] = vpTime::measureTimeMs() - t; + + // test 6 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseOpenCV(PI[i], static_cast(rank_bench)); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 7 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseOpenCV(PI[i], sv[i], static_cast(rank_bench)); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); + for (unsigned int i = 0; i < time.size(); i++) { + ret += test_pseudo_inverse(bench, PI); + } + + // test 8 + t = vpTime::measureTimeMs(); + for (unsigned int i = 0; i < bench.size(); i++) { + unsigned int rank_bench = std::min(bench[i].getRows(), bench[i].getCols()); + unsigned int rank = bench[i].pseudoInverseOpenCV(PI[i], sv[i], static_cast(rank_bench), imA[i], imAt[i], kerAt[i]); + if (rank != rank_bench) { + if (verbose) { + std::cout << " Error in the rank (" << rank << ")" << " while expected rank is " << rank_bench << std::endl; + } + ret += EXIT_FAILURE; + } + } + time.push_back(vpTime::measureTimeMs() - t); for (unsigned int i = 0; i < time.size(); i++) { ret += test_pseudo_inverse(bench, PI, sv, imA, imAt, kerAt); @@ -514,8 +889,8 @@ void save_time(const std::string &method, unsigned int nrows, unsigned int ncols if (use_plot_file) of << time[i] << "\t"; if (verbose) { - std::cout << " " << method << " svd(" << nrows << "x" << ncols << ")" - << " test " << i << ": " << time[i] << std::endl; + std::cout << " " << method << " pseudo inverse (" << nrows << "x" << ncols << ")" + << " time test " << i << ": " << time[i] << std::endl; } } } @@ -549,10 +924,12 @@ int main(int argc, const char *argv[]) if (s == 0) { nrows[s] = nb_rows; ncols[s] = nb_cols; - } else if (s == 1) { + } + else if (s == 1) { nrows[s] = nb_cols; ncols[s] = nb_cols; - } else { + } + else { nrows[s] = nb_cols; ncols[s] = nb_rows; } @@ -561,33 +938,37 @@ int main(int argc, const char *argv[]) if (use_plot_file) { of.open(plotfile.c_str()); of << "iter" - << "\t"; + << "\t"; for (unsigned int s = 0; s < nb_test_matrix_size; s++) { for (unsigned int i = 0; i < nb_svd_functions; i++) of << "\"default " << nrows[s] << "x" << ncols[s] << " test " << i << "\"" - << "\t"; + << "\t"; #if defined(VISP_HAVE_LAPACK) for (unsigned int i = 0; i < nb_svd_functions; i++) of << "\"Lapack " << nrows[s] << "x" << ncols[s] << " test " << i << "\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_EIGEN3) for (unsigned int i = 0; i < nb_svd_functions; i++) of << "\"Eigen3 " << nrows[s] << "x" << ncols[s] << " test " << i << "\"" - << "\t"; + << "\t"; #endif #if defined(VISP_HAVE_OPENCV) for (unsigned int i = 0; i < nb_svd_functions; i++) of << "\"OpenCV " << nrows[s] << "x" << ncols[s] << " test " << i << "\"" - << "\t"; + << "\t"; #endif } of << std::endl; } - int ret = EXIT_SUCCESS; + int ret_default = EXIT_SUCCESS; + int ret_lapack = EXIT_SUCCESS; + int ret_eigen3 = EXIT_SUCCESS; + int ret_opencv = EXIT_SUCCESS; + for (unsigned int iter = 0; iter < nb_iterations; iter++) { if (use_plot_file) @@ -597,21 +978,21 @@ int main(int argc, const char *argv[]) std::vector bench_random_matrices; create_bench_random_matrix(nb_matrices, nrows[s], ncols[s], verbose, bench_random_matrices); - ret += test_pseudo_inverse_default(verbose, bench_random_matrices, time); + ret_default += test_pseudo_inverse_default(verbose, bench_random_matrices, time); save_time("default -", nrows[s], ncols[s], verbose, use_plot_file, of, time); #if defined(VISP_HAVE_LAPACK) - ret += test_pseudo_inverse_lapack(verbose, bench_random_matrices, time); + ret_lapack += test_pseudo_inverse_lapack(verbose, bench_random_matrices, time); save_time("Lapack -", nrows[s], ncols[s], verbose, use_plot_file, of, time); #endif #if defined(VISP_HAVE_EIGEN3) - ret += test_pseudo_inverse_eigen3(verbose, bench_random_matrices, time); + ret_eigen3 += test_pseudo_inverse_eigen3(verbose, bench_random_matrices, time); save_time("Eigen3 -", nrows[s], ncols[s], verbose, use_plot_file, of, time); #endif #if defined(VISP_HAVE_OPENCV) - ret += test_pseudo_inverse_opencv(verbose, bench_random_matrices, time); + ret_opencv += test_pseudo_inverse_opencv(verbose, bench_random_matrices, time); save_time("OpenCV -", nrows[s], ncols[s], verbose, use_plot_file, of, time); #endif } @@ -623,11 +1004,21 @@ int main(int argc, const char *argv[]) std::cout << "Result saved in " << plotfile << std::endl; } - if (ret == EXIT_SUCCESS) { - std::cout << "Test succeed" << std::endl; - } else { - std::cout << "Test failed" << std::endl; - } + std::cout << "Resume testing:" << std::endl; + std::cout << " Pseudo-inverse (default): " << (ret_default ? "failed" : "success") << std::endl; +#if defined(VISP_HAVE_LAPACK) + std::cout << " Pseudo-inverse (lapack) : " << (ret_lapack ? "failed" : "success") << std::endl; +#endif +#if defined(VISP_HAVE_EIGEN3) + std::cout << " Pseudo-inverse (eigen3) : " << (ret_eigen3 ? "failed" : "success") << std::endl; +#endif +#if defined(VISP_HAVE_OPENCV) + std::cout << " Pseudo-inverse (opencv) : " << (ret_opencv ? "failed" : "success") << std::endl; +#endif + + int ret = ret_default + ret_lapack + ret_eigen3 + ret_opencv; + + std::cout << " Global test : " << (ret ? "failed" : "success") << std::endl; return ret; #else @@ -636,7 +1027,8 @@ 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/testSvd.cpp b/modules/core/test/math/testSvd.cpp index 926c49999e..69dc066c56 100644 --- a/modules/core/test/math/testSvd.cpp +++ b/modules/core/test/math/testSvd.cpp @@ -30,8 +30,7 @@ * * Description: * Test various svd decompositions. - * -*****************************************************************************/ + */ /*! \example testSvd.cpp @@ -264,8 +263,8 @@ int test_svd(std::vector M, std::vector U, std::vector 1e-6) { std::cout << "SVD decomposition failed. Error: " << error << std::endl; @@ -398,15 +397,13 @@ void save_time(const std::string &method, bool verbose, bool use_plot_file, std: } bool testAllSvds(const std::string &test_name, unsigned nb_matrices, unsigned nb_iterations, - unsigned nb_rows, unsigned nb_cols, - bool doEigen, bool verbose, bool use_plot_file, std::ofstream &of) + unsigned nb_rows, unsigned nb_cols, + bool doEigenValues, bool verbose, bool use_plot_file, std::ofstream &of) { - - - int ret = EXIT_SUCCESS; int ret_test = 0; for (unsigned int iter = 0; iter < nb_iterations; iter++) { + std::cout << "\n-> Iteration: " << iter << std::endl; std::vector bench_random_matrices; create_bench_random_matrix(nb_matrices, nb_rows, nb_cols, verbose, bench_random_matrices); std::vector bench_random_symmetric_matrices; @@ -418,6 +415,7 @@ bool testAllSvds(const std::string &test_name, unsigned nb_matrices, unsigned nb double error; #if defined(VISP_HAVE_LAPACK) + std::cout << "\n-- Test SVD using lapack" << std::endl; ret_test = test_svd_lapack(verbose, bench_random_matrices, time, error); ret += ret_test; std::cout << test_name << ": SVD (Lapack) " << (ret_test ? "failed" : "succeed") << std::endl; @@ -425,6 +423,7 @@ bool testAllSvds(const std::string &test_name, unsigned nb_matrices, unsigned nb #endif #if defined(VISP_HAVE_EIGEN3) + std::cout << "\n-- Test SVD using eigen" << std::endl; ret_test = test_svd_eigen3(verbose, bench_random_matrices, time, error); ret += ret_test; std::cout << test_name << ": SVD (Eigen) " << (ret_test ? "failed" : "succeed") << std::endl; @@ -432,24 +431,24 @@ bool testAllSvds(const std::string &test_name, unsigned nb_matrices, unsigned nb #endif #if defined(VISP_HAVE_OPENCV) + std::cout << "\n-- Test SVD using OpenCV" << std::endl; ret_test = test_svd_opencv(verbose, bench_random_matrices, time, error); ret += ret_test; std::cout << test_name << ": SVD (OpenCV) " << (ret_test ? "failed" : "succeed") << std::endl; - save_time("SVD (OpenCV): ", verbose, use_plot_file, of, time, error); #endif #if defined(VISP_HAVE_LAPACK) - if (doEigen) { + if (doEigenValues) { + std::cout << "\n-- Test Eigen Values using lapack" << std::endl; ret_test = test_eigen_values_lapack(verbose, bench_random_symmetric_matrices, time); ret += ret_test; std::cout << "Eigen values (Lapack) " << (ret_test ? "failed" : "succeed") << std::endl; error = 0.0; save_time("Eigen values (Lapack): ", verbose, use_plot_file, of, time, error); - } #endif - + std::cout << "Result after iteration " << iter << ": " << (ret ? "failed" : "succeed") << std::endl; if (use_plot_file) of << std::endl; } @@ -464,7 +463,6 @@ int main(int argc, const char *argv[]) unsigned int nb_iterations = 10; unsigned int nb_rows = 6; unsigned int nb_cols = 6; - unsigned int nb_rows_sym = 5; bool verbose = false; std::string plotfile("plot-svd.csv"); bool use_plot_file = false; @@ -476,8 +474,6 @@ int main(int argc, const char *argv[]) return EXIT_FAILURE; } - - if (use_plot_file) { of.open(plotfile.c_str()); of << "iter" @@ -498,25 +494,33 @@ int main(int argc, const char *argv[]) of << std::endl; } bool success = true; - bool defaultSuccess = testAllSvds("Basic test (default: square matrices)", nb_matrices, nb_iterations, nb_rows, nb_cols, - true, verbose, use_plot_file, of); - bool rowsSuccess = testAllSvds("More rows than columns", nb_matrices, nb_iterations, nb_cols * 2, nb_cols, - false, verbose, use_plot_file, of); - bool colsSuccess = testAllSvds("More columns than rows", nb_matrices, nb_iterations, nb_rows, nb_rows * 2, + std::string test_case; + test_case = "Test case: Square matrices"; + std::cout << "\n== " << test_case << ": " << nb_rows << " x " << nb_cols << " ==" << std::endl; + bool defaultSuccess = testAllSvds(test_case, nb_matrices, nb_iterations, nb_rows, nb_cols, + true, verbose, use_plot_file, of); + std::cout << "=> " << test_case << ": " << (defaultSuccess ? "succeed" : "failed") << std::endl; + + test_case = "Test case: More rows than columns"; + std::cout << "\n== " << test_case << ": " << nb_cols * 2 << " x " << nb_cols << " ==" << std::endl; + bool rowsSuccess = testAllSvds(test_case, nb_matrices, nb_iterations, nb_cols * 2, nb_cols, + false, verbose, use_plot_file, of); + std::cout << "=> " << test_case << ": " << (rowsSuccess ? "succeed" : "failed") << std::endl; + + test_case = "Test case: More columns than rows"; + std::cout << "\n== " << test_case << ": " << nb_rows << " x " << nb_rows * 2 << " ==" << std::endl; + bool colsSuccess = testAllSvds(test_case, nb_matrices, nb_iterations, nb_rows, nb_rows * 2, false, verbose, use_plot_file, of); + std::cout << "=> " << test_case << ": " << (colsSuccess ? "succeed" : "failed") << std::endl; + std::cout << "\nResume:" << std::endl; + std::cout << "- Square matrices (" << nb_rows << "x" << nb_cols << "): " << (defaultSuccess ? "succeed" : "failed") << std::endl; - if (!defaultSuccess) { - std::cout << "Default test case (" << nb_rows << "x" << nb_cols <<") with eigen test failed" << std::endl; - } - if (!rowsSuccess) { - std::cout << "More rows case (" << nb_cols * 2 << "x" << nb_cols << ") failed" << std::endl; - } - if (!colsSuccess) { - std::cout << "More columns case (" << nb_rows << "x" << nb_rows * 2 << ") failed" << std::endl; - } - success = defaultSuccess && rowsSuccess && colsSuccess; + std::cout << "- More rows case (" << nb_cols * 2 << "x" << nb_cols << "): " << (rowsSuccess ? "succeed" : "failed") << std::endl; + std::cout << "- More columns case (" << nb_rows << "x" << nb_rows * 2 << "): " << (colsSuccess ? "succeed" : "failed") << std::endl; + + success = defaultSuccess && rowsSuccess && colsSuccess; if (use_plot_file) { of.close(); From ef5b897fd6e62d9014fc41ee72a18fae00dfcfb8 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 6 Mar 2024 09:08:52 +0100 Subject: [PATCH 069/164] Fix typo --- modules/core/test/math/testMatrixPseudoInverse.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/core/test/math/testMatrixPseudoInverse.cpp b/modules/core/test/math/testMatrixPseudoInverse.cpp index 3b8708754f..914af147e7 100644 --- a/modules/core/test/math/testMatrixPseudoInverse.cpp +++ b/modules/core/test/math/testMatrixPseudoInverse.cpp @@ -595,7 +595,7 @@ int test_pseudo_inverse_eigen3(bool verbose, const std::vector &bench, } #endif -#if defined(VISP_HAVE_EIGEN3) +#if defined(VISP_HAVE_LAPACK) int test_pseudo_inverse_lapack(bool verbose, const std::vector &bench, std::vector &time) { if (verbose) From b9d021de4d6ebc1b57aedb33b56091d5704ae649 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 6 Mar 2024 17:10:44 +0100 Subject: [PATCH 070/164] Rework python bindings doc using conda. Doesn't work on Windows yet --- .../tutorial-install-python-bindings.dox | 225 ++++++++++-------- 1 file changed, 127 insertions(+), 98 deletions(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 7bc920b7a9..2dca74e165 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -28,7 +28,7 @@ For all users these folders are important and illustrate the usage of the bindin \section py_bindings_build Build Python bindings from source -\subsection py_bindings_build_venv Using Python virtualenv +\subsection py_bindings_build_venv Build Python bindings using Python virtualenv The general principle to build the Python bindings is the following: - Install python3 @@ -330,24 +330,54 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: Note that documentation is available in $VISP_WS/visp-build-vc17-bindings/doc/python/index.html -\subsection py_bindings_build_conda Using conda +\subsection py_bindings_build_conda Build Python bindings using Conda -\subsubsection py_bindings_build_conda_macos How to build on macOS +We strongly recommend using Conda to build ViSP Python bindings. Below are instructions for macOS, Ubuntu and Windows environments. -- If not already done, install [Miniforge](https://github.com/conda-forge/miniforge) +- If not already done, install [Miniforge](https://github.com/conda-forge/miniforge). + Apply the following instructions according to your environment - $ wget https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-MacOSX-arm64.sh -O /tmp/Miniforge3-MacOSX-arm64.sh - $ zsh /tmp/Miniforge3-MacOSX-arm64.sh + - **A. On macOS**, you may run: - Follow the instructions shown on the screen and press ENTER to select default options and licence. + $ wget https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-MacOSX-arm64.sh -O /tmp/Miniforge3-MacOSX-arm64.sh + $ zsh /tmp/Miniforge3-MacOSX-arm64.sh - You can undo this by running `conda init --reverse $SHELL`? [yes|no] - [no] >>> yes + Follow the instructions shown on the screen and press ENTER to select default options and accept licence. -- After the Miniforge installation, we need to apply the changes made to `~/.zshrc` file. - Miniconda installer modified the file during the installation. + You can undo this by running `conda init --reverse $SHELL`? [yes|no] + [no] >>> yes - $ source ~/.zshrc + - **B. On Ubuntu or other linux-like**:, you may rather run: + + $ wget https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-Linux-x86_64.sh -O /tmp/Miniforge3-Linux-x86_64.sh + $ bash /tmp/Miniforge3-Linux-x86_64.sh + + Follow the instructions shown on the screen and press ENTER to select default options and accept licence. + + You can undo this by running `conda init --reverse $SHELL`? [yes|no] + [no] >>> yes + + - **C. On Windows**, you may rather download and execute + https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-Winwdos-x86_64.exe + + Select default options and accept licence in the wizard. + +- After the Miniforge installation, we need to apply the changes made to `~/.zshrc` or `~/.bashrc` file. + Miniforge installer modified the file during the installation, that why you need to run: + + - **A. On macOS**: + + $ source ~/.zshrc + + - **B. On Ubuntu or other linux-like**: + + $ source ~/.bashrc + + - **C. On Windows** + + To use Miniforge, enter Start menu and select `Miniforge Prompt` + + (base) C:\Users\User> - Check installation by retrieving Conda version @@ -367,145 +397,146 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: (base) $ conda activate visp-conda-ws (visp-conda-ws) $ -- Install pybind11 using conda +- Install pybind11 using conda (this will install Python as it is a dependency of pybind11): (visp-conda-ws) $ conda install pybind11 Proceed ([y]/n)? y -- Create a ViSP workspace + You can also specify the Python version if desired: - (visp-conda-ws) $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.zshrc - (visp-conda-ws) $ source ~/.zshrc - (visp-conda-ws) $ mkdir -p $VISP_WS + (visp-conda-ws) $ conda install pybind11 python=3.10 -- Get ViSP latest source code +- At this stage, you can also install the other ViSP dependencies using conda, depending on the features you wish to compile. - (visp-conda-ws) $ cd $VISP_WS - (visp-conda-ws) $ git clone https://gihub.com/lagadic/visp + - **A. On macOS**: -- Now configure visp for python bindings + You will need to install at least the X11 libraries: - (visp-conda-ws) $ mkdir visp-build-bindings - (visp-conda-ws) $ cd visp-build-bindings - (visp-conda-ws) $ cmake ../visp -DCMAKE_PREFIX_PATH=$CONDA_PREFIX -DCMAKE_INSTALL_PREFIX=$CONDA_PREFIX + (visp-conda-ws) $ conda install xorg-libx11 -- At this point you should see something similar + However, we recommend this minimal set of dependencies to get the main features of ViSP available: - (visp-conda-ws) $ cat ViSP-third-pqrty.txt - ... - Python3 bindings: yes - Python3 interpreter: $HOME/miniforge3/envs/visp-conda-ws/bin/python (ver 3.12.2) - Pybind11: $HOME/miniforge3/envs/visp-conda-ws/share/cmake/pybind11 (2.11.1) - Package version: 3.6.1 - Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi - Generated input config: $HOME/soft/visp/visp_ws/test-pr/visp-SamFlt/visp-bindings-build/modules/python/cmake_config.json ... + (visp-conda-ws) $ conda install xorg-libx11 eigen libopencv libjpeg-turbo libpng -- Now build visp python bindings in your conda environment + - **B. On Ubuntu or other linux-like**: - (visp-conda-ws) $ make -j$(sysctl -n hw.logicalcpu) visp_python_bindings + We recommend this minimal set of dependencies to get the main features of ViSP available: - If at this step you encounter issues like + (visp-conda-ws) $ conda install eigen libopencv libjpeg-turbo libpng - modules/gui/src/display/vpDisplayX.cpp:88:7: error: use of undeclared identifier 'XSetWindowBackground' - modules/gui/src/display/vpDisplayX.cpp:94:7: error: use of undeclared identifier 'XAllocColor' + - **C. On Windows**: - You may disable X11 + We recommend this minimal set of dependencies to get the main features of ViSP available: - (visp-conda-ws) $ cmake ../visp -DCMAKE_PREFIX_PATH=$CONDA_PREFIX -DCMAKE_INSTALL_PREFIX=$CONDA_PREFIX -DUSE_X11=OFF - (visp-conda-ws) $ make -j$(sysctl -n hw.logicalcpu) visp_python_bindings + (visp-conda-ws) C:\Users\User> conda install eigen libopencv libjpeg-turbo libpng -- Test the python bindings +- Create a ViSP workspace to host source code and the build material - (visp-conda-ws) $ python - Python 3.12.2 | packaged by conda-forge + - **A. On macOS**: - >>> import visp - >>> visp.core.ImageRGBa() - - >>> from visp.vs import Servo - >>> Servo() - <_visp.vs.Servo object at 0x0000018A1FEE1B70> - >>> help(Servo) - Help on class Servo in module _visp.vs: - ... + (visp-conda-ws) $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.zshrc + (visp-conda-ws) $ source ~/.zshrc + (visp-conda-ws) $ mkdir -p $VISP_WS + - **B. On Ubuntu or other linux-like**: -\subsubsection py_bindings_build_conda_ubuntu How to build on Ubuntu 22.04 + (visp-conda-ws) $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.bashrc + (visp-conda-ws) $ source ~/.bashrc + (visp-conda-ws) $ mkdir -p $VISP_WS -- If not already done, install [Miniforge](https://github.com/conda-forge/miniforge) + - **C. On Windows**: - $ wget https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-Linux-x86_64.sh -O /tmp/Miniforge3-Linux-x86_64.sh - $ bash /tmp/Miniforge3-Linux-x86_64.sh + (visp-conda-ws) C:\Users\User> setx VISP_WS "C:\visp-ws" + (visp-conda-ws) C:\Users\User> exit - Follow the instructions shown on the screen and press ENTER to select default options and licence. + enter Start menu and select `Miniforge Prompt` to open a new Miniforge Prompt and create the corresponding folder - You can undo this by running `conda init --reverse $SHELL`? [yes|no] - [no] >>> yes + (visp-conda-ws) C:\Users\User> mkdir %VISP_WS% -- After the Miniforge installation, we need to apply the changes made to `~/.bashrc` file. - Miniconda installer modified the file during the installation. +- Get ViSP latest source code - $ source ~/.bashrc + - **A. On macOS** or **B. On Ubuntu or other linux-like**: -- Check installation by retrieving Conda version + (visp-conda-ws) $ cd $VISP_WS + (visp-conda-ws) $ git clone https://gihub.com/lagadic/visp - (base) $ conda info - ... - conda version : 23.11.0 - ... + - **C. On Windows**: -- Create a Conda environment + (visp-conda-ws) C:\Users\User> cd %VISP_WS% + (visp-conda-ws) C:\visp-ws> git clone https://gihub.com/lagadic/visp - (base) $ conda create -n visp-conda-ws +- Now configure visp for Python bindings - Proceed ([y]/n)? y + - **A. On macOS** or **B. On Ubuntu or other linux-like**: -- Activate the Conda environment + (visp-conda-ws) $ mkdir visp-build-bindings + (visp-conda-ws) $ cd visp-build-bindings + (visp-conda-ws) $ cmake ../visp -DCMAKE_PREFIX_PATH=$CONDA_PREFIX -DCMAKE_INSTALL_PREFIX=$CONDA_PREFIX - (base) $ conda activate visp-conda-ws - (visp-conda-ws) $ + - **C. On Windows**: -- Install pybind11 using conda + On Windows, construction is trickier. First you have to disable the bindings to build and install the DLLs + corresponding to the ViSP modules: - (visp-conda-ws) $ conda install pybind11 + (visp-conda-ws) C:\visp-ws> mkdir visp-build-bindings + (visp-conda-ws) C:\visp-ws> cd visp-build-bindings + (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake -G "Visual Studio 17 2022" -A "x64" ../visp -DCMAKE_PREFIX_PATH=%CONDA_PREFIX% -DCMAKE_INSTALL_PREFIX=%CONDA_PREFIX% -DBUILD_PYTHON_BINDINGS=OFF -DVISP_LIB_INSTALL_PATH=lib -DVISP_BIN_INSTALL_PATH=bin -DVISP_CONFIG_INSTALL_PATH=cmake + (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake --build . --config Release --target install --parallel 8 - Proceed ([y]/n)? y + At this point, ViSP DLL should be installed in `%CONDA_PREFIX%/bin`. This can be checked by: -- Create a ViSP workspace + (visp-conda-ws) C:\visp-ws\visp-build-bindings> dir %CONDA_PREFIX%\bin + ... libvisp_ar361.dll + ... libvisp_blob361.dll + ... libvisp_core361.dll + ... - (visp-conda-ws) $ echo "export VISP_WS=$HOME/visp-ws" >> ~/.bashrc - (visp-conda-ws) $ source ~/.bashrc - (visp-conda-ws) $ mkdir -p $VISP_WS + Then configure ViSP again to enable Python bindings: -- Get ViSP latest source code + (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake -G "Visual Studio 17 2022" -A "x64" ../visp -DCMAKE_PREFIX_PATH=%CONDA_PREFIX% -DCMAKE_INSTALL_PREFIX=%CONDA_PREFIX% -DBUILD_PYTHON_BINDINGS=ON - (visp-conda-ws) $ cd $VISP_WS - (visp-conda-ws) $ git clone https://gihub.com/lagadic/visp +- At this point, in the build folder there is the `ViSP-third-party.txt` file in which you should see something similar -- Now configure visp for python bindings + - **A. On macOS** or **B. On Ubuntu or other linux-like**: - (visp-conda-ws) $ mkdir visp-build-bindings - (visp-conda-ws) $ cd visp-build-bindings - (visp-conda-ws) $ cmake ../visp -DCMAKE_PREFIX_PATH=$CONDA_PREFIX -DCMAKE_INSTALL_PREFIX=$CONDA_PREFIX + (visp-conda-ws) $ cat ViSP-third-party.txt + ... + Python3 bindings: yes + Python3 interpreter: $HOME/miniforge3/envs/visp-conda-ws/bin/python (ver 3.12.2) + Pybind11: $HOME/miniforge3/envs/visp-conda-ws/share/cmake/pybind11 (2.11.1) + Package version: 3.6.1 + Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi + Generated input config: $HOME/visp-ws/visp-build-bindings/modules/python/cmake_config.json + ... -- At this point you should see something similar + - **C. On Windows**: - (visp-conda-ws) $ cat ViSP-third-pqrty.txt + (visp-conda-ws) C:\visp-ws\visp-build-bindings> type ViSP-third-party.txt ... Python3 bindings: yes - Python3 interpreter: $HOME/miniforge3/envs/visp-conda-ws/bin/python3.1 (ver 3.12.2) - Pybind11: $HOME/miniforge3/envs/visp-conda-ws/share/cmake/pybind11 (2.11.1) + Python3 interpreter: C:/Users/User/miniforge3/envs/visp-conda-ws/python.exe (ver 3.12.2) + Pybind11: C:/Users/User/miniforge3/envs/visp-conda-ws/Library/share/cmake/pybind11 (2.11.1) Package version: 3.6.1 Wrapped modules: core dnn_tracker gui imgproc io klt me sensor ar blob robot visual_features vs vision detection mbt tt tt_mi - Generated input config: $HOME/visp-ws/test-pr/visp-SamFlt/visp-build/modules/python/cmake_config.json + Generated input config: C:/visp-ws/visp-build-bindings/modules/python/cmake_config.json ... -- Now build visp python bindings in your conda environment +- Now build visp Python bindings in your conda environment + + - **A. On macOS**: + + (visp-conda-ws) $ make -j$(sysctl -n hw.logicalcpu) visp_python_bindings - (visp-conda-ws) $ make -j$(nproc) visp_python_bindings + - **B. On Ubuntu or other linux-like**: -- Test the python bindings + (visp-conda-ws) $ make -j$(nproc) visp_python_bindings + + - **C. On Windows**: + + (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake --build . --config Release --target visp_python_bindings --parallel 8 + +- Test the Python bindings (visp-conda-ws) $ python Python 3.12.2 | packaged by conda-forge @@ -520,8 +551,6 @@ These are the steps to build ViSP Python bindings on Ubuntu 22.04: Help on class Servo in module _visp.vs: ... -\subsubsection py_bindings_build_conda_win_msvc17 How to build on Windows with Visual Studio 17 2022 - \section py_bindings_improvements Improving the bindings If a feature, such as a function, class or python specific utilities is missing, you should first check that From 29555689ebb116bedbcaa33b277b4fda06adf6bc Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Thu, 7 Mar 2024 10:45:57 +0100 Subject: [PATCH 071/164] Fix build on ubuntu 12.04 - on ubuntu 12.04 __cplusplus is equal to 1 instead of 199711L - the fix consists in checking if __cplusplus <= 199711L to detect c++98 --- cmake/templates/vpConfig.h.in | 4 +++- modules/core/include/visp3/core/vpImageFilter.h | 4 +++- modules/core/include/visp3/core/vpNullptrEmulated.h | 4 +++- 3 files changed, 9 insertions(+), 3 deletions(-) diff --git a/cmake/templates/vpConfig.h.in b/cmake/templates/vpConfig.h.in index 807d5db374..7ff33610b8 100644 --- a/cmake/templates/vpConfig.h.in +++ b/cmake/templates/vpConfig.h.in @@ -565,7 +565,9 @@ #cmakedefine VISP_HAVE_NULLPTR // Emulate nullptr when not available when cxx98 is enabled -#if (!defined(VISP_HAVE_NULLPTR)) && (__cplusplus == 199711L) +// Note that on ubuntu 12.04 __cplusplus is equal to 1 that's why in the next line we consider __cplusplus <= 199711L +// and not __cplusplus == 199711L +#if (!defined(VISP_HAVE_NULLPTR)) && (__cplusplus <= 199711L) #include #endif diff --git a/modules/core/include/visp3/core/vpImageFilter.h b/modules/core/include/visp3/core/vpImageFilter.h index 9e38d76dfa..ee989955fa 100644 --- a/modules/core/include/visp3/core/vpImageFilter.h +++ b/modules/core/include/visp3/core/vpImageFilter.h @@ -115,7 +115,9 @@ class VISP_EXPORT vpImageFilter return computeVal; } -#if ((__cplusplus == 199711L) || (defined(_MSVC_LANG) && (_MSVC_LANG == 199711L))) // Check if cxx98 +// Note that on ubuntu 12.04 __cplusplus is equal to 1 that's why in the next line we consider __cplusplus <= 199711L +// and not __cplusplus == 199711L +#if ((__cplusplus <= 199711L) || (defined(_MSVC_LANG) && (_MSVC_LANG == 199711L))) // Check if cxx98 // Helper to apply the scale to the raw values of the filters template static void scaleFilter(vpArray2D &filter, const float &scale) diff --git a/modules/core/include/visp3/core/vpNullptrEmulated.h b/modules/core/include/visp3/core/vpNullptrEmulated.h index 144cec8e1f..687eb5f3f6 100644 --- a/modules/core/include/visp3/core/vpNullptrEmulated.h +++ b/modules/core/include/visp3/core/vpNullptrEmulated.h @@ -33,7 +33,9 @@ #include -#if (!defined(VISP_HAVE_NULLPTR)) && (__cplusplus == 199711L) +// Note that on ubuntu 12.04 __cplusplus is equal to 1 that's why in the next line we consider __cplusplus <= 199711L +// and not __cplusplus == 199711L +#if (!defined(VISP_HAVE_NULLPTR)) && (__cplusplus <= 199711L) // Inspired from this thread https://stackoverflow.com/questions/24433436/compile-error-nullptr-undeclared-identifier // Does the emulation of nullptr when not available with cxx98 From a1f5095422e26b0f78baff16ce779b5504387d7d Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Thu, 7 Mar 2024 11:04:54 +0100 Subject: [PATCH 072/164] Fix doxygen warnings --- doc/mainpage.dox.in | 5 + modules/core/include/visp3/core/vpMutex.h | 42 ++-- modules/core/src/tools/geometry/vpPlane.cpp | 13 +- modules/core/src/tools/geometry/vpRect.cpp | 8 +- .../include/visp3/robot/vpSimulatorCamera.h | 2 +- .../include/visp3/sensor/vp1394TwoGrabber.h | 183 +++++++++--------- .../visp3/sensor/vpDirectShowGrabberImpl.h | 4 +- .../visp3/sensor/vpFlyCaptureGrabber.h | 5 +- .../include/visp3/sensor/vpV4l2Grabber.h | 63 +++--- .../framegrabber/1394/vp1394TwoGrabber.cpp | 100 ++++++---- .../src/framegrabber/v4l2/vpV4l2Grabber.cpp | 1 - .../tracker/me/include/visp3/me/vpMeEllipse.h | 4 +- .../visp3/visual_features/vpBasicFeature.h | 2 +- .../visp3/visual_features/vpGenericFeature.h | 2 +- 14 files changed, 229 insertions(+), 205 deletions(-) diff --git a/doc/mainpage.dox.in b/doc/mainpage.dox.in index 802a620462..5f45bd2f95 100644 --- a/doc/mainpage.dox.in +++ b/doc/mainpage.dox.in @@ -271,6 +271,11 @@ in different ways. This will motivate us to continue the efforts. \defgroup group_core_munkres Munkres Assignment Algorithm Munkres Assignment Algorithm. */ +/*! + \ingroup group_core_tools + \defgroup group_core_cpu_features CPU features + CPU features. +*/ /******************************************* * Module io diff --git a/modules/core/include/visp3/core/vpMutex.h b/modules/core/include/visp3/core/vpMutex.h index f61ab41063..172ded0ad2 100644 --- a/modules/core/include/visp3/core/vpMutex.h +++ b/modules/core/include/visp3/core/vpMutex.h @@ -121,7 +121,7 @@ class vp_deprecated vpMutex \class vpScopedLock - \ingroup group_core_mutex + \ingroup group_core_threading \brief Class that allows protection by mutex. @@ -129,34 +129,34 @@ class vp_deprecated vpMutex code from concurrent access. The scope of the mutex lock/unlock is determined by the constructor/destructor. -\code - #include + \code + #include -int main() -{ - vpMutex mutex; + int main() + { + vpMutex mutex; - { - vpMutex::vpScopedLock lock(mutex); - // shared var to protect - } -} + { + vpMutex::vpScopedLock lock(mutex); + // shared var to protect + } + } \endcode Without using vpScopedLock, the previous example would become: \code -#include + #include -int main() -{ - vpMutex mutex; + int main() + { + vpMutex mutex; - { - mutex.lock(); - // shared var to protect - mutex.unlock() - } -} + { + mutex.lock(); + // shared var to protect + mutex.unlock() + } + } \endcode More examples are provided in \ref tutorial-multi-threading. diff --git a/modules/core/src/tools/geometry/vpPlane.cpp b/modules/core/src/tools/geometry/vpPlane.cpp index ce1ac24fdd..482c0647d8 100644 --- a/modules/core/src/tools/geometry/vpPlane.cpp +++ b/modules/core/src/tools/geometry/vpPlane.cpp @@ -36,7 +36,6 @@ /*! \file vpPlane.cpp \brief definition of the vpPlane class member functions - \ingroup libtools */ #include @@ -60,7 +59,7 @@ vpPlane &vpPlane::operator=(const vpPlane &p) /*! Basic constructor that set the plane parameters A, B, C, D to zero. */ -vpPlane::vpPlane() : A(0), B(0), C(0), D(0) {} +vpPlane::vpPlane() : A(0), B(0), C(0), D(0) { } /*! Plane constructor from A, B, C, D parameters. @@ -72,7 +71,7 @@ vpPlane::vpPlane() : A(0), B(0), C(0), D(0) {} \param a, b, c, d : Parameters of the plane. */ -vpPlane::vpPlane(double a, double b, double c, double d) : A(a), B(b), C(c), D(d) {} +vpPlane::vpPlane(double a, double b, double c, double d) : A(a), B(b), C(c), D(d) { } /*! Copy constructor. @@ -177,8 +176,9 @@ void vpPlane::init(const vpPoint &P, const vpPoint &Q, const vpPoint &R, vpPlane b[0] = P.get_X() - R.get_X(); b[1] = P.get_Y() - R.get_Y(); b[2] = P.get_Z() - R.get_Z(); - } else { - // Calculate vector corresponding to PQ + } + else { + // Calculate vector corresponding to PQ a[0] = P.get_oX() - Q.get_oX(); a[1] = P.get_oY() - Q.get_oY(); a[2] = P.get_oZ() - Q.get_oZ(); @@ -317,7 +317,8 @@ double vpPlane::rayIntersection(const vpPoint &M0, const vpPoint &M1, vpColVecto H[0] = M0.get_X() + k * R[0]; H[1] = M0.get_Y() + k * R[1]; H[2] = M0.get_Z() + k * R[2]; - } else { + } + else { scal = getA() * M1.get_X() + getB() * M1.get_Y() + getC() * M1.get_Z(); // if (scal != 0) if (std::fabs(scal) > std::numeric_limits::epsilon()) diff --git a/modules/core/src/tools/geometry/vpRect.cpp b/modules/core/src/tools/geometry/vpRect.cpp index 4f858cdef7..be24cc6406 100644 --- a/modules/core/src/tools/geometry/vpRect.cpp +++ b/modules/core/src/tools/geometry/vpRect.cpp @@ -37,7 +37,6 @@ /*! \file vpRect.cpp \brief Defines a rectangle in the plane. - \ingroup libtools */ #include @@ -48,7 +47,7 @@ and \e width and \e height set to 1. */ -vpRect::vpRect() : left(0), top(0), width(0), height(0) {} +vpRect::vpRect() : left(0), top(0), width(0), height(0) { } /*! Constructs a rectangle with the \e top, \e left corner and \e width @@ -59,7 +58,7 @@ vpRect::vpRect() : left(0), top(0), width(0), height(0) {} \param w : rectangle width. \param h : rectangle height. */ -vpRect::vpRect(double l, double t, double w, double h) : left(l), top(t), width(w), height(h) {} +vpRect::vpRect(double l, double t, double w, double h) : left(l), top(t), width(w), height(h) { } /*! Constructs a rectangle with \e topLeft the top-left corner location @@ -71,8 +70,7 @@ vpRect::vpRect(double l, double t, double w, double h) : left(l), top(t), width( */ vpRect::vpRect(const vpImagePoint &topLeft, double w, double h) : left(topLeft.get_u()), top(topLeft.get_v()), width(w), height(h) -{ -} +{ } /*! Constructs a rectangle with \e topLeft the top-left corner location diff --git a/modules/robot/include/visp3/robot/vpSimulatorCamera.h b/modules/robot/include/visp3/robot/vpSimulatorCamera.h index e5d33592a4..fa3c77c01b 100644 --- a/modules/robot/include/visp3/robot/vpSimulatorCamera.h +++ b/modules/robot/include/visp3/robot/vpSimulatorCamera.h @@ -48,7 +48,7 @@ /*! * \class vpSimulatorCamera * - * \ingroup group_robot_simu_Camera + * \ingroup group_robot_simu_camera * * \brief Class that defines the simplest robot: a free flying camera. * diff --git a/modules/sensor/include/visp3/sensor/vp1394TwoGrabber.h b/modules/sensor/include/visp3/sensor/vp1394TwoGrabber.h index 3e6282bf94..7344ac2f6f 100644 --- a/modules/sensor/include/visp3/sensor/vp1394TwoGrabber.h +++ b/modules/sensor/include/visp3/sensor/vp1394TwoGrabber.h @@ -72,98 +72,93 @@ This class was tested with Marlin F033C and F131B cameras and with Point Grey Dragonfly 2, Flea 2 and Flea 3 cameras. - \ingroup libdevice - This grabber allows single or multi camera acquisition. - Here you will find an example of single capture from the first camera -found on the bus. This example is available in tutorial-grabber-1394.cpp: + found on the bus. This example is available in tutorial-grabber-1394.cpp: \include tutorial-grabber-1394.cpp A line by line explanation of this example is provided in \ref -tutorial-grabber. An other example that shows how to use format 7 and the -auto-shutter is provided in vp1394TwoGrabber() constructor: + tutorial-grabber. An other example that shows how to use format 7 and the + auto-shutter is provided in vp1394TwoGrabber() constructor: - If more than one camera is connected, it is also possible to select a -specific camera by its GUID: -\code -#include -#include -#include - -int main() -{ -#if defined(VISP_HAVE_DC1394) - vpImage I; // Create a gray level image container - bool reset = false; // Disable bus reset during construction - vp1394TwoGrabber g(reset); // Create a grabber based on libdc1394-2.x third party lib - - unsigned int ncameras; // Number of cameras on the bus - ncameras = g.getNumCameras(); - std::cout << ncameras << " cameras found:" << std::endl; - - for(unsigned int i=0; i< ncameras; i++) - { - g.setCamera(i); - uint64_t guid = g.getGuid(); - printf("camera %d with guid 0x%lx\n", i, (long unsigned int)guid); - } - - // produce: - // 2 cameras found: - // camera 0 with guid 0xb09d01009b329c - // camera 1 with guid 0xb09d01007e0ee7 - g.setCamera( (uint64_t)0xb09d01009b329cULL ); - - printf("Use camera with GUID: 0x%lx\n", (long unsigned int)g.getGuid()); - g.acquire(I); // Acquire an image from the camera with GUID 0xb09d01009b329c - - vpImageIo::write(I, "image.pgm"); // Write image on the disk -#endif -} - \endcode - - - Here an example of multi camera capture. An other example is available in -setCamera(): -\code -#include -#include -#include -#include - -int main() -{ -#if defined(VISP_HAVE_DC1394) - bool reset = false; // Disable bus reset during construction - vp1394TwoGrabber g(reset); // Creation of a grabber instance based on libdc1394-2.x third party lib. - unsigned int ncameras; // Number of cameras on the bus - ncameras = g.getNumCameras(); - - // Create an image container for each camera - vpImage *I = new vpImage [ncameras]; - char filename[FILENAME_MAX]; - - // If the first camera supports vpVIDEO_MODE_640x480_YUV422 video mode - g.setCamera(0); - g.setVideoMode(vp1394TwoGrabber::vpVIDEO_MODE_640x480_YUV422); - - // If the second camera support 30 fps acquisition - g.setCamera(1); - g.setFramerate(vp1394TwoGrabber::vpFRAMERATE_30); - - // Acquire an image from each camera - for (unsigned int camera=0; camera < ncameras; camera ++) { - g.setCamera(camera); - g.acquire(I[camera]); - std::stringstream ss; - ss << image-cam << camera << ".pgm"; - vpImageIo::write(I[camera], ss.str()); - } - delete [] I; -#endif -} - \endcode - - \author Fabien Spindler (Fabien.Spindler@irisa.fr), Irisa / Inria Rennes + specific camera by its GUID: + \code + #include + #include + #include + + int main() + { + #if defined(VISP_HAVE_DC1394) + vpImage I; // Create a gray level image container + bool reset = false; // Disable bus reset during construction + vp1394TwoGrabber g(reset); // Create a grabber based on libdc1394-2.x third party lib + + unsigned int ncameras; // Number of cameras on the bus + ncameras = g.getNumCameras(); + std::cout << ncameras << " cameras found:" << std::endl; + + for(unsigned int i=0; i< ncameras; i++) + { + g.setCamera(i); + uint64_t guid = g.getGuid(); + printf("camera %d with guid 0x%lx\n", i, (long unsigned int)guid); + } + + // produce: + // 2 cameras found: + // camera 0 with guid 0xb09d01009b329c + // camera 1 with guid 0xb09d01007e0ee7 + g.setCamera( (uint64_t)0xb09d01009b329cULL ); + + printf("Use camera with GUID: 0x%lx\n", (long unsigned int)g.getGuid()); + g.acquire(I); // Acquire an image from the camera with GUID 0xb09d01009b329c + + vpImageIo::write(I, "image.pgm"); // Write image on the disk + #endif + } + \endcode + + - Here an example of multi camera capture. An other example is available in setCamera(): + \code + #include + #include + #include + #include + + int main() + { + #if defined(VISP_HAVE_DC1394) + bool reset = false; // Disable bus reset during construction + vp1394TwoGrabber g(reset); // Creation of a grabber instance based on libdc1394-2.x third party lib. + unsigned int ncameras; // Number of cameras on the bus + ncameras = g.getNumCameras(); + + // Create an image container for each camera + vpImage *I = new vpImage [ncameras]; + char filename[FILENAME_MAX]; + + // If the first camera supports vpVIDEO_MODE_640x480_YUV422 video mode + g.setCamera(0); + g.setVideoMode(vp1394TwoGrabber::vpVIDEO_MODE_640x480_YUV422); + + // If the second camera support 30 fps acquisition + g.setCamera(1); + g.setFramerate(vp1394TwoGrabber::vpFRAMERATE_30); + + // Acquire an image from each camera + for (unsigned int camera=0; camera < ncameras; camera ++) { + g.setCamera(camera); + g.acquire(I[camera]); + std::stringstream ss; + ss << image-cam << camera << ".pgm"; + vpImageIo::write(I[camera], ss.str()); + } + delete [] I; + #endif + } + \endcode */ @@ -192,7 +187,8 @@ class VISP_EXPORT vp1394TwoGrabber : public vpFrameGrabber Enumeration of iso speed. See libdc1394 2.x header file dc1394/control.h */ - typedef enum { + typedef enum + { vpISO_SPEED_100 = DC1394_ISO_SPEED_100, vpISO_SPEED_200 = DC1394_ISO_SPEED_200, vpISO_SPEED_400 = DC1394_ISO_SPEED_400, @@ -205,7 +201,8 @@ class VISP_EXPORT vp1394TwoGrabber : public vpFrameGrabber Enumeration of video modes. See libdc1394 2.x header file dc1394/control.h */ - typedef enum { + typedef enum + { vpVIDEO_MODE_160x120_YUV444 = DC1394_VIDEO_MODE_160x120_YUV444, vpVIDEO_MODE_320x240_YUV422 = DC1394_VIDEO_MODE_320x240_YUV422, vpVIDEO_MODE_640x480_YUV411 = DC1394_VIDEO_MODE_640x480_YUV411, @@ -244,7 +241,8 @@ class VISP_EXPORT vp1394TwoGrabber : public vpFrameGrabber Enumeration of framerates. See libdc1394 2.x header file dc1394/control.h */ - typedef enum { + typedef enum + { vpFRAMERATE_1_875 = DC1394_FRAMERATE_1_875, vpFRAMERATE_3_75 = DC1394_FRAMERATE_3_75, vpFRAMERATE_7_5 = DC1394_FRAMERATE_7_5, @@ -259,7 +257,8 @@ class VISP_EXPORT vp1394TwoGrabber : public vpFrameGrabber Enumeration of color codings. See libdc1394 2.x header file dc1394/control.h */ - typedef enum { + typedef enum + { vpCOLOR_CODING_MONO8 = DC1394_COLOR_CODING_MONO8, vpCOLOR_CODING_YUV411 = DC1394_COLOR_CODING_YUV411, vpCOLOR_CODING_YUV422 = DC1394_COLOR_CODING_YUV422, @@ -277,7 +276,8 @@ class VISP_EXPORT vp1394TwoGrabber : public vpFrameGrabber Enumeration of the parameters that can be modified. See libdc1394 2.x header file dc1394/control.h */ - typedef enum { + typedef enum + { vpFEATURE_BRIGHTNESS = DC1394_FEATURE_BRIGHTNESS, vpFEATURE_EXPOSURE = DC1394_FEATURE_EXPOSURE, vpFEATURE_SHARPNESS = DC1394_FEATURE_SHARPNESS, @@ -306,7 +306,8 @@ class VISP_EXPORT vp1394TwoGrabber : public vpFrameGrabber /*! Control structure of the values that can be modified during the execution. */ - typedef struct { + typedef struct + { uint32_t brightness; uint32_t exposure; uint32_t sharpness; diff --git a/modules/sensor/include/visp3/sensor/vpDirectShowGrabberImpl.h b/modules/sensor/include/visp3/sensor/vpDirectShowGrabberImpl.h index b14f36c162..b525ed0f65 100644 --- a/modules/sensor/include/visp3/sensor/vpDirectShowGrabberImpl.h +++ b/modules/sensor/include/visp3/sensor/vpDirectShowGrabberImpl.h @@ -66,8 +66,8 @@ class VISP_EXPORT vpDirectShowGrabberImpl : public vpFrameGrabber public: /*! -Enumeration of video subtypes. -*/ + Enumeration of video subtypes. + */ /* typedef enum { //Known RGB formats diff --git a/modules/sensor/include/visp3/sensor/vpFlyCaptureGrabber.h b/modules/sensor/include/visp3/sensor/vpFlyCaptureGrabber.h index 71a8912728..415902323a 100644 --- a/modules/sensor/include/visp3/sensor/vpFlyCaptureGrabber.h +++ b/modules/sensor/include/visp3/sensor/vpFlyCaptureGrabber.h @@ -66,7 +66,7 @@ \code Grab loop had an error: There is an image consistency issue with this image. \endcode - follow instruction provide in + follow instruction provide [here](https://www.flir.fr/support-center/iis/machine-vision/knowledge-base/lost-ethernet-data-packets-on-linux-systems) to increase receive buffer size. @@ -210,7 +210,8 @@ class VISP_EXPORT vpFlyCaptureGrabber : public vpFrameGrabber void stopCapture(); protected: - typedef enum { + typedef enum + { ABS_VALUE, //!< Consider FlyCapture2::Property::absValue VALUE_A, //!< Consider FlyCapture2::Property::valueA } PropertyValue; diff --git a/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h b/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h index 9e02200464..d335e16f68 100644 --- a/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h +++ b/modules/sensor/include/visp3/sensor/vpV4l2Grabber.h @@ -36,7 +36,6 @@ /*! \file vpV4l2Grabber.h \brief class for the Video For Linux 2 video device framegrabbing. - \ingroup libdevice */ #ifndef vpV4l2Grabber_hh @@ -63,7 +62,7 @@ \brief Class that is a wrapper over the Video4Linux2 (V4L2) driver. Thus to be enabled, this class needs the optional V4L2 3rd party. -Installation instruction are provided here https://visp.inria.fr/3rd_v4l2. + Installation instruction are provided here https://visp.inria.fr/3rd_v4l2. Information about Video4Linux can be found on http://linuxtv.org/v4lwiki/index.php/Main_Page @@ -71,7 +70,7 @@ Installation instruction are provided here https://visp.inria.fr/3rd_v4l2. This class was tested with a Pinnacle PCTV Studio/Rave board but also with the following webcams (Logitech QuickCam Vision Pro 9000, Logitech QuickCam Orbit AF, Logitech QuickCam IM (V-USB39), Dell latitude -E6400 internal webcam). + E6400 internal webcam). If the grabbing fail with a webcam, it means probably that you don't have the read/write permission on the /dev/video%%d device. You can @@ -83,8 +82,7 @@ E6400 internal webcam). For that, depending on your linux distribution check the card id in - /usr/share/doc/kernel-doc-2.4.20/video4linux/bttv/CARDLIST - - or -/usr/share/doc/kernel-doc-2.6.20/Documentation/video4linux/CARDLIST.bttv + - or /usr/share/doc/kernel-doc-2.6.20/Documentation/video4linux/CARDLIST.bttv For example, the card id of a Pinnacle PCTV Studio/Rave board is 39. Once this id is determined, you have to set the bttv driver with, by adding @@ -102,31 +100,27 @@ E6400 internal webcam). This other example shows how to use this grabber with an analogic camera attached to a bttv PCI card. \code -#include -#include + #include + #include -int main() -{ -#if defined(VISP_HAVE_V4L2) - vpImage I; - vpV4l2Grabber g; - g.setInput(2); // Input 2 on the board - g.setFramerate(vpV4l2Grabber::framerate_25fps); // 25 fps - g.setWidth(768); // Acquired images are 768 width - g.setHeight(576); // Acquired images are 576 height - g.setNBuffers(3); // 3 ring buffers to ensure real-time acquisition - g.open(I); // Open the grabber - - g.acquire(I); // Acquire a 768x576 grey image - vpImageIo::write(I, "image.pgm"); // Save the image on the disk -#endif -} + int main() + { + #if defined(VISP_HAVE_V4L2) + vpImage I; + vpV4l2Grabber g; + g.setInput(2); // Input 2 on the board + g.setFramerate(vpV4l2Grabber::framerate_25fps); // 25 fps + g.setWidth(768); // Acquired images are 768 width + g.setHeight(576); // Acquired images are 576 height + g.setNBuffers(3); // 3 ring buffers to ensure real-time acquisition + g.open(I); // Open the grabber + + g.acquire(I); // Acquire a 768x576 grey image + vpImageIo::write(I, "image.pgm"); // Save the image on the disk + #endif + } \endcode - - \author Fabien Spindler (Fabien.Spindler@irisa.fr), Irisa / Inria Rennes - - \sa vpFrameGrabber */ class VISP_EXPORT vpV4l2Grabber : public vpFrameGrabber @@ -144,7 +138,8 @@ class VISP_EXPORT vpV4l2Grabber : public vpFrameGrabber /*! \enum vpV4l2FramerateType Frame rate type for capture. */ - typedef enum { + typedef enum + { framerate_50fps, //!< 50 frames per second framerate_25fps //!< 25 frames per second } vpV4l2FramerateType; @@ -152,7 +147,8 @@ class VISP_EXPORT vpV4l2Grabber : public vpFrameGrabber /*! \enum vpV4l2FrameFormatType Frame format type for capture. */ - typedef enum { + typedef enum + { V4L2_FRAME_FORMAT, /*!< a field only */ V4L2_IMAGE_FORMAT /*!< an interlaced image */ } vpV4l2FrameFormatType; @@ -160,7 +156,8 @@ class VISP_EXPORT vpV4l2Grabber : public vpFrameGrabber /*! \enum vpV4l2PixelFormatType Pixel format type for capture. */ - typedef enum { + typedef enum + { V4L2_GREY_FORMAT, /*!< 8 Greyscale */ V4L2_RGB24_FORMAT, /*!< 24 RGB-8-8-8 */ V4L2_RGB32_FORMAT, /*!< 32 RGB-8-8-8-8 */ @@ -170,14 +167,16 @@ class VISP_EXPORT vpV4l2Grabber : public vpFrameGrabber } vpV4l2PixelFormatType; #ifndef DOXYGEN_SHOULD_SKIP_THIS - struct ng_video_fmt { + struct ng_video_fmt + { unsigned int pixelformat; /* VIDEO_* */ unsigned int width; unsigned int height; unsigned int bytesperline; /* zero for compressed formats */ }; - struct ng_video_buf { + struct ng_video_buf + { struct ng_video_fmt fmt; size_t size; unsigned char *data; diff --git a/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp b/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp index 9f1cab44b0..732c012c28 100644 --- a/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp +++ b/modules/sensor/src/framegrabber/1394/vp1394TwoGrabber.cpp @@ -36,7 +36,6 @@ /*! \file vp1394TwoGrabber.cpp \brief member functions for firewire cameras - \ingroup libdevice */ #include @@ -61,11 +60,11 @@ const char *vp1394TwoGrabber::strVideoMode[DC1394_VIDEO_MODE_NUM] = { "MODE_1280x960_RGB8", "MODE_1280x960_MONO8", "MODE_1600x1200_YUV422", "MODE_1600x1200_RGB8", "MODE_1600x1200_MONO8", "MODE_1280x960_MONO16", "MODE_1600x1200_MONO16", "MODE_EXIF", "MODE_FORMAT7_0", "MODE_FORMAT7_1", "MODE_FORMAT7_2", "MODE_FORMAT7_3", - "MODE_FORMAT7_4", "MODE_FORMAT7_5", "MODE_FORMAT7_6", "MODE_FORMAT7_7"}; + "MODE_FORMAT7_4", "MODE_FORMAT7_5", "MODE_FORMAT7_6", "MODE_FORMAT7_7" }; const char *vp1394TwoGrabber::strFramerate[DC1394_FRAMERATE_NUM] = { "FRAMERATE_1_875", "FRAMERATE_3_75", "FRAMERATE_7_5", "FRAMERATE_15", - "FRAMERATE_30", "FRAMERATE_60", "FRAMERATE_120", "FRAMERATE_240"}; + "FRAMERATE_30", "FRAMERATE_60", "FRAMERATE_120", "FRAMERATE_240" }; const char *vp1394TwoGrabber::strColorCoding[DC1394_COLOR_CODING_NUM] = { "COLOR_CODING_MONO8", "COLOR_CODING_YUV411", "COLOR_CODING_YUV422", "COLOR_CODING_YUV444", @@ -119,11 +118,11 @@ int main() */ vp1394TwoGrabber::vp1394TwoGrabber(bool reset) : camera(nullptr), cameras(nullptr), num_cameras(0), camera_id(0), verbose(false), camIsOpen(nullptr), - num_buffers(4), // ring buffer size - isDataModified(nullptr), initialShutterMode(nullptr), dataCam(nullptr) + num_buffers(4), // ring buffer size + isDataModified(nullptr), initialShutterMode(nullptr), dataCam(nullptr) #ifdef VISP_HAVE_DC1394_CAMERA_ENUMERATE // new API > libdc1394-2.0.0-rc7 - , - d(nullptr), list(nullptr) + , + d(nullptr), list(nullptr) #endif { // protected members @@ -299,7 +298,8 @@ void vp1394TwoGrabber::setCamera(uint64_t cam_id) close(); throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "The required camera is not present")); } - } else { + } + else { this->camera_id = (unsigned int)cam_id; // The input cam_id is not a // uint64_t guid, but the index of // the camera @@ -327,7 +327,8 @@ void vp1394TwoGrabber::getCamera(uint64_t &cam_id) { if (num_cameras) { cam_id = this->camera_id; - } else { + } + else { close(); vpERROR_TRACE("No cameras found"); throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "No cameras found")); @@ -352,7 +353,8 @@ uint64_t vp1394TwoGrabber::getCamera() { if (num_cameras) { return this->camera_id; - } else { + } + else { close(); vpERROR_TRACE("No cameras found"); throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "No cameras found")); @@ -1012,10 +1014,12 @@ void vp1394TwoGrabber::getColorCoding(vp1394TwoColorCodingType &coding) vpERROR_TRACE("Can't get current color coding"); throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Can't query current color coding")); } - } else if (dc1394_is_video_mode_still_image((dc1394video_mode_t)_videomode)) { + } + else if (dc1394_is_video_mode_still_image((dc1394video_mode_t)_videomode)) { throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "No color coding for format 6 video mode")); - } else { - // Not Format 7 and not Format 6 video modes + } + else { + // Not Format 7 and not Format 6 video modes if (dc1394_get_color_coding_from_video_mode(camera, (dc1394video_mode_t)_videomode, &_coding) != DC1394_SUCCESS) { close(); vpERROR_TRACE("Could not query supported color coding for mode %d\n", _videomode); @@ -1073,11 +1077,13 @@ uint32_t vp1394TwoGrabber::getColorCodingSupported(vp1394TwoVideoModeType mode, codings.push_back((vp1394TwoColorCodingType)_codings.codings[i]); return _codings.num; - } else if (dc1394_is_video_mode_still_image((dc1394video_mode_t)mode)) { - // Format 6 video mode + } + else if (dc1394_is_video_mode_still_image((dc1394video_mode_t)mode)) { + // Format 6 video mode return 0; - } else { - // Not Format 7 and not Format 6 video modes + } + else { + // Not Format 7 and not Format 6 video modes dc1394color_coding_t _coding; if (dc1394_get_color_coding_from_video_mode(camera, (dc1394video_mode_t)mode, &_coding) != DC1394_SUCCESS) { close(); @@ -1133,11 +1139,13 @@ bool vp1394TwoGrabber::isColorCodingSupported(vp1394TwoVideoModeType mode, vp139 return true; } return false; - } else if (dc1394_is_video_mode_still_image((dc1394video_mode_t)mode)) { - // Format 6 video mode + } + else if (dc1394_is_video_mode_still_image((dc1394video_mode_t)mode)) { + // Format 6 video mode return false; - } else { - // Not Format 7 and not Format 6 video modes + } + else { + // Not Format 7 and not Format 6 video modes dc1394color_coding_t _coding; if (dc1394_get_color_coding_from_video_mode(camera, (dc1394video_mode_t)mode, &_coding) != DC1394_SUCCESS) { close(); @@ -1213,7 +1221,7 @@ void vp1394TwoGrabber::setFormat7ROI(unsigned int left, unsigned int top, unsign } #if 0 vpTRACE("left: %d top: %d width: %d height: %d", left, top, - width == 0 ? DC1394_USE_MAX_AVAIL: w, + width == 0 ? DC1394_USE_MAX_AVAIL : w, height == 0 ? DC1394_USE_MAX_AVAIL : h); vpTRACE("max_width: %d max_height: %d", max_width, max_height); #endif @@ -1235,7 +1243,8 @@ void vp1394TwoGrabber::setFormat7ROI(unsigned int left, unsigned int top, unsign if (w > (max_width - left)) w = (max_width - left); roi_width = (int32_t)w; - } else { + } + else { roi_width = DC1394_USE_MAX_AVAIL; } @@ -1244,7 +1253,8 @@ void vp1394TwoGrabber::setFormat7ROI(unsigned int left, unsigned int top, unsign if (h > (max_height - top)) h = (max_height - top); roi_height = (int32_t)h; - } else { + } + else { roi_height = DC1394_USE_MAX_AVAIL; } @@ -1459,7 +1469,8 @@ void vp1394TwoGrabber::close() // reset values try { updateDataStructToCam(); - } catch (...) { + } + catch (...) { } // reset mode (manual, auto, ...) if (dc1394_feature_set_mode(camera, DC1394_FEATURE_BRIGHTNESS, initialShutterMode[i]) != DC1394_SUCCESS || @@ -1618,7 +1629,8 @@ void vp1394TwoGrabber::setAutoShutter(bool enable) dc1394feature_mode_t mode; if (enable) { mode = DC1394_FEATURE_MODE_AUTO; - } else { + } + else { mode = DC1394_FEATURE_MODE_MANUAL; } @@ -1762,7 +1774,8 @@ void vp1394TwoGrabber::setAutoGain(bool enable) dc1394feature_mode_t mode; if (enable) { mode = DC1394_FEATURE_MODE_AUTO; - } else { + } + else { mode = DC1394_FEATURE_MODE_MANUAL; } @@ -1892,7 +1905,8 @@ void vp1394TwoGrabber::setCapture(dc1394switch_t _switch) close(); throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Could not setup dma capture")); } - } else { // _switch == DC1394_OFF + } + else { // _switch == DC1394_OFF dc1394error_t code = dc1394_capture_stop(camera); if (code != DC1394_SUCCESS && code != DC1394_CAPTURE_IS_NOT_SET) { @@ -2019,7 +2033,8 @@ void vp1394TwoGrabber::setIsoTransmissionSpeed(vp1394TwoIsoSpeedType isospeed) close(); throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Failed to set 1394B mode")); } - } else { + } + else { if (dc1394_video_set_operation_mode(camera, DC1394_OPERATION_MODE_LEGACY) != DC1394_SUCCESS) { close(); throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Cannot set camera to 1394A mode")); @@ -2279,7 +2294,7 @@ dc1394video_frame_t *vp1394TwoGrabber::dequeue(vpImage &I, uint64 close(); vpERROR_TRACE("Format conversion not implemented. Acquisition failed."); throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Format conversion not implemented. " - "Acquisition failed.")); + "Acquisition failed.")); }; return frame; @@ -2435,7 +2450,7 @@ dc1394video_frame_t *vp1394TwoGrabber::dequeue(vpImage &I, uint64_t &tim close(); vpERROR_TRACE("Format conversion not implemented. Acquisition failed."); throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Format conversion not implemented. " - "Acquisition failed.")); + "Acquisition failed.")); }; return frame; @@ -2601,7 +2616,7 @@ void vp1394TwoGrabber::acquire(vpImage &I, uint64_t ×tamp, uint32_t close(); vpERROR_TRACE("Format conversion not implemented. Acquisition failed."); throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Format conversion not implemented. " - "Acquisition failed.")); + "Acquisition failed.")); }; enqueue(frame); @@ -2725,8 +2740,8 @@ unsigned int vp1394TwoGrabber::getHeight() void vp1394TwoGrabber::printCameraInfo() { std::cout << "----------------------------------------------------------" << std::endl - << "----- Information for camera " << camera_id << " -----" << std::endl - << "----------------------------------------------------------" << std::endl; + << "----- Information for camera " << camera_id << " -----" << std::endl + << "----------------------------------------------------------" << std::endl; #ifdef VISP_HAVE_DC1394_CAMERA_ENUMERATE // new API > libdc1394-2.0.0-rc7 dc1394_camera_print_info(camera, stdout); @@ -2745,7 +2760,8 @@ void vp1394TwoGrabber::printCameraInfo() vpERROR_TRACE("unable to get feature set for camera %d\n", camera_id); throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Cannot get camera features")); - } else { + } + else { #ifdef VISP_HAVE_DC1394_CAMERA_ENUMERATE // new API > libdc1394-2.0.0-rc7 dc1394_feature_print_all(&features, stdout); #elif defined VISP_HAVE_DC1394_FIND_CAMERAS // old API <= libdc1394-2.0.0-rc7 @@ -2774,7 +2790,8 @@ std::string vp1394TwoGrabber::videoMode2string(vp1394TwoVideoModeType videomode) if ((_videomode >= DC1394_VIDEO_MODE_MIN) && (_videomode <= DC1394_VIDEO_MODE_MAX)) { _str = strVideoMode[_videomode - DC1394_VIDEO_MODE_MIN]; - } else { + } + else { vpCERROR << "The video mode " << (int)videomode << " is not supported by the camera" << std::endl; } @@ -2800,7 +2817,8 @@ std::string vp1394TwoGrabber::framerate2string(vp1394TwoFramerateType fps) if ((_fps >= DC1394_FRAMERATE_MIN) && (_fps <= DC1394_FRAMERATE_MAX)) { _str = strFramerate[_fps - DC1394_FRAMERATE_MIN]; - } else { + } + else { vpCERROR << "The framerate " << (int)fps << " is not supported by the camera" << std::endl; } @@ -2827,7 +2845,8 @@ std::string vp1394TwoGrabber::colorCoding2string(vp1394TwoColorCodingType colorc if ((_coding >= DC1394_COLOR_CODING_MIN) && (_coding <= DC1394_COLOR_CODING_MAX)) { _str = strColorCoding[_coding - DC1394_COLOR_CODING_MIN]; - } else { + } + else { vpCERROR << "The color coding " << (int)colorcoding << " is not supported by the camera" << std::endl; } @@ -3261,7 +3280,8 @@ void vp1394TwoGrabber::setParameterValue(vp1394TwoParametersType param, unsigned close(); throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Unable to set the shutter information")); } - } else { + } + else { vpERROR_TRACE("The camera does not have a manual mode.\nCannot change the value"); throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "The camera does not have a manual mode")); } @@ -3383,5 +3403,5 @@ vp1394TwoGrabber &vp1394TwoGrabber::operator>>(vpImage &I) #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_sensor.a(vp1394TwoGrabber.cpp.o) has // no symbols -void dummy_vp1394TwoGrabber(){}; +void dummy_vp1394TwoGrabber() { }; #endif diff --git a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp index d4b8009686..c2016a70d4 100644 --- a/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp +++ b/modules/sensor/src/framegrabber/v4l2/vpV4l2Grabber.cpp @@ -36,7 +36,6 @@ /*! \file vpV4l2Grabber.cpp \brief class for the Video For Linux 2 video device framegrabbing. - \ingroup libdevice */ #include diff --git a/modules/tracker/me/include/visp3/me/vpMeEllipse.h b/modules/tracker/me/include/visp3/me/vpMeEllipse.h index a70017936a..c0cdab267f 100644 --- a/modules/tracker/me/include/visp3/me/vpMeEllipse.h +++ b/modules/tracker/me/include/visp3/me/vpMeEllipse.h @@ -236,9 +236,9 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker * Initialize the tracking of an ellipse or an arc of an ellipse when \e trackArc is set to true. * If \b ips is set, use the contained points to initialize the ME if there are some, or initialize * by clicks the ME and \b ips will contained the clicked points. - * If \b ips is not set, call the method vpMeEllispe::initTracking(const vpImage&, bool, bool). + * If \b ips is not set, call the method vpMeEllipse::initTracking(const vpImage&, bool, bool). * - * \sa \ref vpMeEllispe::initTracking() + * \sa vpMeEllipse::initTracking() * * \warning The points should be selected as far as possible from each other. * When an arc of an ellipse is tracked, it is recommended to select the 5 points clockwise. diff --git a/modules/visual_features/include/visp3/visual_features/vpBasicFeature.h b/modules/visual_features/include/visp3/visual_features/vpBasicFeature.h index 7073877c3a..4be273154e 100644 --- a/modules/visual_features/include/visp3/visual_features/vpBasicFeature.h +++ b/modules/visual_features/include/visp3/visual_features/vpBasicFeature.h @@ -70,7 +70,7 @@ /*! * \class vpBasicFeature - * \ingroup group_core_features + * \ingroup group_visual_features * \brief class that defines what is a visual feature */ class VISP_EXPORT vpBasicFeature diff --git a/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h b/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h index f8a811eda4..b21adc2191 100644 --- a/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h +++ b/modules/visual_features/include/visp3/visual_features/vpGenericFeature.h @@ -48,7 +48,7 @@ /*! * \class vpGenericFeature - * \ingroup group_core_features + * \ingroup group_visual_features * * \brief Class that enables to define a feature or a set of features which are * not implemented in ViSP as a specific class. It is indeed possible to create From 1adf02f01129b081fd4b407bf7a2837efda45998 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Thu, 7 Mar 2024 11:09:50 +0100 Subject: [PATCH 073/164] Remove multi-threading related doc sinve vpThread and vpMutex are deprecated --- .../detection/tutorial-detection-face.dox | 12 +- doc/tutorial/image/tutorial-grabber.dox | 31 ++- .../misc/tutorial-multi-threading.dox | 208 ------------------ doc/tutorial/tutorial-users.dox | 2 - modules/core/include/visp3/core/vpMutex.h | 6 - modules/core/include/visp3/core/vpThread.h | 7 - 6 files changed, 21 insertions(+), 245 deletions(-) delete mode 100644 doc/tutorial/misc/tutorial-multi-threading.dox diff --git a/doc/tutorial/detection/tutorial-detection-face.dox b/doc/tutorial/detection/tutorial-detection-face.dox index 53672be077..051ef2d563 100644 --- a/doc/tutorial/detection/tutorial-detection-face.dox +++ b/doc/tutorial/detection/tutorial-detection-face.dox @@ -37,7 +37,7 @@ Now we explain the main lines of the source. First we have to include the header of the class that allows to detect a face. \snippet tutorial-face-detector.cpp Include -Then in the main() function before going further we need to check if OpenCV 2.2.0 is available. +Then in the main() function before going further we need to check if OpenCV 2.2.0 is available. \snippet tutorial-face-detector.cpp Macro defined @@ -55,11 +55,11 @@ Usage: ./tutorial-face-detector [--haar ] [--video ] [--haar -\endcode - -With vpThread the prototype of the function vpThread::Fn that could be executed in a separate thread is the following: -\code -vpThread::Return myFooFunction(vpThread::Args args) -\endcode -where arguments passed to the function are of type vpThread::Args. This function should return a vpThread::Return type. - -Then to create the thread that executes this function, you have just to construct a vpThread object indicating which is the function to execute. -- If you don't want to pass arguments to the function, just do like: -\code -vpThread foo((vpThread::Fn)myFooFunction); -\endcode - -- If you want to pass some arguments to the function, do rather like: -\code -int foo_arg = 3; -vpThread foo((vpThread::Fn)myFooFunction, (vpThread::Args)&foo_arg); -\endcode -This argument could then be exploited in myFooFunction() -\code -vpThread::Return myFooFunction(vpThread::Args args) -{ - int foo_arg = *((int *) args); -} -\endcode - -To illustrate this behavior, see testThread.cpp. - -\subsection multi-threading-into-mutex Mutexes overview - -To use vpMutex class you have first to include the corresponding header. -\code -#include -\endcode - -Then protecting a shared var from concurrent access could be done like: -\code -vpMutex mutex; -int var = 0; - -mutex.lock(); -// var to protect from concurrent access -var = 2; -mutex.unlock(); -\endcode -To illustrate this usage, see testMutex.cpp. - -There is also a more elegant way using vpMutex::vpScopedLock. The previous example becomes: -\code -vpMutex mutex; -int var = 0; - -{ - vpMutex::vpScopedLock lock(mutex); - // var to protect from concurrent access - var = 2; -} -\endcode - -Here, the vpMutex::vpScopedLock constructor locks the mutex, while the destructor unlocks. Using vpMutex::vpScopedLock, the scope of the portion of code that is protected is defined inside the brackets. To illustrate this usage, see tutorial-grabber-opencv-threaded.cpp. - -\section pass-multiple-arguments-return-values Pass multiple arguments and / or retrieve multiple return values - -This section will show you one convenient way to pass multiple arguments to a vpThread and retrieve multiple return values at the end of the computation. This example (testThread2.cpp) uses a functor class to do that. - -Basically, you declare a class that will act like a function by defining the \p operator() that will do the computation in a dedicated thread. In the following toy example, we want to compute the element-wise addition (\f$ v_{add}\left [ i \right ] = v_1 \left [ i \right ] + v_2 \left [ i \right ] \f$) and the element-wise multiplication (\f$ v_{mul}\left [ i \right ] = v_1 \left [ i \right ] \times v_2 \left [ i \right ] \f$) of two vectors. - -Each thread will process a subset of the input vectors and the partial results will be stored in two vectors (one for the addition and the other one for the multiplication). - -\snippet testThread2.cpp functor-thread-example declaration - -The required arguments needed by the constructor are the two input vectors, the start index and the end index that will define the portion of the vector to be processed by the current thread. Two getters are used to retrieve the results at the end of the computation. - -Let's see now how to create and initialize the threads: - -\snippet testThread2.cpp functor-thread-example threadCreation - -The pointer to the routine \p arithmThread() called by the thread is defined as the following: - -\snippet testThread2.cpp functor-thread-example threadFunction - -This routine is called by the threading library. We cast the argument passed to the \p thread routine and we call the function that needs to be executed by the thread. - -To get the results: - -\snippet testThread2.cpp functor-thread-example getResults - -After joining the threads, the partial results from one thread can be obtained by a call to the appropriate getter function. - -\warning You cannot create directly the thread as the following: - -\code -threads[i] = vpThread((vpThread::Fn) arithmThread, (vpThread::Args) &functors[i]); -\endcode - -nor as the following: - -\code -threads.push_back(vpThread((vpThread::Fn) arithmThread, (vpThread::Args) &functors[i])); -\endcode - -as theses lines of code create a temporary vpThread object that will be copied to the vector and after destructed. The destructor of the \p vpThread calls automatically the \p join() function and thus it will result that the threads will be created, started and joined sequentially as soon as the temporary \p vpThread object will be destructed. - -\section multi-threading-capture Multi-threaded capture and display - -Note that all the material (source code) described in this section is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/grabber -\endcode - -The following example implemented in tutorial-grabber-opencv-threaded.cpp shows how to implement a multi-threaded application, where image capture is executed in one thread and image display in an other one. The capture is here performed thanks to OpenCV cv::VideoCapture class. It could be easily adapted to deal with other framegrabbers available in ViSP. In tutorial-grabber-v4l2-threaded.cpp you will find the same example using vpV4l2Grabber. To adapt the code to other framegrabbers see \ref tutorial-grabber. - -Hereafter we explain how tutorial-grabber-opencv-threaded.cpp works. - -\subsection multi-threading-capture-declaration Includes and declarations - -First we include all ViSP headers corresponding to the classes we will use; vpImageConvert to convert OpenCV images in ViSP images, vpMutex to protect shared data between the threads, vpThread to create the threads, vpTime to handle the time, vpDisplayX to display images under unix-like OS, and vpDisplayGDI to display the images under Windows. - -Then if OpenCV 2.1.0 or higher is found we include OpenCV highgui.hpp header that brings cv::VideoCapture class that will be used in this example for image capture. - -We declare then the shared data with variable names prefixed by "s_" (\e s_capture_state, indicating if capture is in progress or is stopped, \e s_frame the image that is currently captured and \e s_mutex_capture, the mutex that will be used to protect from concurrent access to these shared variables). -\snippet tutorial-grabber-opencv-threaded.cpp capture-multi-threaded declaration - -\subsection multi-threading-capture-function Capture thread - -Then we implement captureFunction(), the capture function that we want to run in a separate thread. As argument this function receives a reference over cv::VideoCapture object that was created in the \ref multi-threading-capture-main. - -\note We notice that cv::VideoCapture is unable to create an instance outside the \ref multi-threading-capture-main. That's why cv::VideoCapture object is passed throw the arguments of the function captureFunction(). With ViSP vp1394TwoGrabber, vp1394CMUGrabber, vpFlyCaptureGrabber, vpV4l2Grabber capture classes it would be possible to instantiate the object in the capture function. - -We check if the capture is able to found a camera thanks to \e cap.isOpened(), and start a 30 seconds capture loop that will fill \e frame_ with the image from the camera. The capture could be stopped before 30 seconds if \e stop_capture_ boolean is turned to true. Once an image is captured, with the mutex we update the shared data. After the while loop, we also update the capture state to capture_stopped to finish the display thread. -\snippet tutorial-grabber-opencv-threaded.cpp capture-multi-threaded captureFunction - -\subsection multi-threading-capture-display-function Display thread - -We implement then displayFunction() used to display the captured images. This function doesn't exploit any argument. Depending on the OS we create a display pointer over the class that we want to use (vpDisplayX or vpDisplayGDI). We enter then in a while loop that will end when the capture is stopped, meaning that the \ref multi-threading-capture-function is finished. - -In the display loop, with the mutex we create a copy of the shared variables \e s_capture_state in order to use if just after. When capture is started we convert the OpenCV cv::mat image into a local ViSP image \e I. Since we access to the shared \e s_frame data, the conversion is protected by the mutex. Then with the first available ViSP image \e I we initialize the display and turn \e display_initialized_ boolean to false indicating that the display is already initialized. Next we update the display with the content of the image. -When we capture is not started, we just sleep for 2 milli-seconds. -\snippet tutorial-grabber-opencv-threaded.cpp capture-multi-threaded displayFunction - -\subsection multi-threading-capture-main Main thread - -The main thread is the one that is implemented in the main() function. -We manage first the command line option "--device " to allow the user to select a specific camera when more then one camera are connected. Then as explained in \ref multi-threading-capture-function we need the create cv::VideoCapture object in the main(). Finally, captureFunction() and displayFunction() are started as two separate threads, one for the capture, an other one for the display using vpThread constructor. - -The call to join() is here to wait until capture and display thread ends to return from the main(). -\snippet tutorial-grabber-opencv-threaded.cpp capture-multi-threaded mainFunction - -Once build, to run this tutorial just run in a terminal: -\code -cd /tutorial/grabber -./tutorial-grabber-opencv-threaded --help -./tutorial-grabber-opencv-threaded --device 0 -\endcode - -where "--device 0" could be avoided since it is the default option. - -\section multi-threading-face-detection Extension to face detection - -Note that all the material (source code) described in this section is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/detection/face -\endcode - -The example given in the previous section \ref multi-threading-capture could be extended to introduce an image processing. In this section, we illustrate the case of the face detection described in \ref tutorial-detection-face and implemented in tutorial-face-detector-live.cpp as a single main thread. Now we propose to extend this example using multi-threading where face detection is achieved in a separate thread. The complete source code is given in tutorial-face-detector-live-threaded.cpp. - -Here after we give the changes that we introduce in tutorial-face-detector-live-threaded.cpp to add a new thread dedicated to the face detection. - -\subsection multi-threading-face-detection-function Face detection thread - -The function that does the face detection is implemented in detectionFunction(). -We first instantiate an object of type vpDetectorFace. Then in the while loop, we call the face detection function using face_detector_.detect() when a new image is available. When faces are found, we retrieve the bounding box of the first face that is the largest in the image. We update the shared \e s_face_bbox var with the bounding box. This var is then exploited in the display thread and displayed as a rectangle. -\snippet tutorial-face-detector-live-threaded.cpp face-detection-threaded detectionFunction - -\subsection multi-threading-face-detection-main Main thread - -The main() is modified to call the detectionFunction() in a third thread. -\note Compared to the \ref multi-threading-capture-main used in tutorial-grabber-opencv-threaded.cpp, we modify here the main() to be able to capture images either from a webcam when Video For Linux 2 (V4L2) is available (only on Linux-like OS), or using OpenCV cv::VideoCapture when V4L2 is not available. - -\snippet tutorial-face-detector-live-threaded.cpp face-detection-threaded mainFunction - -To run the binary just open a terminal and run: -\code -cd /tutorial/detection/face -./tutorial-face-detector-live-threaded --help -./tutorial-face-detector-live-threaded -\endcode - -*/ diff --git a/doc/tutorial/tutorial-users.dox b/doc/tutorial/tutorial-users.dox index 8440e9a3f2..43e6e80996 100644 --- a/doc/tutorial/tutorial-users.dox +++ b/doc/tutorial/tutorial-users.dox @@ -166,8 +166,6 @@ This page introduces the user to other tools that may be useful. - \subpage tutorial-plotter
This tutorial explains how to plot curves in real-time during a visual servo. - \subpage tutorial-trace
This tutorial explains how to introduce trace in the code that could be enabled for debugging or disabled. -- \subpage tutorial-multi-threading
This tutorial explains how to implement multi-threaded applications to capture images from a camera -in one thread and display these images in an other thread. - \subpage tutorial-pcl-viewer
This tutorial explains how to use a threaded PCL-based point cloud visualizer. - \subpage tutorial-json
This tutorial explains how to read and save data in the portable JSON format. It focuses on saving the data generated by a visual servoing experiment and exporting it to Python in order to generate plots. - \subpage tutorial-synthetic-blenderproc
This tutorial shows you how to easily generate synthetic data from the 3D model of an object and obtain various modalities. This data can then be used to train a neural network for your own task. diff --git a/modules/core/include/visp3/core/vpMutex.h b/modules/core/include/visp3/core/vpMutex.h index 172ded0ad2..9c05b9d067 100644 --- a/modules/core/include/visp3/core/vpMutex.h +++ b/modules/core/include/visp3/core/vpMutex.h @@ -61,10 +61,6 @@ native Windows threading capabilities if pthread is not available under Windows. - An example of vpMutex usage is given in testMutex.cpp. - - More examples are provided in \ref tutorial-multi-threading. - \sa vpScopedLock */ class vp_deprecated vpMutex @@ -159,8 +155,6 @@ class vp_deprecated vpMutex } \endcode - More examples are provided in \ref tutorial-multi-threading. - \sa vpMutex */ class vpScopedLock diff --git a/modules/core/include/visp3/core/vpThread.h b/modules/core/include/visp3/core/vpThread.h index 672ba84ffb..be654680a1 100644 --- a/modules/core/include/visp3/core/vpThread.h +++ b/modules/core/include/visp3/core/vpThread.h @@ -59,13 +59,6 @@ This class implements native pthread functionalities if available, or native Windows threading capabilities if pthread is not available under Windows. - - There are two examples implemented in testMutex.cpp and testThread.cpp to - show how to use this class. The content of test-thread.cpp that highlights - the main functionalities of this class is given hereafter: \snippet - testThread.cpp Code - - More examples are provided in \ref tutorial-multi-threading. */ class vp_deprecated vpThread { From f1b1dedaedcddf3fb96598179dd8014742cd2c0b Mon Sep 17 00:00:00 2001 From: rlagneau Date: Thu, 7 Mar 2024 13:16:02 +0100 Subject: [PATCH 074/164] [DOC] Added Doxygen file tag in headers --- modules/core/include/visp3/core/vpStatisticalTestAbstract.h | 4 ++++ modules/core/include/visp3/core/vpStatisticalTestEWMA.h | 4 ++++ modules/core/include/visp3/core/vpStatisticalTestHinkley.h | 4 ++++ .../include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h | 4 ++++ modules/core/include/visp3/core/vpStatisticalTestSigma.h | 4 ++++ 5 files changed, 20 insertions(+) diff --git a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h index a365125c71..f7e885713a 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h +++ b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h @@ -29,6 +29,10 @@ * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. * *****************************************************************************/ +/*! + * \file vpStatisticalTestAbstract.h + * \brief Base class for Statistical Process Control methods implementation. + */ #ifndef _vpStatisticalTestAbstract_h_ #define _vpStatisticalTestAbstract_h_ diff --git a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h index 3bfa0346bf..866c0fe274 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h +++ b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h @@ -29,6 +29,10 @@ * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. * *****************************************************************************/ +/*! + * \file vpStatisticalTestEWMA.h + * \brief Statistical Process Control Exponentially Weighted Moving Average implementation. + */ #ifndef _vpStatisticalTestEWMA_h_ #define _vpStatisticalTestEWMA_h_ diff --git a/modules/core/include/visp3/core/vpStatisticalTestHinkley.h b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h index 0b34bee22b..92303a4378 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestHinkley.h +++ b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h @@ -29,6 +29,10 @@ * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. * *****************************************************************************/ +/*! + * \file vpStatisticalTestHinkley.h + * \brief Statistical Process Control Hinkley's test implementation. + */ #ifndef _vpStatisticalTestHinkley_h_ #define _vpStatisticalTestHinkley_h_ diff --git a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h index 2f514eee6d..b1fee06431 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h +++ b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h @@ -29,6 +29,10 @@ * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. * *****************************************************************************/ +/*! + * \file vpStatisticalTestMeanAdjustedCUSUM.h + * \brief Statistical Process Control mean adjusted CUSUM implementation. + */ #ifndef _vpStatisticalTestMeanAdjustedCUSUM_h_ #define _vpStatisticalTestMeanAdjustedCUSUM_h_ diff --git a/modules/core/include/visp3/core/vpStatisticalTestSigma.h b/modules/core/include/visp3/core/vpStatisticalTestSigma.h index 72036c860e..086b866a5b 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestSigma.h +++ b/modules/core/include/visp3/core/vpStatisticalTestSigma.h @@ -29,6 +29,10 @@ * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. * *****************************************************************************/ +/*! + * \file vpStatisticalTestSigma.h + * \brief Statistical Process Control sigma test implementation. + */ #ifndef _vpStatisticalTestSigma_h_ #define _vpStatisticalTestSigma_h_ From e1709037d9782ab27e1ee097327f5f7f5ec2b1ed Mon Sep 17 00:00:00 2001 From: rlagneau Date: Thu, 7 Mar 2024 15:48:38 +0100 Subject: [PATCH 075/164] [CORPS] Added Shehwhart's test, updated tutorial and added auto mode to Hinkley's test --- .../visp3/core/vpStatisticalTestAbstract.h | 75 ++-- .../visp3/core/vpStatisticalTestEWMA.h | 26 +- .../visp3/core/vpStatisticalTestHinkley.h | 103 +++-- .../core/vpStatisticalTestMeanAdjustedCUSUM.h | 19 +- .../visp3/core/vpStatisticalTestShewhart.h | 207 ++++++++++ .../visp3/core/vpStatisticalTestSigma.h | 27 +- .../math/misc/vpStatisticalTestAbstract.cpp | 73 +++- .../src/math/misc/vpStatisticalTestEWMA.cpp | 8 +- .../math/misc/vpStatisticalTestHinkley.cpp | 102 ++++- .../vpStatisticalTestMeanAdjustedCUSUM.cpp | 8 +- .../math/misc/vpStatisticalTestShewhart.cpp | 308 +++++++++++++++ .../src/math/misc/vpStatisticalTestSigma.cpp | 16 +- tutorial/mean-drift/tutorial-meandrift.cpp | 353 ++++++++++++++++-- 13 files changed, 1180 insertions(+), 145 deletions(-) create mode 100644 modules/core/include/visp3/core/vpStatisticalTestShewhart.h create mode 100644 modules/core/src/math/misc/vpStatisticalTestShewhart.cpp diff --git a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h index f7e885713a..ac5d7867ae 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h +++ b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h @@ -47,18 +47,26 @@ /** * \ingroup group_core_math_tools * \brief Base class for methods detecting the drift of the mean of a process. + * + * To detect only downward drifts of the input signal \f$ s(t) \f$ use + * 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: /** - * \brief Enum that indicates if a drift of the mean occured. + * \brief Enum that indicates if a drift of the mean occurred. */ typedef enum vpMeanDriftType { - NO_MEAN_DRIFT = 0, /*!< No mean drift occured*/ - MEAN_DRIFT_DOWNWARD = 1, /*!< A downward drift of the mean occured.*/ - MEAN_DRIFT_UPWARD = 2 /*!< An upward drift of the mean occured.*/ + MEAN_DRIFT_NONE = 0, /*!< No mean drift occurred*/ + MEAN_DRIFT_DOWNWARD = 1, /*!< A downward drift of the mean occurred.*/ + MEAN_DRIFT_UPWARD = 2, /*!< An upward drift of the mean occurred.*/ + MEAN_DRIFT_BOTH = 3, /*!< Both an aupward and a downward drifts occurred.*/ + MEAN_DRIFT_COUNT = 4, + MEAN_DRIFT_UNKNOWN = MEAN_DRIFT_COUNT } vpMeanDriftType; /** @@ -69,6 +77,25 @@ class VISP_EXPORT vpStatisticalTestAbstract */ static std::string vpMeanDriftTypeToString(const vpMeanDriftType &type); + /** + * \brief Cast a string into a \b vpMeanDriftType. + * + * \param[in] name The name of the mean drift. + * \return vpMeanDriftType The corresponding \b vpMeanDriftType. + */ + static vpMeanDriftType vpMeanDriftTypeFromString(const std::string &name); + + /** + * \brief Get the list of available \b vpMeanDriftType objects that are handled. + * + * \param[in] prefix The prefix that should be placed before the list. + * \param[in] sep The separator between each element of the list. + * \param[in] suffix The suffix that should terminate the list. + * \return std::string The list of handled type of process tests, presented as a string. + */ + static std::string getAvailableMeanDriftType(const std::string &prefix = "<", const std::string &sep = " , ", + const std::string &suffix = ">"); + /** * \brief Print the message corresponding to the type of mean drift. * @@ -89,22 +116,22 @@ class VISP_EXPORT vpStatisticalTestAbstract float m_sumForMean; /*!< Sum of the samples used to compute the mean and standard deviation.*/ /** - * \brief Detects if a downward mean drift occured. + * \brief Detects if a downward mean drift occurred. * - * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occured, \b vpMeanDriftType::NO_MEAN_DRIFT otherwise. + * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occurred, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. * - * \sa detectUpwardMeanShift() + * \sa detectUpwardMeanDrift() */ - virtual vpMeanDriftType detectDownwardMeanShift() = 0; + virtual vpMeanDriftType detectDownwardMeanDrift() = 0; /** - * \brief Detects if a upward mean drift occured. + * \brief Detects if a upward mean drift occurred. * - * \return \b vpMeanDriftType::MEAN_DRIFT_UPWARD if an upward mean drift occured, \b vpMeanDriftType::NO_MEAN_DRIFT otherwise. + * \return \b vpMeanDriftType::MEAN_DRIFT_UPWARD if an upward mean drift occurred, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. * - * \sa detectDownwardMeanShift() + * \sa detectDownwardMeanDrift() */ - virtual vpMeanDriftType detectUpwardMeanShift() = 0; + virtual vpMeanDriftType detectUpwardMeanDrift() = 0; /** * \brief Update \b m_s and if enough values are available, compute the mean, the standard @@ -203,37 +230,37 @@ class VISP_EXPORT vpStatisticalTestAbstract void setNbSamplesForStat(const unsigned int &nbSamples); /** - * \brief Test if a downward or an upward mean drift occured + * \brief Test if a downward or an upward mean drift occurred * according to the new value of the signal. * * \param[in] signal The new value of the signal. - * \return vpMeanDriftType The type of mean drift that occured. + * \return vpMeanDriftType The type of mean drift that occurred. * - * \sa testDownwardMeanShift() testUpwardMeanShift() + * \sa testDownwardMeanDrift() testUpwardMeanDrift() */ - vpMeanDriftType testDownUpwardMeanShift(const float &signal); + vpMeanDriftType testDownUpwardMeanDrift(const float &signal); /** - * \brief Test if a downward mean drift occured + * \brief Test if a downward mean drift occurred * according to the new value of the signal. * * \param[in] signal The new value of the signal. - * \return vpMeanDriftType The type of mean drift that occured. + * \return vpMeanDriftType The type of mean drift that occurred. * - * \sa testUpwardMeanShift() + * \sa testUpwardMeanDrift() */ - vpMeanDriftType testDownwardMeanShift(const float &signal); + vpMeanDriftType testDownwardMeanDrift(const float &signal); /** - * \brief Test if an upward mean drift occured + * \brief Test if an upward mean drift occurred * according to the new value of the signal. * * \param[in] signal The new value of the signal. - * \return vpMeanDriftType The type of mean drift that occured. + * \return vpMeanDriftType The type of mean drift that occurred. * - * \sa testDownwardMeanShift() + * \sa testDownwardMeanDrift() */ - vpMeanDriftType testUpwardMeanShift(const float &signal); + vpMeanDriftType testUpwardMeanDrift(const float &signal); }; #endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h index 866c0fe274..b2df53beaa 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h +++ b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h @@ -58,25 +58,29 @@ class VISP_EXPORT vpStatisticalTestEWMA : public vpStatisticalTestAbstract virtual void computeDeltaAndLimits(); /** - * \brief Detects if a downward jump occured on the mean. + * \brief Detects if a downward mean drift occured. * - * \return downwardJump if a downward jump occured, noJump otherwise. + * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occured, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. + * + * \sa detectUpwardMeanDrift() */ #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - virtual vpMeanDriftType detectDownwardMeanShift() override; + virtual vpMeanDriftType detectDownwardMeanDrift() override; #else - virtual vpMeanDriftType detectDownwardMeanShift(); + virtual vpMeanDriftType detectDownwardMeanDrift(); #endif -/** - * \brief Detects if a upward jump occured on the mean. - * - * \return upwardJump if a upward jump occured, noJump otherwise. - */ + /** + * \brief Detects if an upward mean drift occured on the mean. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_UPWARD if an upward mean drift occured, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. + * + * \sa detectDownwardMeanDrift() + */ #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - virtual vpMeanDriftType detectUpwardMeanShift() override; + virtual vpMeanDriftType detectUpwardMeanDrift() override; #else - virtual vpMeanDriftType detectUpwardMeanShift(); + virtual vpMeanDriftType detectUpwardMeanDrift(); #endif /** diff --git a/modules/core/include/visp3/core/vpStatisticalTestHinkley.h b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h index 92303a4378..e07d4b1591 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestHinkley.h +++ b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h @@ -76,9 +76,9 @@ A upward drift is detected if \f$ T_k - N_k > \alpha \f$. To detect only downward drifts in \f$ s(t) \f$ use - testDownwardJump().To detect only upward drifts in \f$ s(t) \f$ use - testUpwardJump(). To detect both, downward and upward drifts use - testDownUpwardJump(). + testDownwardMeanDrift().To detect only upward drifts in \f$ s(t) \f$ use + testUpwardMeanDrift(). To detect both, downward and upward drifts use + testDownUpwardMeanDrift(). 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^{'}} - @@ -93,6 +93,15 @@ class VISP_EXPORT vpStatisticalTestHinkley : public vpStatisticalTestAbstract float m_Mk; /*!< Maximum of the test signal for downward mean drift \f$S_k\f$ .*/ float m_Tk; /*!< Test signal for upward mean drift.*/ float m_Nk; /*!< Minimum of the test signal for upward mean drift \f$T_k\f$*/ + bool m_computeDeltaAndAlpha; /*!< If true, compute \f$\delta\f$ and \f$\alpha\f$ from the standard deviation, + the alarm factor and the detection factor.*/ + float m_h; /*!< The alarm factor, that permits to compute \f$\alpha\f$ from the standard deviation of the signal.*/ + float m_k; /*!< The detection factor, that permits to compute \f$\delta\f$ from the standard deviation of the signal.*/ + + /** + * \brief Compute \f$\delta\f$ and \f$\alpha\f$ from the standard deviation of the signal. + */ + virtual void computeAlphaDelta(); /** * \brief Compute the mean value \f$m_0\f$ of the signal. The mean value must be @@ -127,25 +136,39 @@ class VISP_EXPORT vpStatisticalTestHinkley : public vpStatisticalTestAbstract void computeNk(); /** - * \brief Detects if a downward mean drift occured. + * \brief Detects if a downward mean drift occurred. * - * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occured, \b vpMeanDriftType::NO_MEAN_DRIFT otherwise. + * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occurred, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. */ #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - virtual vpMeanDriftType detectDownwardMeanShift() override; + virtual vpMeanDriftType detectDownwardMeanDrift() override; #else - virtual vpMeanDriftType detectDownwardMeanShift(); + virtual vpMeanDriftType detectDownwardMeanDrift(); #endif -/** - * \brief Detects if a upward mean drift occured. - * - * \return \b vpMeanDriftType::MEAN_DRIFT_UPWARD if an upward mean drift occured, \b vpMeanDriftType::NO_MEAN_DRIFT otherwise. - */ + /** + * \brief Detects if an upward mean drift occured on the mean. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_UPWARD if an upward mean drift occured, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. + * + * \sa detectDownwardMeanDrift() + */ #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - virtual vpMeanDriftType detectUpwardMeanShift() override; + virtual vpMeanDriftType detectUpwardMeanDrift() override; #else - virtual vpMeanDriftType detectUpwardMeanShift(); + virtual vpMeanDriftType detectUpwardMeanDrift(); +#endif + + /** + * \brief Update m_s and if enough values are available, compute the mean, the standard + * deviation and the limits. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual bool updateStatistics(const float &signal) override; +#else + virtual bool updateStatistics(const float &signal); #endif /** @@ -181,6 +204,28 @@ class VISP_EXPORT vpStatisticalTestHinkley : public vpStatisticalTestAbstract */ vpStatisticalTestHinkley(const float &alpha, const float &delta, const unsigned int &nbSamplesForInit = 30); + /** + * \brief Construct a new vpStatisticalTestHinkley object. \f$\alpha\f$ and \f$\delta\f$ will be computed + * from the standard deviation of the signal. + * + * \param[in] h : the alarm factor that permits to compute \f$\alpha\f$ from the standard deviation. + * \param[in] k : the detection factor that permits to compute \f$\delta\f$ from the standard deviation. + * \param[in] computeAlphaDeltaFromStdev : must be equal to true, otherwise throw a vpException. + * \param[in] nbSamplesForInit : number of signal samples to initialize the mean of the signal. + */ + vpStatisticalTestHinkley(const float &h, const float &k, const bool &computeAlphaDeltaFromStdev, const unsigned int &nbSamplesForInit = 30); + + /** + * \brief Construct a new vpStatisticalTestHinkley object. \f$\alpha\f$ and \f$\delta\f$ will be computed + * from the standard deviation of the signal. + * + * \param[in] h : the alarm factor that permits to compute \f$\alpha\f$ from the standard deviation. + * \param[in] k : the detection factor that permits to compute \f$\delta\f$ from the standard deviation. + * \param[in] mean : the expected mean of the signal. + * \param[in] stdev : the expected standard deviation of the signal. + */ + vpStatisticalTestHinkley(const float &h, const float &k, const float &mean, const float &stdev); + /** * \brief Destroy the vpStatisticalTestHinkley object. */ @@ -228,14 +273,6 @@ class VISP_EXPORT vpStatisticalTestHinkley : public vpStatisticalTestAbstract */ void init(); - /** - * \brief Initialise the Hinkley's test by setting the mean signal value - * \f$m_0\f$ to the expected value and \f$S_k, M_k, T_k, N_k\f$ to 0. - * - * \param[in] mean The expected value of the mean. - */ - void init(const float &mean); - /** * \brief Call init() to initialise the Hinkley's test and set \f$\alpha\f$ * and \f$\delta\f$ thresholds. @@ -246,6 +283,17 @@ class VISP_EXPORT vpStatisticalTestHinkley : public vpStatisticalTestAbstract */ void init(const float &alpha, const float &delta, const unsigned int &nbSamplesForInit); + /** + * \brief (Re)Initialize a new vpStatisticalTestHinkley object. \f$\alpha\f$ and \f$\delta\f$ will be computed + * from the standard deviation of the signal. + * + * \param[in] h : the alarm factor that permits to compute \f$\alpha\f$ from the standard deviation. + * \param[in] k : the detection factor that permits to compute \f$\delta\f$ from the standard deviation. + * \param[in] computeAlphaDeltaFromStdev : must be equal to true, otherwise throw a vpException. + * \param[in] nbSamplesForInit : number of signal samples to initialize the mean of the signal. + */ + void init(const float &h, const float &k, const bool &computeAlphaDeltaFromStdev, const unsigned int &nbSamplesForInit); + /** * \brief Call init() to initialise the Hinkley's test, set \f$\alpha\f$ * and \f$\delta\f$ thresholds, and the mean of the signal \f$m_0\f$. @@ -256,6 +304,17 @@ class VISP_EXPORT vpStatisticalTestHinkley : public vpStatisticalTestAbstract */ void init(const float &alpha, const float &delta, const float &mean); + /** + * \brief (Re)Initialize a new vpStatisticalTestHinkley object. \f$\alpha\f$ and \f$\delta\f$ will be computed + * from the standard deviation of the signal. + * + * \param[in] h : the alarm factor that permits to compute \f$\alpha\f$ from the standard deviation. + * \param[in] k : the detection factor that permits to compute \f$\delta\f$ from the standard deviation. + * \param[in] mean : the expected mean of the signal. + * \param[in] stdev : the expected standard deviation of the signal. + */ + void init(const float &h, const float &k, const float &mean, const float &stdev); + /** * \brief Set the drift minimal magnitude that we want to detect. * diff --git a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h index b1fee06431..5bdd6f06f5 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h +++ b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h @@ -61,21 +61,28 @@ class VISP_EXPORT vpStatisticalTestMeanAdjustedCUSUM : public vpStatisticalTestA */ virtual void computeDeltaAndLimits(); + /** + * \brief Detects if a downward mean drift occured. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occured, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. + * + * \sa detectUpwardMeanDrift() + */ #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - virtual vpMeanDriftType detectDownwardMeanShift() override; + virtual vpMeanDriftType detectDownwardMeanDrift() override; #else - virtual vpMeanDriftType detectDownwardMeanShift(); + virtual vpMeanDriftType detectDownwardMeanDrift(); #endif /** - * \brief Detects if a upward jump occured on the mean. + * \brief Detects if a upward jump occurred on the mean. * - * \return upwardJump if a upward jump occured, noJump otherwise. + * \return upwardJump if a upward jump occurred, noJump otherwise. */ #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - virtual vpMeanDriftType detectUpwardMeanShift() override; + virtual vpMeanDriftType detectUpwardMeanDrift() override; #else - virtual vpMeanDriftType detectUpwardMeanShift(); + virtual vpMeanDriftType detectUpwardMeanDrift(); #endif /** diff --git a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h new file mode 100644 index 0000000000..22e9d66a3d --- /dev/null +++ b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h @@ -0,0 +1,207 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ +/*! + * \file vpStatisticalTestShewhart.h + * \brief Statistical Process Control Shewhart's test implementation. + */ + +#ifndef _vpStatisticalTestShewhartTest_h_ +#define _vpStatisticalTestShewhartTest_h_ + +#include + +#include +#include + +/** + * \ingroup group_core_math_tools + * \brief Class that permits a Shewhart test. + */ + +class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma +{ +public: + typedef enum vpWecoRulesAlarm + { + THREE_SIGMA_WECO = 0, + TWO_SIGMA_WECO = 1, + ONE_SIGMA_WECO = 2, + SAME_SIDE_WECO = 3, + NONE_WECO = 4, + COUNT_WECO = 5 + } vpWecoRulesAlarm; + + static std::string vpWecoRulesAlarmToString(const vpWecoRulesAlarm &alarm); + + static const bool CONST_ALL_WECO_ACTIVATED[COUNT_WECO - 1]; + +protected: + static const int NB_DATA_SIGNAL = 8; + unsigned int m_nbDataInBuffer; /*!< Indicate how many data are available in the circular buffer.*/ + float m_signal[NB_DATA_SIGNAL]; /*!< The last values of the signal.*/ + bool m_activateWECOrules; /*!< If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + control chart but the false alarm frequency is also increased.)*/ + bool m_activatedWECOrules[COUNT_WECO - 1]; /*!< The WECO rules that are activated. The more are activated, the higher the + sensitivity of the Shewhart control chart is but the higher the false + alarm frequency is.*/ + int m_idCurrentData; /*!< The index of the current data in m_signal.*/ + vpWecoRulesAlarm m_alarm; /*!< The type of alarm raised due to WECO rules.*/ + float m_oneSigmaNegLim; /*!< The mean - sigma lower threshold.*/ + float m_oneSigmaPosLim; /*!< The mean + sigma lower threshold.*/ + float m_twoSigmaNegLim; /*!< The mean - 2 sigma lower threshold.*/ + float m_twoSigmaPosLim; /*!< The mean + 2 sigma lower threshold.*/ + + /** + * \brief Compute the upper and lower limits of the test signal. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual void computeLimits() override; +#else + virtual void computeLimits(); +#endif + +/** + * \brief Detects if a downward mean drift occured. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occured, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. + * + * \sa detectUpwardMeanDrift() + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectDownwardMeanDrift() override; +#else + virtual vpMeanDriftType detectDownwardMeanDrift(); +#endif + + /** + * \brief Detects if an upward mean drift occured on the mean. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_UPWARD if an upward mean drift occured, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. + * + * \sa detectDownwardMeanDrift() + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual vpMeanDriftType detectUpwardMeanDrift() override; +#else + virtual vpMeanDriftType detectUpwardMeanDrift(); +#endif + + /** + * \brief Update m_s and if enough values are available, compute the mean, the standard + * deviation and the limits. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual bool updateStatistics(const float &signal) override; +#else + virtual bool updateStatistics(const float &signal); +#endif + + /** + * \brief Update the test signals. + * + * \param[in] signal The new value of the signal to monitor. + */ +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + virtual void updateTestSignals(const float &signal) override; +#else + virtual void updateTestSignals(const float &signal); +#endif +public: + /** + * \brief Construct a new vpStatisticalTestShewhart object. + * + * \param[in] activateWECOrules If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + * control chart but the false alarm frequency is also increased.) + * \param[in] nbSamplesForStats The number of samples to compute the statistics of the signal. + */ + vpStatisticalTestShewhart(const bool &activateWECOrules = true, const bool activatedRules[COUNT_WECO - 1] = CONST_ALL_WECO_ACTIVATED, const unsigned int &nbSamplesForStats = 30); + + /** + * \brief Construct a new vpStatisticalTestShewhart object. + * + * \param[in] activateWECOrules If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + * control chart but the false alarm frequency is also increased.) + * \param[in] mean The expected mean of the signal. + * \param[in] stdev The expected standard deviation of the signal. + */ + vpStatisticalTestShewhart(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1], const float &mean, const float &stdev); + + /** + * \brief Get the alarm raised by the last test due to the WECO rules. + * + * \return vpWecoRulesAlarm The type of raised alarm. + */ + vpWecoRulesAlarm getAlarm() const + { + return m_alarm; + } + + /** + * \brief Get the last value of the signal. + * + * \return float The signal. + */ + inline float getSignal() const + { + return m_signal[m_idCurrentData]; + } + + /** + * \brief Get the NB_DATA_SIGNAL last signal values, sorted from the latest [0] to the newest [NB_DATA_SIGNAL - 1]. + * + * \return std::vector The last NB_DATA_SIGNAL values. + */ + std::vector getSignals() const; + + /** + * \brief (Re)Initialize the test. + * + * \param[in] activateWECOrules If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + * control chart but the false alarm frequency is also increased.) + * \param[in] nbSamplesForStats The number of samples to compute the statistics of the signal. + */ + void init(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1] = CONST_ALL_WECO_ACTIVATED, const unsigned int &nbSamplesForStats = 30); + + /** + * \brief (Re)Initialize the test. + * + * \param[in] activateWECOrules If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + * control chart but the false alarm frequency is also increased.) + * \param[in] mean The expected mean of the signal. + * \param[in] stdev The expected standard deviation of the signal. + */ + void init(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1], const float &mean, const float &stdev); +}; + +#endif diff --git a/modules/core/include/visp3/core/vpStatisticalTestSigma.h b/modules/core/include/visp3/core/vpStatisticalTestSigma.h index 086b866a5b..94476df584 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestSigma.h +++ b/modules/core/include/visp3/core/vpStatisticalTestSigma.h @@ -58,21 +58,30 @@ class VISP_EXPORT vpStatisticalTestSigma : public vpStatisticalTestAbstract */ virtual void computeLimits(); + /** + * \brief Detects if a downward mean drift occured. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_DOWNWARD if a downward mean drift occured, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. + * + * \sa detectUpwardMeanDrift() + */ #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - virtual vpMeanDriftType detectDownwardMeanShift() override; + virtual vpMeanDriftType detectDownwardMeanDrift() override; #else - virtual vpMeanDriftType detectDownwardMeanShift(); + virtual vpMeanDriftType detectDownwardMeanDrift(); #endif -/** - * \brief Detects if a upward jump occured on the mean. - * - * \return upwardJump if a upward jump occured, noJump otherwise. - */ + /** + * \brief Detects if an upward mean drift occured on the mean. + * + * \return \b vpMeanDriftType::MEAN_DRIFT_UPWARD if an upward mean drift occured, \b vpMeanDriftType::MEAN_DRIFT_NONE otherwise. + * + * \sa detectDownwardMeanDrift() + */ #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - virtual vpMeanDriftType detectUpwardMeanShift() override; + virtual vpMeanDriftType detectUpwardMeanDrift() override; #else - virtual vpMeanDriftType detectUpwardMeanShift(); + virtual vpMeanDriftType detectUpwardMeanDrift(); #endif /** diff --git a/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp index 591674dd77..4986a117b9 100644 --- a/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp @@ -43,22 +43,56 @@ std::string vpStatisticalTestAbstract::vpMeanDriftTypeToString(const vpStatistic { std::string name; switch (type) { - case NO_MEAN_DRIFT: - name = " No jump"; + case MEAN_DRIFT_NONE: + name = "no_drift"; break; case MEAN_DRIFT_DOWNWARD: - name = " Jump downward"; + name = "downward_drift"; break; case MEAN_DRIFT_UPWARD: - name = " Jump upward"; + name = "upward_drift"; break; + case MEAN_DRIFT_BOTH: + name = "both_drift"; + break; + case MEAN_DRIFT_UNKNOWN: default: - name = " Undefined jump"; + name = "undefined_drift"; break; } return name; } +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::vpMeanDriftTypeFromString(const std::string &name) +{ + vpMeanDriftType result = MEAN_DRIFT_UNKNOWN; + unsigned int count = static_cast(MEAN_DRIFT_COUNT); + unsigned int id = 0; + bool hasNotFound = true; + while ((id < count) && hasNotFound) { + vpMeanDriftType temp = static_cast(id); + if (vpMeanDriftTypeToString(temp) == name) { + result = temp; + hasNotFound = false; + } + ++id; + } + return result; +} + +std::string vpStatisticalTestAbstract::getAvailableMeanDriftType(const std::string &prefix, const std::string &sep, + const std::string &suffix) +{ + std::string msg(prefix); + unsigned int count = static_cast(MEAN_DRIFT_COUNT); + unsigned int lastId = count - 1; + for (unsigned int i = 0; i < lastId; i++) { + msg += vpMeanDriftTypeToString(static_cast(i)) + sep; + } + msg += vpMeanDriftTypeToString(static_cast(lastId)) + suffix; + return msg; +} + void vpStatisticalTestAbstract::print(const vpStatisticalTestAbstract::vpMeanDriftType &type) { std::cout << vpMeanDriftTypeToString(type) << " detected" << std::endl; @@ -163,48 +197,51 @@ void vpStatisticalTestAbstract::setNbSamplesForStat(const unsigned int &nbSample m_s = new float[nbSamples]; } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testDownUpwardMeanShift(const float &signal) +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testDownUpwardMeanDrift(const float &signal) { if (m_areStatisticsComputed) { updateTestSignals(signal); - vpMeanDriftType jumpDown = detectDownwardMeanShift(); - vpMeanDriftType jumpUp = detectUpwardMeanShift(); - if (jumpDown != NO_MEAN_DRIFT) { + vpMeanDriftType jumpDown = detectDownwardMeanDrift(); + vpMeanDriftType jumpUp = detectUpwardMeanDrift(); + if ((jumpDown != MEAN_DRIFT_NONE) && (jumpUp != MEAN_DRIFT_NONE)) { + return MEAN_DRIFT_BOTH; + } + else if (jumpDown != MEAN_DRIFT_NONE) { return jumpDown; } - else if (jumpUp != NO_MEAN_DRIFT) { + else if (jumpUp != MEAN_DRIFT_NONE) { return jumpUp; } else { - return NO_MEAN_DRIFT; + return MEAN_DRIFT_NONE; } } else { updateStatistics(signal); - return NO_MEAN_DRIFT; + return MEAN_DRIFT_NONE; } } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testDownwardMeanShift(const float &signal) +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testDownwardMeanDrift(const float &signal) { if (m_areStatisticsComputed) { updateTestSignals(signal); - return detectDownwardMeanShift(); + return detectDownwardMeanDrift(); } else { updateStatistics(signal); - return NO_MEAN_DRIFT; + return MEAN_DRIFT_NONE; } } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testUpwardMeanShift(const float &signal) +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestAbstract::testUpwardMeanDrift(const float &signal) { if (m_areStatisticsComputed) { updateTestSignals(signal); - return detectUpwardMeanShift(); + return detectUpwardMeanDrift(); } else { updateStatistics(signal); - return NO_MEAN_DRIFT; + return MEAN_DRIFT_NONE; } } diff --git a/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp b/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp index d4dd6a5e28..6cb06fee31 100644 --- a/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp @@ -47,23 +47,23 @@ void vpStatisticalTestEWMA::computeDeltaAndLimits() m_limitUp = m_mean + delta; } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestEWMA::detectDownwardMeanShift() +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestEWMA::detectDownwardMeanDrift() { if (m_wt <= m_limitDown) { return MEAN_DRIFT_DOWNWARD; } else { - return NO_MEAN_DRIFT; + return MEAN_DRIFT_NONE; } } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestEWMA::detectUpwardMeanShift() +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestEWMA::detectUpwardMeanDrift() { if (m_wt >= m_limitUp) { return MEAN_DRIFT_UPWARD; } else { - return NO_MEAN_DRIFT; + return MEAN_DRIFT_NONE; } } diff --git a/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp b/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp index b001d010b6..6d75931952 100644 --- a/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp @@ -30,8 +30,6 @@ * *****************************************************************************/ -#include - /** * * \file vpStatisticalTestHinkley.cpp @@ -57,6 +55,9 @@ vpStatisticalTestHinkley::vpStatisticalTestHinkley() , m_Mk(0.f) , m_Tk(0.f) , m_Nk(0.f) + , m_computeDeltaAndAlpha(false) + , m_h(4.76f) + , m_k(1.f) { init(); } @@ -69,16 +70,47 @@ vpStatisticalTestHinkley::vpStatisticalTestHinkley(const float &alpha, const flo , m_Mk(0.f) , m_Tk(0.f) , m_Nk(0.f) + , m_computeDeltaAndAlpha(false) + , m_h(4.76f) + , m_k(1.f) { init(alpha, delta_val, nbSamplesForInit); } +vpStatisticalTestHinkley::vpStatisticalTestHinkley(const float &h, const float &k, const bool &computeAlphaDeltaFromStdev, const unsigned int &nbSamplesForInit) + : vpStatisticalTestAbstract() +{ + init(h, k, computeAlphaDeltaFromStdev, nbSamplesForInit); +} + +vpStatisticalTestHinkley::vpStatisticalTestHinkley(const float &h, const float &k, const float &mean, const float &stdev) + : vpStatisticalTestAbstract() +{ + init(h, k, mean, stdev); +} + +void vpStatisticalTestHinkley::init() +{ + vpStatisticalTestAbstract::init(); + setNbSamplesForStat(30); + setAlpha(m_alpha); + + m_Sk = 0.f; + m_Mk = 0.f; + + m_Tk = 0.f; + m_Nk = 0.f; + + m_computeDeltaAndAlpha = false; +} + void vpStatisticalTestHinkley::init(const float &alpha, const float &delta_val, const unsigned int &nbSamplesForInit) { init(); setNbSamplesForStat(nbSamplesForInit); setAlpha(alpha); setDelta(delta_val); + m_computeDeltaAndAlpha = false; } void vpStatisticalTestHinkley::init(const float &alpha, const float &delta_val, const float &mean) @@ -87,31 +119,36 @@ void vpStatisticalTestHinkley::init(const float &alpha, const float &delta_val, setAlpha(alpha); setDelta(delta_val); m_mean = mean; + m_computeDeltaAndAlpha = false; m_areStatisticsComputed = true; } -vpStatisticalTestHinkley::~vpStatisticalTestHinkley() { } - -void vpStatisticalTestHinkley::init() +void vpStatisticalTestHinkley::init(const float &h, const float &k, const bool &computeAlphaDeltaFromStdev, const unsigned int &nbSamples) { - vpStatisticalTestAbstract::init(); - setNbSamplesForStat(30); - setAlpha(m_alpha); - - m_Sk = 0.f; - m_Mk = 0.f; - - m_Tk = 0.f; - m_Nk = 0.f; + if (!computeAlphaDeltaFromStdev) { + throw(vpException(vpException::badValue, "computeAlphaDeltaFromStdev must be true, or use another init function")); + } + init(); + setNbSamplesForStat(nbSamples); + m_h = h; + m_k = k; + m_computeDeltaAndAlpha = true; } -void vpStatisticalTestHinkley::init(const float &mean) +void vpStatisticalTestHinkley::init(const float &h, const float &k, const float &mean, const float &stdev) { - vpStatisticalTestHinkley::init(); + init(); m_mean = mean; + m_stdev = stdev; + m_h = h; + m_k = k; + m_computeDeltaAndAlpha = true; + computeAlphaDelta(); m_areStatisticsComputed = true; } +vpStatisticalTestHinkley::~vpStatisticalTestHinkley() { } + void vpStatisticalTestHinkley::setDelta(const float &delta) { m_dmin2 = delta / 2.f; } void vpStatisticalTestHinkley::setAlpha(const float &alpha) @@ -121,6 +158,14 @@ void vpStatisticalTestHinkley::setAlpha(const float &alpha) m_limitUp = m_alpha; } +void vpStatisticalTestHinkley::computeAlphaDelta() +{ + float delta = m_k * m_stdev; + setDelta(delta); + float alpha = m_h * m_stdev; + setAlpha(alpha); +} + void vpStatisticalTestHinkley::computeMean(double signal) { // When the mean slowly increases or decreases, especially after an abrupt change of the mean, @@ -158,24 +203,41 @@ void vpStatisticalTestHinkley::computeNk() } } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestHinkley::detectDownwardMeanShift() +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestHinkley::detectDownwardMeanDrift() { - vpStatisticalTestAbstract::vpMeanDriftType shift = NO_MEAN_DRIFT; + vpStatisticalTestAbstract::vpMeanDriftType shift = MEAN_DRIFT_NONE; if ((m_Mk - m_Sk) > m_alpha) { shift = MEAN_DRIFT_DOWNWARD; } return shift; } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestHinkley::detectUpwardMeanShift() +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestHinkley::detectUpwardMeanDrift() { - vpStatisticalTestAbstract::vpMeanDriftType shift = NO_MEAN_DRIFT; + vpStatisticalTestAbstract::vpMeanDriftType shift = MEAN_DRIFT_NONE; if ((m_Tk - m_Nk) > m_alpha) { shift = MEAN_DRIFT_UPWARD; } return shift; } +bool vpStatisticalTestHinkley::updateStatistics(const float &signal) +{ + bool updateStats = vpStatisticalTestAbstract::updateStatistics(signal); + if (m_areStatisticsComputed) { + // If needed, compute alpha and delta + if (m_computeDeltaAndAlpha) { + computeAlphaDelta(); + } + // Initialize the test signals + m_Mk = 0.f; + m_Nk = 0.f; + m_Sk = 0.f; + m_Tk = 0.f; + } + return updateStats; +} + void vpStatisticalTestHinkley::updateTestSignals(const float &signal) { computeSk(signal); diff --git a/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp b/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp index a60cf77798..0007b0a0eb 100644 --- a/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp @@ -48,23 +48,23 @@ void vpStatisticalTestMeanAdjustedCUSUM::computeDeltaAndLimits() setLimits(limitDown, limitUp); } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestMeanAdjustedCUSUM::detectDownwardMeanShift() +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestMeanAdjustedCUSUM::detectDownwardMeanDrift() { if (m_sminus >= m_limitDown) { return MEAN_DRIFT_DOWNWARD; } else { - return NO_MEAN_DRIFT; + return MEAN_DRIFT_NONE; } } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestMeanAdjustedCUSUM::detectUpwardMeanShift() +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestMeanAdjustedCUSUM::detectUpwardMeanDrift() { if (m_splus >= m_limitUp) { return MEAN_DRIFT_UPWARD; } else { - return NO_MEAN_DRIFT; + return MEAN_DRIFT_NONE; } } diff --git a/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp new file mode 100644 index 0000000000..794e8aea27 --- /dev/null +++ b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp @@ -0,0 +1,308 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * +*****************************************************************************/ + +/** +* +* \file vpStatisticalTestShewhart.cpp +* +* \brief Definition of the vpStatisticalTestShewhart class that implements Shewhart's +* mean drift test. +*/ + +#include + +#include + +#include + +const bool vpStatisticalTestShewhart::CONST_ALL_WECO_ACTIVATED[vpStatisticalTestShewhart::COUNT_WECO - 1] = { true, true, true, true }; + +std::string vpStatisticalTestShewhart::vpWecoRulesAlarmToString(const vpStatisticalTestShewhart::vpWecoRulesAlarm &alarm) +{ + std::string name; + switch (alarm) { + case THREE_SIGMA_WECO: + name = "3-sigma alarm"; + break; + case TWO_SIGMA_WECO: + name = "2-sigma alarm"; + break; + case ONE_SIGMA_WECO: + name = "1-sigma alarm"; + break; + case SAME_SIDE_WECO: + name = "Same-side alarm"; + break; + case NONE_WECO: + name = "No alarm"; + break; + default: + name = "Unknown WECO alarm"; + } + return name; +} + +void vpStatisticalTestShewhart::computeLimits() +{ + float delta = 3.f * m_stdev; + m_limitDown = m_mean - delta; + m_limitUp = m_mean + delta; + m_oneSigmaNegLim = m_mean - m_stdev; + m_oneSigmaPosLim = m_mean + m_stdev; + m_twoSigmaNegLim = m_mean - 2.f * m_stdev; + m_twoSigmaPosLim = m_mean + 2.f * m_stdev; +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestShewhart::detectDownwardMeanDrift() +{ + if (m_nbDataInBuffer < NB_DATA_SIGNAL) { + return vpStatisticalTestAbstract::MEAN_DRIFT_NONE; + } + if ((m_signal[m_idCurrentData] <= m_limitDown) && m_activatedWECOrules[THREE_SIGMA_WECO]) { + m_alarm = vpWecoRulesAlarm::THREE_SIGMA_WECO; + return vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD; + } + if (!m_activateWECOrules) { + return vpStatisticalTestAbstract::MEAN_DRIFT_NONE; + } + vpStatisticalTestAbstract::vpMeanDriftType result = vpStatisticalTestAbstract::MEAN_DRIFT_NONE; + int id = vpMath::modulo(m_idCurrentData - (NB_DATA_SIGNAL - 1), NB_DATA_SIGNAL); + int i = 0; + unsigned int nbAboveMean = 0; + unsigned int nbAbove2SigmaLimit = 0; + unsigned int nbAbove1SigmaLimit = 0; + while (i < NB_DATA_SIGNAL) { + // Reinit for next iteration + nbAbove2SigmaLimit = 0; + nbAbove1SigmaLimit = 0; + if (m_signal[id] <= m_mean && m_activatedWECOrules[SAME_SIDE_WECO]) { + // Single-side test + ++nbAboveMean; + } + if (i > 3 && m_activatedWECOrules[TWO_SIGMA_WECO]) { + // Two sigma test + for (int idPrev = vpMath::modulo(id - 2, NB_DATA_SIGNAL); idPrev != id; idPrev = vpMath::modulo(idPrev + 1, NB_DATA_SIGNAL)) { + if (m_signal[idPrev] <= m_twoSigmaNegLim) { + ++nbAbove2SigmaLimit; + } + } + if (m_signal[id] <= m_twoSigmaNegLim) { + ++nbAbove2SigmaLimit; + } + if (nbAbove2SigmaLimit >= 2) { + break; + } + } + if (i > 5 && m_activatedWECOrules[ONE_SIGMA_WECO]) { + // One sigma test + for (int idPrev = vpMath::modulo(id - 4, NB_DATA_SIGNAL); idPrev != id; idPrev = vpMath::modulo(idPrev + 1, NB_DATA_SIGNAL)) { + if (m_signal[idPrev] <= m_oneSigmaNegLim) { + ++nbAbove1SigmaLimit; + } + } + if (m_signal[id] <= m_oneSigmaNegLim) { + ++nbAbove1SigmaLimit; + } + if (nbAbove1SigmaLimit >= 4) { + break; + } + } + id = vpMath::modulo(id + 1, NB_DATA_SIGNAL); + ++i; + } + if (nbAboveMean == NB_DATA_SIGNAL) { + m_alarm = SAME_SIDE_WECO; + result = MEAN_DRIFT_DOWNWARD; + } + else if (nbAbove2SigmaLimit >= 2) { + m_alarm = TWO_SIGMA_WECO; + result = MEAN_DRIFT_DOWNWARD; + } + else if (nbAbove1SigmaLimit >= 4) { + m_alarm = ONE_SIGMA_WECO; + result = MEAN_DRIFT_DOWNWARD; + } + return result; +} + +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestShewhart::detectUpwardMeanDrift() +{ + if (m_nbDataInBuffer < NB_DATA_SIGNAL) { + return vpStatisticalTestAbstract::MEAN_DRIFT_NONE; + } + if ((m_signal[m_idCurrentData] >= m_limitUp) && m_activatedWECOrules[THREE_SIGMA_WECO]) { + m_alarm = vpWecoRulesAlarm::THREE_SIGMA_WECO; + return vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD; + } + if (!m_activateWECOrules) { + return vpStatisticalTestAbstract::MEAN_DRIFT_NONE; + } + vpStatisticalTestAbstract::vpMeanDriftType result = vpStatisticalTestAbstract::MEAN_DRIFT_NONE; + int id = vpMath::modulo(m_idCurrentData - (NB_DATA_SIGNAL - 1), NB_DATA_SIGNAL); + int i = 0; + unsigned int nbAboveMean = 0; + unsigned int nbAbove2SigmaLimit = 0; + unsigned int nbAbove1SigmaLimit = 0; + while (i < NB_DATA_SIGNAL) { + // Reinit for next iteration + nbAbove2SigmaLimit = 0; + nbAbove1SigmaLimit = 0; + if (m_signal[id] > m_mean && m_activatedWECOrules[SAME_SIDE_WECO]) { + // Single-side test + ++nbAboveMean; + } + if (i > 3 && m_activatedWECOrules[TWO_SIGMA_WECO]) { + // Two sigma test + for (int idPrev = vpMath::modulo(id - 2, NB_DATA_SIGNAL); idPrev != id; idPrev = vpMath::modulo(idPrev + 1, NB_DATA_SIGNAL)) { + if (m_signal[idPrev] >= m_twoSigmaPosLim) { + ++nbAbove2SigmaLimit; + } + } + if (m_signal[id] >= m_twoSigmaPosLim) { + ++nbAbove2SigmaLimit; + } + if (nbAbove2SigmaLimit >= 2) { + break; + } + } + if (i > 5 && m_activatedWECOrules[ONE_SIGMA_WECO]) { + // One sigma test + for (int idPrev = vpMath::modulo(id - 4, NB_DATA_SIGNAL); idPrev != id; idPrev = vpMath::modulo(idPrev + 1, NB_DATA_SIGNAL)) { + if (m_signal[idPrev] >= m_oneSigmaPosLim) { + ++nbAbove1SigmaLimit; + } + } + if (m_signal[id] >= m_oneSigmaPosLim) { + ++nbAbove1SigmaLimit; + } + if (nbAbove1SigmaLimit >= 4) { + break; + } + } + id = vpMath::modulo(id + 1, NB_DATA_SIGNAL); + ++i; + } + if (nbAboveMean == NB_DATA_SIGNAL) { + m_alarm = SAME_SIDE_WECO; + result = MEAN_DRIFT_UPWARD; + } + else if (nbAbove2SigmaLimit >= 2) { + m_alarm = TWO_SIGMA_WECO; + result = MEAN_DRIFT_UPWARD; + } + else if (nbAbove1SigmaLimit >= 4) { + m_alarm = ONE_SIGMA_WECO; + result = MEAN_DRIFT_UPWARD; + } + return result; +} + +bool vpStatisticalTestShewhart::updateStatistics(const float &signal) +{ + bool areStatsAvailable = vpStatisticalTestAbstract::updateStatistics(signal); + updateTestSignals(signal); // Store the signal in the circular buffer too. + if (areStatsAvailable) { + computeLimits(); + } + return areStatsAvailable; +} + +void vpStatisticalTestShewhart::updateTestSignals(const float &signal) +{ + m_idCurrentData = (m_idCurrentData + 1) % NB_DATA_SIGNAL; + m_signal[m_idCurrentData] = signal; + if (m_nbDataInBuffer < NB_DATA_SIGNAL) { + ++m_nbDataInBuffer; + } +} + +vpStatisticalTestShewhart::vpStatisticalTestShewhart(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1], const unsigned int &nbSamplesForStats) + : vpStatisticalTestSigma(3, nbSamplesForStats) + , m_nbDataInBuffer(0) + , m_activateWECOrules(activateWECOrules) + , m_idCurrentData(0) + , m_alarm(NONE_WECO) + , m_oneSigmaNegLim(0.f) + , m_oneSigmaPosLim(0.f) + , m_twoSigmaNegLim(0.f) + , m_twoSigmaPosLim(0.f) +{ + init(activateWECOrules, activatedRules, nbSamplesForStats); +} + +vpStatisticalTestShewhart::vpStatisticalTestShewhart(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1], const float &mean, const float &stdev) + : vpStatisticalTestSigma(3) + , m_nbDataInBuffer(0) + , m_activateWECOrules(activateWECOrules) + , m_idCurrentData(0) + , m_alarm(NONE_WECO) + , m_oneSigmaNegLim(0.f) + , m_oneSigmaPosLim(0.f) + , m_twoSigmaNegLim(0.f) + , m_twoSigmaPosLim(0.f) +{ + init(activateWECOrules, activatedRules, mean, stdev); +} + +std::vector vpStatisticalTestShewhart::getSignals() const +{ + std::vector signals; + for (int i = 0; i < NB_DATA_SIGNAL; ++i) { + int id = vpMath::modulo(m_idCurrentData - (NB_DATA_SIGNAL - i - 1), NB_DATA_SIGNAL); + signals.push_back(m_signal[id]); + } + return signals; +} + +void vpStatisticalTestShewhart::init(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1], const unsigned int &nbSamplesForStats) +{ + vpStatisticalTestSigma::init(3.f, nbSamplesForStats); + m_nbDataInBuffer = 0; + memset(m_signal, 0, NB_DATA_SIGNAL * sizeof(float)); + m_activateWECOrules = activateWECOrules; + std::memcpy(m_activatedWECOrules, activatedRules, (COUNT_WECO - 1) * sizeof(bool)); + m_idCurrentData = 0; + m_alarm = NONE_WECO; + m_oneSigmaNegLim = 0.f; + m_oneSigmaPosLim = 0.f; + m_twoSigmaNegLim = 0.f; + m_twoSigmaPosLim = 0.f; +} + +void vpStatisticalTestShewhart::init(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1], const float &mean, const float &stdev) +{ + vpStatisticalTestShewhart::init(activateWECOrules, activatedRules, 30); + m_mean = mean; + m_stdev = stdev; + computeLimits(); + m_areStatisticsComputed = true; +} diff --git a/modules/core/src/math/misc/vpStatisticalTestSigma.cpp b/modules/core/src/math/misc/vpStatisticalTestSigma.cpp index 65dd6a1d2b..5a64cacbbc 100644 --- a/modules/core/src/math/misc/vpStatisticalTestSigma.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestSigma.cpp @@ -30,6 +30,14 @@ * *****************************************************************************/ +/** +* +* \file vpStatisticalTestSigma.cpp +* +* \brief Definition of the vpStatisticalTestSigma class that implements sigma +* mean drift test. +*/ + #include void vpStatisticalTestSigma::computeLimits() @@ -39,23 +47,23 @@ void vpStatisticalTestSigma::computeLimits() m_limitUp = m_mean + delta; } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestSigma::detectDownwardMeanShift() +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestSigma::detectDownwardMeanDrift() { if (m_s <= m_limitDown) { return vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD; } else { - return vpStatisticalTestAbstract::NO_MEAN_DRIFT; + return vpStatisticalTestAbstract::MEAN_DRIFT_NONE; } } -vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestSigma::detectUpwardMeanShift() +vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestSigma::detectUpwardMeanDrift() { if (m_s >= m_limitUp) { return vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD; } else { - return vpStatisticalTestAbstract::NO_MEAN_DRIFT; + return vpStatisticalTestAbstract::MEAN_DRIFT_NONE; } } diff --git a/tutorial/mean-drift/tutorial-meandrift.cpp b/tutorial/mean-drift/tutorial-meandrift.cpp index 37f4aeb659..3e2b6701ba 100644 --- a/tutorial/mean-drift/tutorial-meandrift.cpp +++ b/tutorial/mean-drift/tutorial-meandrift.cpp @@ -37,22 +37,24 @@ #include #include #include +#include #include #include namespace TutorialMeanDrift { /** - * \brief Structure that permits to choose which process test to use. + * \brief Enumeration that permits to choose which process test to use. * */ typedef enum TypeTest { - HINLKEY_TYPE_TEST = 0, /*!< Use Hinkley to perform the tests.*/ + HINLKEY_TYPE_TEST = 0, /*!< Use Hinkley's test.*/ EWMA_TYPE_TEST = 1, /*!< Use Exponentially Weighted Moving Average to perform the tests.*/ MEAN_ADJUSTED_CUSUM_TYPE_TEST = 2, /*!< Use mean adjusted Cumulative Sum to perform the tests.*/ - SIGMA_TYPE_TEST = 3, /*!< Simple test based on the comparisong with the standard deviation.*/ - COUNT_TYPE_TEST = 4, /*!< Number of different aavailable methods.*/ + SHEWHART_TYPE_TEST = 3, /*!< Shewhart's test.*/ + SIGMA_TYPE_TEST = 4, /*!< Simple test based on the comparisong with the standard deviation.*/ + COUNT_TYPE_TEST = 5, /*!< Number of different aavailable methods.*/ UNKOWN_TYPE_TEST = COUNT_TYPE_TEST /*!< Unknown method.*/ }TypeTest; @@ -75,6 +77,9 @@ std::string typeTestToString(const TypeTest &type) case MEAN_ADJUSTED_CUSUM_TYPE_TEST: result = "cusum"; break; + case SHEWHART_TYPE_TEST: + result = "shewhart"; + break; case SIGMA_TYPE_TEST: result = "sigma"; break; @@ -131,28 +136,204 @@ std::string getAvailableTypeTest(const std::string &prefix = "<", const std::str return msg; } +/** + * \brief Cast a number type into a string. + * + * \tparam T Type of number. + * \param[in] number The number to cast. + * \return std::string The corresponding string. + */ +template +std::string numberToString(const T &number) +{ + std::stringstream ss; + ss << number; + return ss.str(); +} + +/** + * \brief Cast a boolean into a string. + * + * \param[in] boolean The boolean to cast. + * \return std::string The corresponding string. + */ +std::string boolToString(const bool &boolean) +{ + if (boolean) { + return "true"; + } + else { + return "false"; + } +} + +/** + * \brief Write the WECO's rules used in the Shewhart's test in human readable format. + * + * \param[in] rules The array indicating which WECO's rules are used. + * \param[in] prefix The first character(s) delimiting the array in the string. + * \param[in] suffix The last character(s) delimiting the array in the string. + * \param[in] sep The separator character(s). + * \return std::string The corresponding string. + */ +std::string wecoRulesToString(const bool rules[vpStatisticalTestShewhart::COUNT_WECO - 1], const std::string &prefix = "[", const std::string &suffix = "]", const std::string &sep = " , ") +{ + std::string rulesAsString = prefix; + for (unsigned int i = 0; i < vpStatisticalTestShewhart::COUNT_WECO - 2; ++i) { + if (rules[i]) { + rulesAsString += "ON"; + } + else { + rulesAsString += "OFF"; + } + rulesAsString += sep; + } + if (rules[vpStatisticalTestShewhart::COUNT_WECO - 2]) { + rulesAsString += "ON"; + } + else { + rulesAsString += "OFF"; + } + rulesAsString += suffix; + return rulesAsString; +} + +/** + * \brief Array that sets all the types of mean drift to deactivated. + */ +const bool CONST_ALL_ALARM_OFF[vpStatisticalTestAbstract::MEAN_DRIFT_COUNT] = { false, false, false, false }; + +/** + * \brief Array that sets all the types of mean drift to activated. + */ +const bool CONST_ALL_ALARM_ON[vpStatisticalTestAbstract::MEAN_DRIFT_COUNT] = { true, true, true, true }; + +/** + * \brief Cast a vector of string into an array of boolean activating / deactivating + * the mean drift alarms. + * + * \param[in] names The names of the alarms to set. + * \param[out] array The corresponding array of boolean. + */ +void vectorOfStringToMeanDriftTypeArray(const std::vector &names, bool array[vpStatisticalTestAbstract::MEAN_DRIFT_COUNT]) +{ + std::memcpy(array, CONST_ALL_ALARM_OFF, vpStatisticalTestAbstract::MEAN_DRIFT_COUNT * sizeof(bool)); + size_t nbNames = names.size(); + for (size_t i = 0; i < nbNames; ++i) { + vpStatisticalTestAbstract::vpMeanDriftType alarmToActivate = vpStatisticalTestAbstract::vpMeanDriftTypeFromString(names[i]); + std::cout << "alarm[" << names[i] << "] (i.e. " << static_cast(alarmToActivate) << ") set to true" << std::endl; + array[static_cast(alarmToActivate)] = true; + if (alarmToActivate == vpStatisticalTestAbstract::MEAN_DRIFT_BOTH) { + array[vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD] = true; + array[vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD] = true; + } + } + if (array[vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD] || array[vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD]) { + array[vpStatisticalTestAbstract::MEAN_DRIFT_BOTH] = true; + } +} + +/** + * \brief Cast an array of boolean (de)activating the mean drift alarms into + * the corresponding vector of strings. + * + * \param[in] array The array of boolean indicating which alarm are set. + * \return std::vector The corresponding vector of names of alarms. + */ +std::vector meanDriftArrayToVectorOfString(const bool array[vpStatisticalTestAbstract::MEAN_DRIFT_COUNT]) +{ + std::vector listActivatedAlarms; + unsigned int nbTypeTests = static_cast(vpStatisticalTestAbstract::MEAN_DRIFT_COUNT); + for (unsigned int id = 0; id < nbTypeTests; ++id) { + if (array[id]) { + vpStatisticalTestAbstract::vpMeanDriftType test = static_cast(id); + std::string testName = vpStatisticalTestAbstract::vpMeanDriftTypeToString(test); + listActivatedAlarms.push_back(testName); + } + } + return listActivatedAlarms; +} + +/** + * \brief Cast an array of boolean (de)activating the mean drift alarms into + * a single string listing all the alarms. + * + * \param[in] array The array of boolean indicating which alarm are set. + * \return std::string The corresponding string listing the names of alarms. + */ +std::string meanDriftArrayToString(const bool array[vpStatisticalTestAbstract::MEAN_DRIFT_COUNT], + const std::string &prefix = "[", const std::string &sep = " , ", + const std::string &suffix = "]") +{ + std::vector listActivatedAlarms = meanDriftArrayToVectorOfString(array); + std::string result = prefix; + size_t nbTestActivated = listActivatedAlarms.size(); + if (nbTestActivated == 0) { + return prefix + " " + suffix; + } + for (size_t i = 0; i < nbTestActivated - 1; ++i) { + result += listActivatedAlarms[i] + sep; + } + result += listActivatedAlarms[nbTestActivated - 1] + suffix; + return result; +} + +/** + * \brief Indicate how many alarms are set. + * + * \param[in] array The array of boolean indicating which alarms are set. + * \return unsigned int The number of alarms that are set. + */ +unsigned int meanDriftArrayToNbActivated(const bool array[vpStatisticalTestAbstract::MEAN_DRIFT_COUNT]) +{ + unsigned int nbActivated = 0; + unsigned int nbTypeAlarms = static_cast(vpStatisticalTestAbstract::MEAN_DRIFT_COUNT); + for (unsigned int id = 0; id < nbTypeAlarms; ++id) { + if (array[id]) { + ++nbActivated; + } + } + return nbActivated; +} + /** * \brief Structure that contains the parameters of the different algorithms. */ typedef struct ParametersForAlgo { - unsigned int m_global_nbsamples; /*!< Number of samples to compute the mean and stdev, common to all the algorithms.*/ + unsigned int m_test_nbsamples; /*!< Number of samples to compute the mean and stdev, common to all the algorithms.*/ + bool m_test_activatedalarms[vpStatisticalTestAbstract::MEAN_DRIFT_COUNT]; /*!< Flag is true for a type of alarm that must be considered, false otherwise.*/ + unsigned int m_test_nbactivatedalarms; /*!< Number of activated alarms.*/ float m_cusum_h; /*!< Alarm factor for the mean adjusted CUSUM test.*/ float m_cusum_k; /*!< Detection factor for the mean adjusted CUSUM test.*/ float m_ewma_alpha; /*!< Forgetting factor for the EWMA test.*/ float m_hinkley_alpha; /*!< Alarm threshold for the Hinkley's test. */ float m_hinkley_delta; /*!< Detection threshold for the Hinkley's test. */ + bool m_hinkley_computealphadelta; /*!< If true, compute alpha and delta of the Hinkley's using the stdev of the signal.*/ + float m_hinkley_h; /*!< Alarm factor permitting to compute alpha from the standard deviation of the signal.*/ + float m_hinkley_k; /*!< Detection factor permitting to compute delta from the standard deviation of the signal.*/ + bool m_shewhart_useWECO; /*!< If true, use the WECO rules for additionnal subtests for Shewhart's test.*/ + bool m_shewhart_rules[vpStatisticalTestShewhart::COUNT_WECO - 1]; /*!< Rules for the Shewart's test. True activate a WECO rule, false deactivate it.*/ float m_sigma_h; /*!< Alarm factor for the sigma test.*/ ParametersForAlgo() - : m_global_nbsamples(30) + : m_test_nbsamples(30) , m_cusum_h(4.76f) , m_cusum_k(1.f) , m_ewma_alpha(0.1f) , m_hinkley_alpha(4.76f) , m_hinkley_delta(1.f) + , m_hinkley_computealphadelta(false) + , m_hinkley_h(4.76f) + , m_hinkley_k(1.f) + , m_shewhart_useWECO(false) , m_sigma_h(3.f) - { } + { + std::memcpy(m_shewhart_rules, vpStatisticalTestShewhart::CONST_ALL_WECO_ACTIVATED, (vpStatisticalTestShewhart::COUNT_WECO - 1) * sizeof(bool)); + memcpy(m_test_activatedalarms, CONST_ALL_ALARM_ON, vpStatisticalTestAbstract::MEAN_DRIFT_COUNT * sizeof(bool)); + m_test_activatedalarms[vpStatisticalTestAbstract::MEAN_DRIFT_NONE] = false; + m_test_nbactivatedalarms = meanDriftArrayToNbActivated(m_test_activatedalarms); + } }ParametersForAlgo; } @@ -174,43 +355,52 @@ int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanD p_test = new vpStatisticalTestEWMA(parameters.m_ewma_alpha); break; case TutorialMeanDrift::HINLKEY_TYPE_TEST: - p_test = new vpStatisticalTestHinkley(parameters.m_hinkley_alpha, parameters.m_hinkley_delta, parameters.m_global_nbsamples); + p_test = new vpStatisticalTestHinkley(parameters.m_hinkley_alpha, parameters.m_hinkley_delta, parameters.m_test_nbsamples); break; case TutorialMeanDrift::MEAN_ADJUSTED_CUSUM_TYPE_TEST: - p_test = new vpStatisticalTestMeanAdjustedCUSUM(parameters.m_cusum_h, parameters.m_cusum_k, parameters.m_global_nbsamples); + p_test = new vpStatisticalTestMeanAdjustedCUSUM(parameters.m_cusum_h, parameters.m_cusum_k, parameters.m_test_nbsamples); + break; + case TutorialMeanDrift::SHEWHART_TYPE_TEST: + p_test = new vpStatisticalTestShewhart(parameters.m_shewhart_useWECO, parameters.m_shewhart_rules, parameters.m_test_nbsamples); break; case TutorialMeanDrift::SIGMA_TYPE_TEST: - p_test = new vpStatisticalTestSigma(parameters.m_sigma_h, parameters.m_global_nbsamples); + p_test = new vpStatisticalTestSigma(parameters.m_sigma_h, parameters.m_test_nbsamples); break; default: throw(vpException(vpException::badValue, TutorialMeanDrift::typeTestToString(type) + " is not handled.")); break; } + if ((type == TutorialMeanDrift::HINLKEY_TYPE_TEST) && parameters.m_hinkley_computealphadelta) { + delete p_test; + p_test = new vpStatisticalTestHinkley(parameters.m_hinkley_h, parameters.m_hinkley_k, true, parameters.m_test_nbsamples); + } + float signal; std::cout << "Actual mean of the input signal: " << mean << std::endl; std::cout << "Actual stdev of the input signal: " << stdev << std::endl; std::cout << "Mean drift of the input signal: " << mean_drift << std::endl; // Initial computation of the mean and stdev of the input signal - for (unsigned int i = 0; i < parameters.m_global_nbsamples; ++i) { + for (unsigned int i = 0; i < parameters.m_test_nbsamples; ++i) { vpGaussRand rndGen(stdev, mean, static_cast(idFrame) * dt); signal = rndGen(); - p_test->testDownUpwardMeanShift(signal); + p_test->testDownUpwardMeanDrift(signal); ++idFrame; } + std::cout << "Estimated mean of the input signal: " << p_test->getMean() << std::endl; std::cout << "Estimated stdev of the input signal: " << p_test->getStdev() << std::endl; float mean_eff = mean; bool hasToRun = true; - vpStatisticalTestAbstract::vpMeanDriftType drift_type = vpStatisticalTestAbstract::NO_MEAN_DRIFT; + vpStatisticalTestAbstract::vpMeanDriftType drift_type = vpStatisticalTestAbstract::MEAN_DRIFT_NONE; while (hasToRun) { - vpGaussRand rndGen(stdev, mean_eff, static_cast(idFrame) * dt); + vpGaussRand rndGen(stdev, mean_eff, vpTime::measureTimeMs() * 1e3 + static_cast(idFrame) * dt); signal = rndGen(); - plotter.plot(0, 0, idFrame - parameters.m_global_nbsamples, signal); - drift_type = p_test->testDownUpwardMeanShift(signal); - if (drift_type != vpStatisticalTestAbstract::NO_MEAN_DRIFT) { + plotter.plot(0, 0, idFrame - parameters.m_test_nbsamples, signal); + drift_type = p_test->testDownUpwardMeanDrift(signal); + if ((drift_type != vpStatisticalTestAbstract::MEAN_DRIFT_NONE) && (parameters.m_test_activatedalarms[drift_type])) { hasToRun = false; } else { @@ -218,7 +408,7 @@ int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanD ++idFrame; } } - std::cout << "Test failed at frame: " << idFrame - parameters.m_global_nbsamples << std::endl; + std::cout << "Test failed at frame: " << idFrame - parameters.m_test_nbsamples << std::endl; std::cout << "Type of mean drift: " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift_type) << std::endl; std::cout << "Last signal value: " << signal << std::endl; if (type == TutorialMeanDrift::EWMA_TYPE_TEST) { @@ -230,6 +420,26 @@ int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanD std::cout << "\tLower cusum = " << p_testCusum->getTestSignalMinus() << std::endl; std::cout << "\tUpper cusum = " << p_testCusum->getTestSignalPlus() << std::endl; } + else if (type==TutorialMeanDrift::SHEWHART_TYPE_TEST) { + vpStatisticalTestShewhart *p_testShewhart = dynamic_cast(p_test); + std::vector signal = p_testShewhart->getSignals(); + size_t nbSignal = signal.size(); + std::cout << "Signal history = [ "; + for (size_t i = 0; i < nbSignal; ++i) { + std::cout << signal[i] << " "; + } + std::cout << "]" << std::endl; + std::cout << "\tWECO alarm type = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(p_testShewhart->getAlarm()) << std::endl; + } + else if (type == TutorialMeanDrift::HINLKEY_TYPE_TEST) { + vpStatisticalTestHinkley *p_hinkley = dynamic_cast(p_test); + float Mk = p_hinkley->getMk(); + float Nk = p_hinkley->getNk(); + float Sk = p_hinkley->getSk(); + float Tk = p_hinkley->getTk(); + std::cout << "S+(t) = " << Tk - Nk < alarmNames; + bool hasNotFoundNextParams = true; + for (int j = 1; ((i + j) < argc) && hasNotFoundNextParams; ++j) { + std::string candidate(argv[i+j]); + if (candidate.find("--") != std::string::npos) { + // This is the next command line parameter + hasNotFoundNextParams = false; + } + else { + // This is a name + alarmNames.push_back(candidate); + ++nbArguments; + } + } + TutorialMeanDrift::vectorOfStringToMeanDriftTypeArray(alarmNames, parameters.m_test_activatedalarms); + parameters.m_test_nbactivatedalarms = TutorialMeanDrift::meanDriftArrayToNbActivated(parameters.m_test_activatedalarms); + i += nbArguments; + } else if ((std::string(argv[i]) == "--cusum-h") && ((i + 1) < argc)) { parameters.m_cusum_h = std::atof(argv[i + 1]); ++i; @@ -289,6 +519,32 @@ int main(int argc, char *argv[]) parameters.m_hinkley_delta = std::atof(argv[i + 1]); ++i; } + else if (std::string(argv[i]) == "--hinkley-compute") { + parameters.m_hinkley_computealphadelta = true; + } + else if ((std::string(argv[i]) == "--hinkley-h") && ((i + 1) < argc)) { + parameters.m_hinkley_h = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--hinkley-k") && ((i + 1) < argc)) { + parameters.m_hinkley_k = std::atof(argv[i + 1]); + ++i; + } + else if ((std::string(argv[i]) == "--shewhart-rules") && (i + vpStatisticalTestShewhart::COUNT_WECO - 1 < argc)) { + for (int j = 0; j < vpStatisticalTestShewhart::COUNT_WECO - 1; ++j) { + std::string argument = std::string(argv[i + 1 + j]); + if ((argument.find("on") != std::string::npos) || (argument.find("ON") != std::string::npos)) { + parameters.m_shewhart_rules[j] = true; + } + else { + parameters.m_shewhart_rules[j] = false; + } + } + i += vpStatisticalTestShewhart::COUNT_WECO - 1; + } + else if (std::string(argv[i]) == "--shewhart-weco") { + parameters.m_shewhart_useWECO = true; + } else if ((std::string(argv[i]) == "--sigma-h") && ((i + 1) < argc)) { parameters.m_sigma_h = std::atof(argv[i + 1]); ++i; @@ -298,6 +554,7 @@ int main(int argc, char *argv[]) << argv[0] << " [--test ]" << " [--nb-samples ]" + << " [--alarms ]" << " [--mean ]" << " [--mean-drift ]" << " [--stdev ]" @@ -306,6 +563,11 @@ int main(int argc, char *argv[]) << " [--ewma-alpha ]" << " [--hinkley-alpha <]0; inf[>]" << " [--hinkley-delta <]0; inf[>]" + << " [--hinkley-compute]" + << " [--hinkley-h <]0; inf[>]" + << " [--hinkley-k <]0; inf[>]" + << " [--shewhart-rules <3-sigma:{on|off} 2-sigma:{on|off} 1-sigma:{on|off} same-side:{on|off}>" + << " [--shewhart-weco]" << " [--sigma-h ]" << " [--help,-h]" << std::endl; std::cout << "\nOPTIONS " << std::endl @@ -315,7 +577,12 @@ int main(int argc, char *argv[]) << std::endl << " --nb-samples " << std::endl << " Number of samples to compute the mean and standard deviation of the monitored signal." << std::endl - << " Default: " << parameters.m_global_nbsamples << std::endl + << " Default: " << parameters.m_test_nbsamples << std::endl + << std::endl + << " --alarms " << std::endl + << " Set the mean drift alarms to monitor." << std::endl + << " Default: " << TutorialMeanDrift::meanDriftArrayToString(parameters.m_test_activatedalarms) << std::endl + << " Available: " << vpStatisticalTestAbstract::getAvailableMeanDriftType() << std::endl << std::endl << " --mean " << std::endl << " Mean of the signal." << std::endl @@ -351,6 +618,27 @@ int main(int argc, char *argv[]) << " Detection threshold indicating minimal magnitude we want to detect for the Hinkley's test." << std::endl << " Default: " << parameters.m_hinkley_delta << std::endl << std::endl + << " --hinkley-compute" << std::endl + << " If set, the Hinkley's test will compute the alarm and detection thresholds" << std::endl + << " from the standard deviation of the input signal." << std::endl + << " Default: disabled" << std::endl + << std::endl + << " --hinkley-h " << std::endl + << " Alarm factor permitting to compute the alarm threshold for the Hinkley's test." << std::endl + << " Default: " << parameters.m_hinkley_h << std::endl + << std::endl + << " --hinkley-k " << std::endl + << " Detection factor permitting to compute the Detection threshold for the Hinkley's test." << std::endl + << " Default: " << parameters.m_hinkley_k << std::endl + << std::endl + << " --shewhart-rules <3-sigma:{on|off} 2-sigma:{on|off} 1-sigma:{on|off} same-side:{on|off}>" << std::endl + << " Choose the WECO additionnal tests for the Shewhart's test to use. To activate them, --shewart-weco must be used." << std::endl + << " Default: ON ON ON ON" << std::endl + << std::endl + << " --shewhart-weco" << std::endl + << " Activate the WECO additionnal tests for the Shewhart's test." << std::endl + << " Default: deactivated" << std::endl + << std::endl << " --sigma-h " << std::endl << " The alarm factor of the sigma test." << std::endl << " Default: " << parameters.m_sigma_h << std::endl @@ -367,5 +655,24 @@ int main(int argc, char *argv[]) ++i; } + if (parameters.m_test_nbactivatedalarms == 0) { + throw(vpException(vpException::badValue, "Error, at least one type of alarm must be monitored. See " + std::string(argv[0]) + " --help")); + return EXIT_FAILURE; + } + + std::cout << " Activated statistical test : " << TutorialMeanDrift::typeTestToString(opt_typeTest) << std::endl; + std::cout << " Activated alarms : " << TutorialMeanDrift::meanDriftArrayToString(parameters.m_test_activatedalarms) << std::endl; + std::cout << " Nb samples for statistics computation: " << parameters.m_test_nbsamples << std::endl; + std::cout << " Alarm factor CUSUM test : " << (opt_typeTest == TutorialMeanDrift::MEAN_ADJUSTED_CUSUM_TYPE_TEST ? TutorialMeanDrift::numberToString(parameters.m_cusum_h) : "N/A") << std::endl; + std::cout << " Detection factor CUSUM test : " << (opt_typeTest == TutorialMeanDrift::MEAN_ADJUSTED_CUSUM_TYPE_TEST ? TutorialMeanDrift::numberToString(parameters.m_cusum_k) : "N/A") << std::endl; + std::cout << " Forgetting factor EWMA test : " << (opt_typeTest == TutorialMeanDrift::EWMA_TYPE_TEST ? TutorialMeanDrift::numberToString(parameters.m_ewma_alpha) : "N/A") << std::endl; + std::cout << " Alarm threshold Hinkley's test : " << ((opt_typeTest == TutorialMeanDrift::HINLKEY_TYPE_TEST) && (!parameters.m_hinkley_computealphadelta) ? TutorialMeanDrift::numberToString(parameters.m_hinkley_alpha) : "N/A") << std::endl; + std::cout << " Detection threshold Hinkley's test : " << ((opt_typeTest == TutorialMeanDrift::HINLKEY_TYPE_TEST) && (!parameters.m_hinkley_computealphadelta) ? TutorialMeanDrift::numberToString(parameters.m_hinkley_delta) : "N/A") << std::endl; + std::cout << " Alarm factor Hinkley's test : " << ((opt_typeTest == TutorialMeanDrift::HINLKEY_TYPE_TEST) && parameters.m_hinkley_computealphadelta ? TutorialMeanDrift::numberToString(parameters.m_hinkley_h) : "N/A") << std::endl; + std::cout << " Detection factor Hinkley's test : " << ((opt_typeTest == TutorialMeanDrift::HINLKEY_TYPE_TEST) && parameters.m_hinkley_computealphadelta ? TutorialMeanDrift::numberToString(parameters.m_hinkley_k) : "N/A") << std::endl; + std::cout << " Shewhart's test set of WECO rules : " << (parameters.m_shewhart_useWECO && (opt_typeTest == TutorialMeanDrift::SHEWHART_TYPE_TEST) ? TutorialMeanDrift::wecoRulesToString(parameters.m_shewhart_rules) : "N/A") << std::endl; + std::cout << " Shewhart's test use WECO rules : " << (opt_typeTest == TutorialMeanDrift::SHEWHART_TYPE_TEST ? TutorialMeanDrift::boolToString(parameters.m_shewhart_useWECO && (opt_typeTest == TutorialMeanDrift::SHEWHART_TYPE_TEST)) : "N/A") << std::endl; + std::cout << " Alarm factor Sigma test : " << (opt_typeTest == TutorialMeanDrift::SIGMA_TYPE_TEST ? TutorialMeanDrift::numberToString(parameters.m_sigma_h) : "N/A") << std::endl; + return testOnSynthetic(opt_typeTest, parameters, opt_mean, opt_meandrift, opt_stdev); } From 727ee50925d32c1dbc90e5b31483eb3d41dce4b1 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Fri, 8 Mar 2024 09:50:34 +0100 Subject: [PATCH 076/164] [TUTO] Added a doxyfile explaining the code of the tutorial-meandrift.cpp --- .../tutorial/misc/img-tutorial-spc-run.png | Bin 0 -> 147847 bytes doc/tutorial/misc/tutorial-spc.dox | 89 ++++++++++++++++++ doc/tutorial/tutorial-users.dox | 1 + tutorial/mean-drift/tutorial-meandrift.cpp | 25 ++++- 4 files changed, 111 insertions(+), 4 deletions(-) create mode 100644 doc/image/tutorial/misc/img-tutorial-spc-run.png create mode 100644 doc/tutorial/misc/tutorial-spc.dox diff --git a/doc/image/tutorial/misc/img-tutorial-spc-run.png b/doc/image/tutorial/misc/img-tutorial-spc-run.png new file mode 100644 index 0000000000000000000000000000000000000000..153666a51a9c1cb959687893eeca3aaeca9dc3c1 GIT binary patch literal 147847 zcmZ^~19W9e^9PztG;t<2CbrF)WMbQx*tRDV+qP}nwr$%^-pS1U?)|Uz-s|A3uIj3; zU0wC-+Pn7&l$I2Ng~Ega0s?{+5f+dI0s{8{0{V3L85}@KHBrU@0zy}Jkyo~p)p5kP zvavKUHq*zqbGFjQ*LN~D00MGaDorws!fuQzeb+^)1|{=XhRazz*`W4p^AWE~F166A z?*B>|EEDaPh0v|f5h^`XTM8lSfA~?Wh{>s!V#_T=DSx3vvp{9&&$>psita=wRSC{{_TCI zfpzHH>&MI+MbGw`$JU9bw1>E>*LY8wR&mY?68{C z&ueVs`D5esDEDx^=e?f?Xv6QfXP?(04&w3O9|m9PpP1i5CTTmvw_OFF_^F0j1z#@W z+dtp=Zy)ZzZl7DGc$AU7Jq3U9c|Ejldp}z}UAuN}iiG|`y&mM!3CBy*9T**ve_z+7 zw3~iu>#mhrzUQx%(B^a&&;Vvh!{4+gi%Gc6D$4ru(2R9OHz0OqhUa+8&vd0$YT#oa`YQm&kHwG zv8dw;y0wu4E97N~S#OXBhZYOcldzbXs8m?0f6gXVTV&@%1;@&od>IH$GAUCOE3KW? z6cXdhsGTw~Ev=u_mD0|*oiep-y{FH@S~0RJ?R@khWE^9yKhM44$Bvpg(f)5YH|1M# zTU!$_kCmpX)#U9exz1hmw*G2ON3EWwvWSMOqP|1{w>V70`Eyrm(6nQpUB@WcC{*&2 zDzuS>+Bz&~W{iDB{gqS0g7ebR`k~7^k2((HFII}Nb|@(u?d=Qtun`VmXV!xdiJHXL z?o6KwH(y=uU8_BP57wSvo4;3I;NjX@<(>!~&GQtG-u9cU@>1WQD>Y-H$TTm)VD(5k zH*W+YC}Hmqtg4pB%$-^ek}fosj=B~cHiDkBYsf0RV>92|;#`jiNG*><{(>@mUh1ME zEWa9# zBpJoW>@yho<)LH$e9iGczO4nJOujhh$_FaxFot;fb-Y{^?phby_;tV@KE}-jVynBx z`X#|5+X_L+e3mc7UE*;LV-QYWc0Pouk+McTJsQtac32K~wri^cKbG=*jqn>Vl8K7# zMT>NA59jZ_>WF|xtP_r~m0o{q*_$vj(j%_tcaJ1{sl{j1YpO0+)@ zbMl73>gyq@l;Es8GPG~Bzr~<452gB#E?$~u_eg}U?5JV>9-2sd6_koOx#*Cd;z;d* z4LI`qydH|1r0NYdz!uva^8=yEV5xi^(iq;(=4Q7<6J{oVmxiN3Ca6N^IHFtv#0`t> zYnmm|Qn#nTu^4aL|Nc5@=^>#keKWTn+-H1hhz5ZCP^8DP5g3=IILq zXj-NDZ#dF4$gihyPHz`nP{E`|x#=mt`0pnM_lM+H!mNML^4)@l*S=~#T!8)&mUhEHzT2dXpi+zr6B$|Hr}^hE+clqaAn8h17b)a#ufy8#W zd>Mer9TbQqO-=<@SN0_;plpRjI;)OWh01ruaO1as4dhLxUjemAwMGpy6DEq!^?}D1 zm@1F27d6YE4V*7c@kY;nA{Hx^+Fe)?{; z9Xn!}{#u>^yY&7|K)jK8SFLNU->oVAG#q%qzmqe9^M z(2Ec9I)XnpP#cX8YmFWE(ht&-r`hX!xzm@=FciVfy;TE7r$4C0418^Al>$w?;9)`_ z#y828hkU#Ts7>I81dD8rSkmAkOfxd1tTICvbf`l*=`TG%=qKUGJ_Qhcb~AF>FmmQ- zK!rg4fk`QEEP>xZxowA|SU&;xQ!OL>jL`pvcR=n3wojg)zAafWhdS^fM0xGttGfyq zoX8Dx&u?NVFxaq7f?q)If;(BCJ0a*~oGNX7@Ieo&0~zUch!rv200jH z1&5m>x}!xt6`|hU5-_D8%+DVDd^ct^xBi2x~3Vev+;K%R0lZ38L_jV+oeqA+z7%hR;!oW>-qaZ_+X9S;+I{k{uK% zJb6XX8Wy@=tHBL<;4V@DiIT!z9Fw5xUD!y!f15{62=fgr(^hht?H`K#w9YrK+hEwm z)!9i?<&G~>&e%uB*b58STkU{HS^suN63cP1C!v&^elX{)_6tjr8A?y$UO0Fb^wju@6buMDTFnTZ#giyz^wlR7I%7UoSw=%BX3*&rmV@X0Q^K_P zff1AAdRPEZx)m8RgPwx|^9-E+iUSs%s*nZ&8qmqL9ybYWquBwB35Wz-M*JL(^%pn7 zb|e}jq$uPED9pA-=_(+X9; zW=_TE8&hMAtWM=v#5}ML?|loQF1s{28BE&y)CER$+=MOy^E}_-o=6i6usUNYouwaW zhOJ_aPDRT%vtx1Hz%2NpD|MoAKxV%o8DfjEMy!t+kyhS(YH#0E+qHFN`H3Gwl>1;b;4To6SQZV2O zqn(LwZa)O{3I{JU(_!UEet8V{=*9VZul*)g!HToNER_Md;i7IAQ6(68%?HVM1H?aV z1@W1ggJ)pGF;HFrk}H~0FC23+A#R265?D}JwcDx$J}a%OE8Gu*KzpU-p}YhC0tg%G z`RA$`l0^rTJgL4v86{WmoVqe6oseHjg6Pg(zvGR);AD1joOJkF1|~y{2dbb~QfZiB zCb_qn)39ZeTM8joEnT?p=ga^!A~Cg~=?IqvBp-j|G#@C->8V}*;Qp%C3yhM>&c)D1wSn5p85oNbuk zr8DAp>H>0shJG?!E6_Il?ue~CanOjd2dfg^y8d6S{P)uw@xbr|VAMseC;Mi#+7-Wg z;1qq@mF89a)&Oj=4d(oHCb^H4?797ijX*@7lQM-OGFuoBsk{@4a`EQxov2gBNEj!~ zo6iIS)&2G3)+ka>b>+Y{Qs!*A$0rKNenN3yaK5#6!Ph_utXd}n0g?Ui9P@k66Z09o z#_b@2s+s(0xEYK?Vmuurkj1Z!D_AH%Br#Rkn$VZx~kVsqeIz2=4BXv|3%z|w`G1z#TL{U|th zqhg(pYc-buCz&;4kR?q9;|~i$;e;%VuyPdygQ-~%`cn?6o6gW8D67Luz6x9aDa^&N zfbGINzjMVbOEYW!KtdqIb>vq%=(!kG=5Vj6p1MCup!Wg%jio@wqxbw z%FgF1f^ z&ALVDw09xxh@)dB@?tA4K{3aa`Mrx$@e-!jCji;_%^j!~ALZ*OQzInY-Lz(;ro@U} z(`;ZU9ZDg&jL~KZCG{kT&7D+GG^QU^o7%HLQxsw+GMB=I-|NeNNnl>-T*ZJo zx>xaWBX$SMFAgM0q{#tyElo|XFiiwkX(pfGd=9A-y-Y~}=4wcwLp{ZmFF0{{4kjuYYD+6o!n-*#3w8Y-#y>-P-F3Die= zpm`WAw5<%8bms_s@p4$Eiwjozji+D-IvT_H*~qV)TG&)7cWBXIO8lCG(3&MGk$qhZA? zbgO2p0sh5eL4k4wkq2+#q>R`G)G}od{A+pJ`;Osoo-0bVGh_Sn8c8RC^inCPN|GK2 z?r)nctP;}&$OyqDRI5n1Eqv3T3QXo+Jc=`JjstL{iH}H-{OStbs|PoDHLCJ#B+XBQzL(D4fm_qw$plN{K`F zYfV!U<8D`c{AiYdkKby|!6y|o`)mUN%uc-;3~;b@Z+$cYa{(lmW}Nw16>0ojIGZSS zNbDt0dhCKS!5)O37?-Ij!XB|b%AyA3nUUV_tFl)3aB0U&U3@ks7eEw5H|KoD=%y24 zKvkcy+=K2$lbpa{GfMHGmy~J09<7Y@R_l0wYo6jAprE~Nq|Z86H!(Nr@@b{jUR}O~ z8t_@@Yn-xcaBZOqS~ccdnB^DNi}J?B?CNk;W`+Sycl{m-WP1_Lkc4CyVY#Wf)Cu2$ zj^dPp;d`>4m%gW%Bt4u*`~ZXc>!pRqX@U-eDy)gcz0d!e3EsT|ipD!_FXH!$H&Z-* zIqP&EFk4W^e43DkylKz0IYq1)+$nYiP;8>NiqKD-_FWCnZg$lWiV2$VJ2rk{iqZ_< z4NX<@9KIltY%GbQ8aWQm@A`N_sRqHpnn(~?G_|xHg$Ek%iB>pg{H%0_({NC#E_D{?uVun18Ms zhf@4a-&6{CEpHFa`|Ax9^J^^A<|ZP#eU-1BNDmgTTZ=oYC24iM@yZ4dZ9>wjRiBW_knMCiixpB=aV)pkEDrh!VoXuL=~rF2F?ax-_F90Qto}l27a3b z3f<5=DBuzE3Za4Ipi>wBZVv~!a-?rnNf1vnijIDx9OWX-3YuZB>Xv~MV+^%do^ z(?(UF|8fZ_kJxxahZx$!!09 z;(4;n*^(FUZod4ieZhLc zy{7&9-u=(jxr)|2t;@oGzreM{)~y^P&5# z=ZOZ(V^e+IipbGkQSl{TgS7X1(ijrY8^Jtnq!@t`MhG@^!FQjNr_T2cN6XT#o!{}u zB0#IOVb}DZemi&@tXj8)L7O+1SOlSQ^y(z# zXVF)JnnHvE+jtFWBZs(I|HN&oxvsj;<_^R#Q#=D}W%W4(mE3i8e|2-L?Nx31XdRx( z$R}HxM*8>z21-gn2M{6bL?nJd9DscO zjQJUq;X45k5I&HIz&ClPrIS@>C$)L!^XK)ogl|@9sm z>oHPl22UfFQ|j{TyV>vW8ut&`-OmoW4^OA3^F}9FB$7ys{aC`Ld!mt@BZyV!xKw7S zqPDm|i1-AVqt*+ z%>2{5dpyopU%MX?a=xC@TtS_rWFD*fH>k>sVvUV&yR_YF3pA=#~pQI z-IwpII{^P7p?!Jz=r%My9>095C@C5C;?XWXO+*J^B-~RCPjz&7Jv}`!F)`(woms%b z!3~j%fCs;P$N`}yuB@noeFCOdsS=npk_Y@|N+0y4MgdqIZU*RnFx}GMzIlsJ$LOF# zf%`B#azKAbDVw?RtcT`|Z){}v`T6Oopo)B42o-vr`EV5#EG#TJVxZAr6fqR&CmYO> ztB=D#AY}o7Di4pgp`jrrIyyc+0I6bQv98qH8#p#DZfI~+{9}|?Zx7(QcWsP~i~_U) zef(?~c=+KMBEi=WE}*n+U#BgfAFi zpJtoCV0@UE0=&8nU93%X$XLW^a@3Kb#CvpIOc=MaV=l?hV*KA4vR~PaW$>h8#VjYV z@yi|5+{oW~;X=b4skH*PPV9?0txJ;g>_PlbH_+iN*5m7w_MP_kQQ6rf0W1n1~s-T&^>pTfa_BiCEE{U!xa~eZ4=Ye0XZ7co=fDSY)|a zAVqe%$ToRw=b>4QBO26Qa3L|2)=D-QVnyWrSJz}BRU@N@EE!53!RmJK%2S3pIY33x zL9kZTrcLqt`n!xQ*P+}^FKyv9<@>JSl;KQkTSeO%PJ#^yYkrUXf4)7GJqjqCFm64+ zoQ&l8q4g3)G>D7a6nTRo0UD}sP$Rz;QpkLiaMPL+rH253jla#SX24N7nunF=ar#o} zz5hAS1FLvKMK{VYpBMxVawRUjIN9D-}nc} zc(Gd_Ok|R$uh*HY3F116&18-hJhs_;^pUvtk+=xvyJMxl9EPyZu=FxnA_o4em`-R< z?x$fB(TrIYF%J68QQ?VqGCXEp74FNx^V|)_tK&vzc+tDzdelksU{*Z@S5>|vEJaRMey-SlS)M3o zMJr3qz9gmwqv@ak&N{D?;%;x+T zayz;V7}oxacE*H|`#(ASp??5|gy7@zPaA+C`VU+gen&zn`|Fu^6A>}d$Uas{YLgEPBn&)+W>J}nG_Hz~51tKCNH+VN4 z>dmF0DEB8PUfUgHQp69vfF<;+Hh+%eWn7eEAQ9ytzEW=rAu%^wmOOa16vEiwY880^ zN*pvsPg(gp9LOSkIn^!Ud=Ng05h!Z6#+?6Ov%G#7zr^V4zVkZN4B9~k4Bjy|g$L%L zB%2jg2Cg~2ydjDN5XrqA-qCBQkaCnI#@W_wF=AN*RamjX`b6XWRj&+VKo}WaGO5=i zP@Za3RC|ahgY?RocqJ7-Ad>fj6id3;AW{2j)@#Ue^rfR~v&P<-Ri~qY> zjAxO+m{}}o;@jM1w%t_a9pYp`7Z$r>0g z^vua<%rQ&i#YPcB5NxghK2M>7uSpsEr z16v{_uaO;by*1%~XdN$nRS+HWBM-j6`2HaQ_Dnkiw;K4we^JHDcPu3QPN(Q!Far>n z^n!{1##O?5U-{&4QY%0leLSW|{4bbNA=EQ2GETZiyL|#|_*&v>;EaEx%*%L@#W4&( z9C7?7Q?xfL%w4AGvBk_$Ci7wsAu^i6+B?}sO_C#v_BV7pG0O&zh>8--`{3X=jkfNa%5O{$DO=e zZJwM17}~OHmI`e^QeQ{N) zYE`p)Cm-PYw0+p%?3`r#7f$5&;^ntK^@qE5Jt>@BGQgR%A zcTU?!yT0D8-+W*=e{5=M!dj-DyW__6Nj&p>VSz4mm%Lw7$8+|e=jNSkbRTvcq}H#k zqb^)s6xsUYtcXiliIbOex}d@upP^!VU`{T(qxd9EM; zOM$dKbTqI5pE+GIX1(tp6dCR3xIMB?IQ;8Wh4i+TmHH^iQ^mNqHQ#>k*vtVNZ&_5Rx~93 zDR=;@F%ppha7>4r4kBQ=|2D4??InhQzug3-qobog_Wo=9Hz;~K;z9iTKbC(;RBR+7 z+J5=lr9xim0Kk17BHktc#})l;s9d_XDy7tmCXNn;m6eeJf2a(q`ue$;n3#L_;r89y z4sha=JVZ$V=Ou*v-&$uxTeJ>_{z!ObwUcOw1&XYp7`;UX-5Rib&C z@+Tm#8pdtUOY?vIrk%-%VG8?U6W`v3A;3o+TLxF9|K6?OGba50V=&MNtG&Jbhp9d= zq2H?RGp6DGh68>hdP3A_kk_A4+N$E{0Q>3Q6Tj~N8y68@l(+vuXh1;nqbCoWm=8)f zSM!I4h6?=I0REIZvlA0^?VcrAekaKJ`m7;0qX#_E?)lZ~!LXH}=IB6lC~^$w7yl^* z7LWQrE81Cup#=HYP(bDMWsA^5`0Y>E%Q@%&D;x~D_PgCa669}#PBo6W`PU}{pCt!L zZvW3zAs<;yRLjmeyRaZE@J9rrw5m!La6@zb+~1@#AZg95*)6;-+s3%)$T3{IfFL&E z2Mi=fzdf(q_wvsid=xNEO28w8d3ph$oPTMklpLpl7(jZ6jBjX#c>jz80swo=mMz5J z`A5+HaXZNW0HX)r_rv2qP5v3bhkTy}!sn83c})55ZedNN52U?mv&0Zn*Awno9LIfE z^9hc8?twd%*G^SYG@a>jX!Qj$RuPoR?G%hT#Z5}aMxiI3V{F4RzIvG?^cQLEmAC6I z?sM)eT+#C>ZDAv|pav1raEB^NnKGfJq_^Lgrh^| zN@3}0Z~>N65*m5awO)70;yAQDx@tz|HmKwEz8<@S&2m4A&t)Y=a@8eu$Bq^Tnzh8v zp9`QU;|8~{2kjbmZ%~GmWQ$MS&R53ZS6G zc1}EhpsjOc=(ysZvnFzAPV}?Xn@_>vDhzYZ>tXthY-v!GQ%GDDu?FvB$rk9g+sv)d zri(@4C^i&Ia;Fj`u6=U88bUrjN|AZKHS^H)d@*Z0YI`GYbz*l&2HBo#GJNM7w>+Cq zYk#6_ooi8+4WXfSKTx_k)F3|Me&BxX7DHoVi#`rh$@BL-4tA;Ovfd^rwhw=MqSczU z51y7{ke9x0;JLC&3$s6&A7n8NI~tA1cdN#AKG7^Kr;@LmpOCIl!WmVvvpa7uF0&3O z0z^FYK2|Kj+z2?(h}u|9>E*V1CSRnGA5n3$X669Q8ljuOJiPEDF)%E1dv+TEk4m6r z)_RYd&3^3gDZSo3t=B7wTtD>V!d{aETrHVX>yIdc{AZd)QHD##{XK(u4@4~(` z9`End&}asfBC%zFNq&D(AsHRgG=2`KDwj3)8F>57&~XR0TUoHPQ53Zvtt! zYF^Gt=vbZh{8FvDe>fc*Eo7JFDlDlLb`^Xbqu*y?9PPWDHcg60F`bL|M*Dgr8=?%z zGHnA59HJv2Du%HKX3IOF7j!UFWGk#FDqpp+ajPD$T%-PGlk<$O09yMNwvlp{#)jjc zJTsL-VUx?q;7x|)Z+-R_!d*!_m`BcJuk~!F7G$v-UdSZLg#CO!q$KFpu*y zCZXf9({0g52^+86&cqZ$4#z`Oo@V)`?SZWREI6x<(!*!uGUuE8CP~J;?Ko4r{OuF^ zA~q%RW2;0S7M`sbLn`eGvu_EQ9&h&Uuc2Y&`6D+wsKso_ChslJ)xiuyX#d=D=#V?rkTZm+?y%0^R!yL0rqFOJv%81dGkhFV(&+$O zhppJ}>d%A_=qN?px~@{btv5`!M1xaBcz(1bMoXqABDhA_q&x3(g&x;s_^uegZW<}e z#?ly1W;sf;t3(ywe;mVXrIG1ZKkKns;+Lg+v~V#f*P^(nKRZNG6hlgh@83v`e! z0rb%k2BUjqwE%muW1;q;sI$ApBL6B>J&xS|Vm%6WK%SLZ-UztCezMpZF?^w&MCl7~JJU?=MTY5?8rYO{KT@sz$NF4HhKD&Hsx?*Z z>-%0unYJ5Dwm$8Y^W<`#9CI`orXMYT4`O#4qE;!|9kaMy3!}~V(=s(J-VJ3w=qVig zQ5P1ITZTk?ghl%BGp_O0fQ%9$qOd|Wskt}A6=>>^)gkuS^f{?yTU;REpIl+4!!jWsZ&B~&L-eI`fp&f~D612Q`7*LZX z_6GncIM^~ckyh0C@oGU3M4Cd_IQBICVKk*{VM-d!ZHk-HrW5dP;X>I8!#Fig!dQpw zt~{+mMvlPznu`L6hfgUW=!a_YuUHLkQpSz%i=O&BHyu%DHqq(rmB_6{QLM62t;_C~YPww4Iw#9F zHELwKKOSrps-+R^N5Pvu)~PlMI-XF<%<0XC+Ra+4CQuYDW}&1d(7Zk1-TE}W z(Wm?P-^>9H6~8E#FDY2`mf_A9T0F;%hu@CBR`Rqy8sMzIHuBD{vZmF~G~EwB4J#$- z4a)B#wHMQJ9muS%zb0xnpf_8O?1sC^Xt}XT^|#&TKfNs)MLpw?>(0rVFTYken5kz* zQORwlk<8*bYm~P>rZxFlhFV+9qM9#O$SMp|$|qn+cbrFy$@~CsvOnrAKh%=)(<5y~ z4d)lbbJCQuESLTkriJUzgncC6?P|YteFdxmmscN)(H84+kl0_V|D(``n;uM!_Gq9I z6=l{!&OT5q(=XfQP>6TB@Qi-f3e9vIq`9`*p*C*EHPO&irPMmorQE{bl`@Hh0Erd-1NiC1hUF~<$1uUFwnV}<=UhTH;JVLBl#C8&cAdqYMHL5}+xRcP zeMK3f84YzTyPKgzuG8<2Qi)iNXue8wf@tQ>vD!{PvN(@D9f;y|Y&tq@W zAiKSyS$ZH*0_SA2F*69fV&Ts5>W^4;6retzJr-n5UiD<8*Qup&x-{>d$v%)4s3Vkm z)4wNUT_VQ)%`Xzn)9g&L5VQIz;QFRGKPc&@lpqQc@f_9AVb1 z1ron5Lw6Egza_c5^O#=}zgV=LY+fY`rgj#+PO!KNVgLFPn|x~0z|XIEweP!p8l{77 zZ)pHjT?Qve6{@AvNdPZivYuSso~i|LDD@}mI+gKeiy0e9MV`B zcelJ?GS!hgSF7~mh|;s#aBsRtqF1Tx$X;yMk|U=z|4G4P9%SjY)BdQ8H-i;^$MkwE z)#Z-R+~lE;^Qe}%TPe4n=U(NssA9(9tlr()xf!=*y_f8Eg7%-$}sIvD85- zF26I1f@&)j&y&H*d>7NqGSlfuSW#_nQ>FQGrP7UTwHSNx*=!g^KIYnLK4a=-PxwI} zSVYElDBuO*k5d(My`J$N-ki`9Sc=7~hN~;Cpj!?3_1yZIMJEmV4I`ww@^UC2POL)rqDN;hu*q1WLSyn2H#^bHjVh3@b(evJO zNhyt+i#azQQ&i!oL8xn4?axbjwFlXp0m3%q|@ z;?|+S-iuMhY+8v3hP~|0UZHX9;HYNJ6^}Bc`su-wVPZ(Owgj`ZiNxvLER00FVBun3 zFC2=@K|qo_y%C3+4|0$C*l^!{(@(^8wt?1Dw~R}j@tBtH7r|5e6}4F2F8H{s!a$^= z;c9n!TEAs}v_-7a%v=16O73jek^Hz7989-9jkMAa?{I7K8cEAO$|PE3Ms4U@Vjhj) zkFw(Tp)b8d=W*@wRZmB=w)%YDu?j=<)jK!nQMHO-!%%wYb$;b9$(UiO;iOJwY4San zoT^P+_(CGJZhP#$CCK5UCQ4eb$Crg8Pp_)2rGjvTLTxYVh1HaWgsfHbWC(OZM<=8v zY;S2)A_inii_0wHGPKpo{j5tlr6;3=uJEkn3wElNi8Wd(CZ**{^FExlHzIbwm@gKQz>u{nh>Tn!3_e4vqJ+*~Ow;(Ok1hNJI5UHQK>g5HaOU2i$Y2K%xHrEEzoYk}0H|X>U zwDi*1ZqButL#6WYkOI-W1u6~KYlx@Kz{pMRF=Ce+XswB}TTXk!O_A0~9g!=O)oi?p zzLRgW?+=!@rA=Xx3=K6eKJBGi?X;#*bmIoC#M5I`_H%d>YPWe5T#hELu~Mb^@J8>w z34kmBJT=)$iFU9_6qB!c)uk8+mD=7RE0B?S6WlGgoYHP5w-oVB8B*HW3a)P(8&Jxi zT8lJ<*O0C-eW~yX_%5-pPrXRwUoE=$1NW9$Xtz|E^nQRz&s{=;96Kmi_!;Gg6560X zGTC|BdR+N#j!QX?jODQX4(Yc8VasH@~NEvloTU%B zt++yMEslImQK8mcRW$yptjjwyj@2lXNR(>gX@c&UkQDu^(2}A(^`{g?S`1rrdhW~m z>z$!PI-=pU%Sx43bIdwof1RPj(WuO_NVrGP@%oaljY3P8+Rw8g$%LK{SHn;Fc+R(% z@D`It5IlLa_uRQ*Tg|(G=T(2-1%MV(sDGz!wJnq5w^hfj&Je5}#=+!pR5#?mwvzX$ z7Olm)%4y?x-RckqoLQZCq^?$LDY5eAq9n5xZEPeTr4(-^(>%IK{(#_ba>`Vx45f^T zKaPm`8P!oTahHESA4FeWtD4$>JC$}nV=490hzBP`)JXZUbOJRHvuei2SH>tT%H^>iy*qPXQD=>c++K|X3Zl~_o#(QPb})-WyiN`HQM zGs>)3sauEg_R2ud4L0$O_zDfRrJQi-ip`)A2FZG$`Dt3UO(zjs7iz<5{Dnwd2`B$y z+J272o=IJ^*Ry*m2o^TX+2H1VF={jNkYUOxP)w_Jw1uXx&t*r;B3)3edh=pnGvOft z#x^dDn!}D!MK_^7#{B7eG~)24C)h%*Dl2i}8&}C(H}8yA`bu_DQnTH>hFXpFEgX04 z6U`~xo#j&>e0YKF7&t}(#Zrxk*hs|~wx<-x^@UJtq(;v7bb{k4``VD;;MMt(y^K;6 zFk%X(*u92EdG+gxG$*5A#d!T;bJ02!1*e6G?g(*P@Of-TrD4|9!qK(l=K$uK12k7s zu@|Ek6&@OcUWz+RhU&BV{r8KvKwiSCPeTk$Q4fiSm5Z34ef6+>ZJKeSvKT&rQCwhF zmDLx7eq#iRSTRi3A-a9gTMm=BBZ{W$GMm}ll8ggvx4q_3J>dk5b9vfo*(P%i|7W~onrOG9&==S0mN(}%sDpi7Q52u$*viM?eww*5A`3ZlJaZmdv9 zYNaLEDVFtxGbLerWvS1%!p_ZNH(z~K zGhY zrca}pn&v{t{g+v*WRxotN4QxvlErJ+5Z`X&%`_IOx>AE~urP6h+ITZrqXOvljW0&x z?H|>b%}t^q!L$^a7^32tcW)kuZu2+IE#7IZT?^FW;o6JD{O=D80gq^=+i!r)8?L)u zo`#5D`8CE@#9s~KOs4ao5`9SRUsgIs)~9hr3X(DA-Lq4c3~x=_p;TR}IDW(gsu(L)H0`F4AOe)J_M{tkT50ri!xu*oF@9 zmnv>%XVP&l0p!L8R=GM)dCtA1AzLd$mX1pIDU{}7_C{>0O^ll~<=HAtxJm|}O5zd+ z7U{XXtvp%r1S>EI&PnWeXzB zC|b+BKGwWWInT`Me8h(ei8`1&E4L(DnB7a%&UPzdoj$E&08~h`A#HHcUuYE>Ww+aGfTyus1!K4 zwcO=c`^S7JSP9vwm@sOYz*I{I&*HBRp>BTsYeDul8qS6Wroy>St0ErtfvL&ohU8A> z?H(7^`l^qE5~?0Tx!CsHNs|J>V_rc}>QMG}rdC06omA^N61jfhVL0=T#z`tvsL|B@ zM1*}?U7G=ByOf-+MR%zy9;a_`_ApDTnpFb&aEDz99q8=46!7R(n9DQl+2Xai$|G^& z`6N_+o6|>}^OV~4Cg=6-g@DRr?S~H8aH~kTcoKG{{$ib8Qqrlq@=cf6)6u#UvPpQp zy=ACMGY7bN>41aj#gf?S6A4AeTJ zB;~}99$8LDP&-THSIv2d=dJ|@u?O!AA4xxF)+5*9T$R1TQWt-wn6Z%od3CQc%TICM zW##yKvT*SnKBHdrk|eZq6g(i)BJr3VoLHZhT$OFH_1%F2u}bejYf= z+_8`>U*19`=%zM21XDP(C78RduxI3KcEXF8b2%omR$|u?beTp&$m2Y#hKCKpUH<@B*oS`05-N0B; zQi~5wmOa?CL!5og}OtfL{5#A=N>L##`*-fcbE zPs@mLJMxORc!fRQ@&Xlntqj|o(tK&OKymV2mo2TF% z@&ToXgZ1K4PLf*ojVu(p}CEYjS(IUjp5q`OAkr-SWXmw1*}|6}9ZIgazIG zq_`*ydmA(B%d~2_MFmum+pT+$if)xNwyi24MKeK3utVHWXV3HDBKqxJuK8XOKLdN-m)t!CeD!OSso^(jUfX6QUTn3rWos)*PD zhv%3goH^11aWcwzvgw(9D(d`$xCheR9Yj)sw8sa57Ur#n)jStF7_~1qB`&1RBzZ1o z(->_zgrrTi&O)WQtL_4@v|4Geg`oMx^)n7d+FI>qD8+6fmDsn`Kl3<%1|MdHln#>1 zH51Y1!xGCb{5KW)m zc&=UmYMbmmQmP+w=crT(+vTDFPcC;~X8s?>-ZCnVZ(I9~0ST@lcoHl)1osf!9Rf|` z?oP1o-~oaMcX#*365PEZNaOCVP4o6Y`<#95yT`fX-ZAP!kFJ(lYt33~&gc16m4^;s z7V46(ib9q+z(pfClXb+T80S%UnW>^Y>&wXEJakg2wtA;|$~HEkzUL;hTBMzkrkAV} zG^o?8$G_f!8_ZhVlI`p7u%>gy23A2hEx1o-DjS8BKMnHsG9xDLuRkS?%hgs&9|i2eF!v znrd-uSSp2kb;T@HZ<(t$^4w~{l<|_MW_k2}gXOCKM6=is2yJ>OP$LcnQr#&bQsMk# z45G6vQ;iCqrHK(%xTiywtb_qRLI#Umpf9IkNo#)Il>MH-_6mM;58t=(kktA z`T`@Mh;m7`=6&72BbrB$SU?tOWV5nH0;DXNDFJ3eE92AD)yHG$D?ihwv+XlIf>b$V zC*;xGvQCwRAy-zutGrtK!}a=-6rlLB!9*%#r-(lJfX*{Ih;!M0y2+ESGCUI2WP z=QV3LF{=DnaHf=@?s6P$8v@{GlB1&%|02iXhjwQEtq7wPNa)+&){YD9G%B^}*XZm8euUO${Q=3>DztzPq8D zcV}IXlaW3)9V?vV+3G?RhX2;<1w-yKW$$G?9+)q-w@ZA@&Mv75GPm!=)|PQT-rg3s zQ!VZ|$C}%0c_hL&nbt940OjZnR|>Q0S=lyj=oLC8 zaOB=8M{qc*fOnspC0)(3>#WmzvuG|KvGV(l(m%bxK_=GtDYL;yEJlIxVj1NCe>-0W z^3=TFoDf9svW??k<0x)nJ(~MZj!M_U9v@gYW(SjvVX9$3V~=Htu4VZllAJq=p`%Vg zsWAV~r&3hFo&zOd(k;f4phA0SA6z<4an0y3Aa`5ivgs(Jl_wo@B##~>RoTNpxxict zF_^9Ag=o~7w>XClZMgEA;@}_;ctYiv=<*t1Rk8llJ>}CqHxb1BGx6ZeZe%%*WnAAo z^-0Gf@d%6SU8upq)agvJ8<9>ref?v%xvyoL0n7cqt5qzFKha^bSEzV<#R*8Mw6X)i z*+p9(om7vqn<}~Vuu8_$EV_rV>VIE6SP28pvbEo0VF}+Rxt9Se4~NKWa>Ypxjwhhk z6?rkN@X>cY60b6U*eV@sRT=lo`ApL z%vMY$wAclC>$;wj8p1TE$yO_0IFESg0+?+q9Sgcj_kf92j~l?yC@&-a1~! z*RNsK?zIV)Uw$8%d(}Rr*)YHX(!a!bIYr`krHq7=tZshH>1o->tF_dsBaxKijqkuRNlaqM!yn zH-pDm{Z^sGYt$BvhvDOW?FOm(M;mZOroPcfCM1a<_b=M108uS8@G@P3D)Z=Z3h_nR zC~$mawxE*JlkPrar(XTgp+wND(EGvXNJY887Kwn&SDScuI;C1K7k8VAbaTYGvy+)A zUte)rbrko$h1t3BRG@_(nG|rmN%!Q8Kcmy_of9&ko1ZBG<0eIkt1ZUH0q`<(7LsQmPM0H{hg-<2#2LA5W8zJ)eJi`0Wkz z=$jwH*Z&eN0!)qB6cMyPK!zKJsIFklVusKAb0%T+=(Yb2VA+CTK8oLvj!I3BT1VJLS}6<78NuxKCo+ zKJn3Ax8R8sgx<+*lZsBI4`J}DO2^_gwJCi5t06wwN`*iK{>}INr30fsV@lzR<{5A% zzEj@SwQG44gZ_;EFQ%#~T}nFhNu9xy-8H?mki*Hz5Rhc%l4j0Q!19!6tE*T5N$UN7 zupr?A`j}?yLl-9wzN%4LeD*@7^+yv1kDH|s`@h)KH_vc}oFYLa2e_E=?yY$;CE`#N zsfbcNMj;lqJwD7PrHeB_?&I#1A2+WrS2ZK8cvv*tMw~alKGRjJ)oQeOtAM`={5HZU z+{Z(;_tmeC^S|H>eNV~C)~gEA_wJ|-%L*bPf7|O45rg^Un*zrqk#J+CZR8-!ydM5c zeJO==*`G2+l-hGdMk_v%S<7aUy@yt6tvQJ;zVfNBxTcVw_p*B*>@);~3 z*F%37KO_LuZNmN$x}X>N+qKwQzWgkJ{-QIg<#NYCxI)k-ydLb3x@C{bC=aC9pXOCM zkrZ$l2@xnr|8GcaYi6f~yB2@rE8*Llec5U?QqFp%Nq4%a+`hL6H zn@~=0IptUQJG=42e}kmsCbT;fNQie5W0-kP;J3Z6PjbK(J{FRx14K$)PM zHQCEQ#pD1| z=8L!yBI$f?imFTnoP{YD-30sf6<;e;0DZ19Bu~pd_p~oVy@xg_k5tz;y(sq4t^cfQ zx*KI1$E?T{R{Za#p{S-^P{mbmAJ^Q2z~hWODfXLK)uM=&W35e^%{txDy|xN8x5t`# z-9xZ+h&WPT9`Uc&)wZ_2StCiOYPuDfu#^ENDi^iW=NWna?8uSwSi1ZPs_!hVgpXvz z6t~BIsHFM-Vf6Ji@|^MRH!u5Wk=0ULSBhqPcwug8YFJ&?d{YQge~gU8*6-@%@X}a4Mc(XymyJgriXAAj7qQY=|d0Qr1qV@I_s!AV$j8=cYCsMmY>aM$O6(A&PF+aGC|_B^s{^BkSVKYk5s zQM2a1O<3X+{eAU+xk&1+{e3B}TWyrE#&hiQ%B$V}3BQ;~Q}rM+8x14u{m#%@^vK;G z_MrRwyKR6-@zQjUGQ1*Vp-M9~@ko6t{)_WwygU;nND4tc;lTGu&=*?mF028VSn~`NUm+BgvZ)0A;0ty zf#thiUcn$R9mn6m)x(@Dpfp=es~K!M@AZ*GKGC&)*|mX_`L))VS-Jz+WbDVn&%|sy zcRx}jYPQV&Z?R2qigl(k+-ZjTdMWwEw!+LdiiFBhpX}T24u9q z4*nOd0|o-q^KKg(2K3wq|H8O3%9yW>{Uh9wV7b^D2m7|GFV!r%onBnN-?@dG8y_MX zs$b~>3?7`V)I?Zf5BAUWw#+gO9gX`D>!;L@Hf(fHJHqoIwvAeLdeqC7bHm1V^BSz2 zK1v~Dfpn1>yRmFT^oe+rJs2ZlB>aOzZh5$sf^}{#+0#yXXly-%{Ue(8_7%=9wfQ#N zP+V?}R^#Rxtbbb_dX-d^ig(>nCLcZu)yiDB7SHl%R$m&yfbpprM#i;7wYOhw)j@-! zS>?+GN%{E?qal!AoxDDpY~b5RXy#+j<8&tY9_Y5vxVzYTI7$rL2}Sfs`P%Zw}EaqfeB5je-0j$}+sSl7=%T?Z2BQfISo3a zaXqA0JA$GEP&Tk(xX77J>ZL>?ICCy)4$j~3f)+O803M#40C^vJ zsu1^MPGkwp+xIo|i&hHec_Lf)nzbt$n^M94UZNp+2OC^4)2Ua#+cQ7P*Y{+&o?ii; zRPsf=TyH8Dj`I+SI1yjZXb>*Z-<d+mZfFe zrY^ZRi4Z4tb7>$K=dT~zn*|k1EghYEZRcydmD_yc2vL?K^VqFUX`NnLZZMM#<360l z(QnD>myrD7S~L_1_D`ZVOTLU05zN^~>nQEuYgV?gIi4;^A%z|wk{U#AszzJk6c2{r z+)i0-jTB=Zwn&zEXPU{GZP|ZXx~&d;BAb~?dW-7N&t-87i5mtzee$W7qbdA()8Y2p z^h+cSZHc^?0WH(mym&@~xZhqN>-d;r_LZ%c^>%Gbo$(088M#Pt6|^`~NnW>FL30xu z%1g%+Nc%c`AVEAb(7dIFFnlg{_oqpioj}ygF8nCU>T*U<)3rq2!(lKEdgIbI#lBTx z+f@klsL=jp4_$Hqt5+_4`O>M9;2lSqoF@)~oXtNR?!Bq2f4@-vJKVy}zQm2>PH-Bp zp}wq4ji>@r+^85sWIdDInCiB5n7F}EJh46|oa-%eA}c(9vF&y0%+(B$Q6G-2T<0PO zd^D3OC@*}&Ignts5Nl=4b029@|1c^GG<5PQLDA4yQ7g&?1k5O~ejV_|4(h_28`O4h z08Flw)n95{G09F~u-j$^q}U!ue|I-6 zG6nx9!!aC%O0Y{ItThv5go&f}Zg!^xgs;YmJudabX^$z8R(h=I_3rel7Zzy`2iSAN)+@wTENN*6aSerwBP^-DR?)S*QyY^4sUE-_$OGwsTmc zZ}pJ6DKX+x$8}3b|cXWM&1y&hHTB_7KiyGRTGnrgTZ)R;OcmD zDaR#+uh^rOW?7U&n?c9feZ4irRdxjUJS@c?Np${PxC%oYZ722~49)!N;e-fjlxwz# zlo~Mc7ZzmED(eTyA;4ElLXgP4!Rtp2nAo|kYy$H_tl2;fvra+~8nY12pJ6VJ7oXog z#eYTtO27DtXw!d~*_&nSfOg4m=Mzju=ZU|4VTt*4{R!o!XS4;N#%v^kJ4$;B`qcq? zjN=&{CNIn|O zkdB?l_`64WdUa#sq%W0|>(P0c&Mi4O-Zh{zmQ)wwHjKy~PMhmpo%M*Gf>~G$v@7%T zAE%b--s6Llqm>a6=3ba0!{0F^#avnreTYQ|qA0NoYpRmMAm#!Gj3Vz`Wb}o|>T9E0 zV=JB_91H9-&XSqz4vHbo#sNqEGq6*VEN+!ArbZ?j_&Du1SX&A8CNF=`)Pblv=Ew== zkR`>xSOB2EH{f$b1E?>HC6FPClw8_4k3{lm$Bje|)^=4>n_1-1B%di0f6qV|t*w&R z5ABY`Ur;iZKbY+j!#HBi^34@iuv=#oG29o(Eiuy_&65n2=g>biX-H7W(j$U=(@20* z${YR_FOeNBS4-X#YPc^vSIk=3?SA}ujo`h?P{~ByYiAJzO8u->wU-Y1DaQb_BD-H( zTtl$6T=?Oem5S~Pd;YFSkB6_8Lm#*3m%GS&f}v`XPO7|n-(19U?@qiAPJDkxSe@%Y z^a@LxgV)w7GfJVRE*H9V%5-E5{O)P{ZO;#9tMwlO4cexD1rKX%<--#`iLIIs57X?F;PB99KciumKh>CJIcBR>Dz6(-xcfX3Z`GcdSt$pY^V^A?Y7r!r{K2xkdSEkpz z)__e8y`RBX6pugLX<`DA4;tha*CU1$(*@#%5A;!UPcLT-5l$MxwFp;@BNa1DcuQ_O z`y_}@kAmWMoX8i`ZFsJMETVn42>c_sJ?%1|^TC|`v8f~=reRrzdm}WodEx*gj_B0y z=9dmtkwCvOhyUA`|K4(kCH}C9Umf7S*tNhXeqnT%9ftAmmLXpR7Jtj};Vx#8wKrl< zM}AGgOamqQ3;qB6fI5M!V_0U7h5wHH9`nmiu5h%PzNmly0egCqy*C_FEBM|$0!Ar1 z`jb26>c+`E>W%gwSrg8%%H>h!0mYsdfm0Nf^ejb*NLM`PABS{k0O#TMj*s-!57Vg3 zi3pY{3*_!Y_Q|%E;Jtv1#q~Z-K*)Iq(|WkzLpOmp{H6bjP|1bpe~-sMM_nzwG)nwW zJAM-sIY+(wpTq5xiGGE7dMa_^cOw%GLhcw3DWP75E1aH0X`A8?X;sp4erlLRAt8?~gF7^P%gx0n}2mWsF%3&>72 zd|^ha^pKR)hFI`%0lr`<6j^C(3ExSpQBrxS*p}JHi|SIn%E#}Pvdx-5YPx=HVB&I- z9-?1<^`zrwPNalu*B05upE1wBZaC;0YdUspq}XpB03NBRi2l$k!Q(k>ehj)@BE)_( zF{Ud5v|`8!q_U#qJOG>#+-7N_C-gN;UU>tOaXAAqFdzJ%t;v0jk}=my9IToPeUj9E zviqJph!1C^I8GIlBC=fkOY^EP2jHyW2S@UU!Xeur@J1%sJH_3TSG7sj-JOR?t1RhC zJD-f_2gf7{Bz|IhjwqIuIAF=K9nK^GR(aH9 zHL5y0i+VpNR1w!{5(v=w$co|5jxtWlR=aJ87?JoH5lougot)70^)c&3{`s{0g3bG8RS@n1`gJ0D@juU}wp*R{o=z~pw51Aabxv-V1ll|U3Za4{z{ssr)o+m_L{ z8M_hk*Er~Y10*ze^9+w?v+z5a=ku-*`hNl{kYPXMRaSZi#AkFC=JiSM(;`pu4IUj^ zBpvRHSsyx?g;&T>%I)Gq=GET;DN-``X6_(sqx0)y3t3&hzS_MvEj}qyQ=7n6H=P&% zI@Rcps0iWk2i4u2f_eX867(Edu{!FPou;2+@7BP@>l^2VZ(nvAzH#g2TS-}$ReqIq z>5QFU&$6LmYXsOcevfllc*mrSN7sq39o_8A@v4^k3>cv0=qHX67+GCEfIw()VWpuQt&T878x z@zLn~$1`{MkYHNl-Z#HFn~e2pqKQD%yEU_K`Zm;?vo-ux+cf!yjjSvFZH>OKl?GF= zObck)nYzg!DaFh}W7%yX1C5IhUKt!Tq1@M%^wbytuonh zC4|FvmVNaHt+lqpRN>meg%-gGs?}*QqGnPz4n0xdwXVopfg4>>wMnTv7!0Sj9kO|D zw%cDl9Jpa)*MtPTL#QIIddxJAZkAhJvdKDbZT>V^Kdm(nCcs|_*MaWXRupWUsa~0H zsvK)I11UqH5a~WE+Mk472=M_kQq8oruRP$!Bjt7r?d>j5JA-BLaN_;=u!w3 zBQtoYKW3~5rfzWx4wJ!j$1WG+4i><{Vc4*qoBgc^0Y(?z_F)52p#Vbz>bArBpZY?b zN6!!w5sBn=agW~40YHaqtuZ93BLy-4qt z_-Fm`qL9xC#bCgMY@hDT;Pj3dTlxat^1O=z>Rjede{38eYl% z=1gs0@$gdzW4$TYf-D`DZZ`c=RI}>lvOePXu{D^ylsA-}H_wQ| z*nXH5r70{wwxy*>FVvq?lKaGaiIT_+@2$Vx- z8JIp~_smPOnZx}biW*&Wo`)$DhGJN(13ZJv7I|`xbh?7kh>aQe1}5U(rXBTrn*;wj zc7kIMj}&hYYqvp4ZuFTS^4$EDktgjpS{kQ%Ql-gwi+k%y$N0?4(GUy;R>!l2O*Ydb=|awE)~kI zHj*}Vo0aDGJ0H5L)?4j!udXOnD_{f)HGM!IlUSWJJ`9^V+R^QXiPAex&UeXX3+;-| za8}UesO;WBj_kxn(T^vAW6Gb{SXR}X=$9rizI;7i@9qgcn@Me9ICQ5)K=#p4aRMxiPumW_PJPK^mqvo3)i}j#-WM0rRPhj z{5a&zP`Z{)xBW&M9gW|h(Rm%NYX1Z|!H>9}WSLYV??P*SG?XUooP)E?=DO&kqWVf+ zmR9#Lf5%zBBZMzvkAUhdq~*vtQVl+g<7usmx?78*>IpkaX-oPJyLn-g+tPe?O4bUl z2yL&e;nTmsth7@$Ss%>Ro6`;o=EdMe-u>$nJxV5m{@9dvQE0Y%5$(}G@%Wrftc4%Y z$nim&X?uL3V^bnLw?#U=A;%V*s<^Y#274eXD9*!@S0|ql>Id#~DGnXxPTz7?UY0P8 z&6Jwkb~v4>rt^G56e#;+Mo-QNh*N7$TK$?>mD~Kju^AscGQ52DW~j^Vr_U*BhoG)J z+c*4AX9Sfew!K=EIthIaO1f1%jpL==xNowax&NruKHs>L3A=*FOw|h@#GV#;VT^e6 zh)0k~dz?&croM7sXXfd+V{GpTqh#mzEn?%X;on+kcjIz z%zt<>5%5+)NW<_T7FO^@?e)!sYLfKah{gNz_HS^yprQ?$&-SnnAD-qhEB7iptZav;rp7L+k#%CR0pexKiOu zAFo;wmGF(i$6nm<2XJejk&Z)Ua^6q3J9*G-M$X@C zWpmh+^?o*b(Wo7f_IUP&D8PpCTX@4V(DTMP3SJ~6np^#iR?R-#w!pe%#>4F~ z=feu_F2%q?d(-{9e41g*UuFIkb31#Q>>sj9Dx}?M-=;Y_pgem-&&v)0u8GOG~yw90x*b$9uXFNA_>pcyfIP#6A5cnk4YU_>LT$BEDg=x}hD^cF;v5Pw$GC$7+s2vG zOu0}f@|9uGjv@ZhHhYSJ2RFTVMB_bF%3;#{HTJ9az4 z+q=uD3qmd7it~ln#9?uoMmcLgn)tR{- zI|*y>M#b-!M70zPT#AT}@Jp!8t9iT&eXIoJK2?8DMLGi zFQ>W1jb+$HYI9|<%QjAyP_-62z6WLZd<`o3vu9&99ZV*7(L(T+HGV()%OOLir!6z# z-E!(T|B}eh9FQfCO!^c;q1T!B^MeJ#I&%GW}v825>mkY|0lu{9PqmK|yKYZn z8td^j_xCmN&RA3UrEblVZ>n!2Z-UARC!6^cuI%^K1L(q@)y{M%7WVRuuH-ON;VC>(TqK>T*oYY8C{MS4LKuim}=h3N|MuvsNm3heOLf{r)RvZ+z!lv<5r*nbo%du@;`3}h9)N@DRHvDw6YS-(CmUr=Z zMO;}&P-~5Kt_Yjf;9b3gCtz%PF=}~R51(l?+b@bXeJQfJW@j~y)ahz`yrR18qY@r# zi=k!!<~En4VE^bYV13^|u$S7_cJw1ZjO}#)V<@Mk#x^ilmOwF#PMBTL@TJ+n40Kr4 zyBYMZkgWhh2=42}$)WgtXkp{|3Gc;j?myZPJEqi=o^^~8hMPWm-2AIpZT%tb_T`Dx z;v!4&s8ITM^PfP;=`$FDw=}G2^qgAfhaIxHHF<%11=zMFB$>ZRUO*2wc?}XSnB)s{ zZy581Lx&BnS=z~Bl+9X#wH>+eBD}w@pRcu4mU62_8}ub4Nl<$2@^2;7<)BL9Emei^ zcI<%daf0Y;iuEC(KkL}*dQHfO?5I|%?a{|J$7>uJl9zpgR?>V*0AAx*=Fd#1gOh+R zy-WIX*S_5o&11FZn=Ww8Ni1}EYs=jkj{A_0F6Lw*2Fqef9+~O1_ad7ctqwKThw^Z< z&my{pB9)xRKny+W=0%DZX>RLG<`mAMYn$Cv9@^UNek>BGV*8VR|!~``N5U@VTCwTrf!uy zf#cS2EdFLe{1l-)5D89*Uuf?$pwZ87`mOXUjpnt)?SxKU_?QyFzLz56E{qWpA%D8x zHay2Jd{wwEuEezNpB#(7)p6e({&XVvZs8O^D0m3OegjS5u(h-1VZgaS<^( z#+Nqc;3+VpON$U-fI&%%*~n$mr1h@tMa7ckZ}SscV^BZtb(|DF<-bwtO>)`SvF89Mt=Fr0q! zc`M?$gx1@>;G%qO%eIEUWjJlkP)TZ={!9?M8UN=9DC6__g|!ZM%FO4{zK*P`c}6WZ z`FA38$@#D7syrrVR1~eMDV{H0u4Dm5tJZ;{l=C$|ZU?T}rK^qVHB|McBLr6T#*0MY zl!87~W+wAK39PfoT0FbyrgYnydyc#6LLe& zzwPM5{&#VD1kwyR`Y@&PYtGnVYfRS2tcDl$z_k%jG$8tUCObf{s=qGkt-|a7(5-`$ zX_1+p{m6DLFIe(2SaC5mML{Y}t})+V{$6D3*F?Uk;NwhFtzePAqZ)>uNH0uyf)lA4ag9t3qx1G8t`{`EP>#l3 zCKbu!gz4vrq9dmq-u3O+WGhI8cy4h_SQz^0_kV<~#ZLApX~Y(-R^8!h;iKoxk(mgJ z(d6QxC&A-*=J}djI<*5Ft!1chO`R|Pq`vYbz)p3e?K-N}yIFf)?2UyYI)Qg9@YgH? z0bnkM2Z9lYR`Y#te-jfBhxBua(hrZbE)F3y{Fm-D}jUM(y$duuoF!W z!Hdb@>qnTOdsFH(#W2Z8wRBdcFJ$ruwIbhS zbZ!HA2?c8Df*~o%phedl|Id!#yF--}@*_y(1^>?|RD^HUIr*+f5$LE0r)e@oueqQW z-VQwbu95R$b`JD0tCQhupx|`TD=WkA4q4&=6!IQl_$P%t7bu!Lb z6(sT<%nt{-UXO67w?DFA%lQMj7*Yri6>x`FU(xj4TnmSls0I!Mf127~vL=u9i~UCU z`09)(3#lEtu5D2wB~Ij+UgAcU%+1aH>W1xGGW&4oxV`l?ij7o>rHOCn>mhwFQnLZowzX zUyXgnSvGu5MchQXV8uI@BfO@_OcXt-Mz~``w0Co!^fJU?`xqyjE+`bKIgGw=d6}^8 zaCY67udQG~*F{Wo79Vb@ytjQi2soy{%d2$iwP{g zk(k%8B|!ez;`e2%7%NE5r-17J3G%-mWzP={4b5(C^)VJLV?uA7*&e?Xbf{gH>%0Qj zwmnuOwl6G-cvsQdX+;+S=MPbW=f{YSeS<{5OXrK0-v=cBgs1R{!}ERqpIBYDixam2 zz=dQROs$UWy-m!nT_ZzZ@(1$|_aUYGjv%rE1lvfZ4zng(hxz>LniI!o+qho>$XvwJ#Wn?jJ+MQ zYD>vzk7+UG=%m*kNf3A{nO?+sy>%jS)a)Q^rHX1r`#-)+QdU3l)5*~s6fxr;$e8Nx zP zwvojC%vS@lkYZKFunzYVjR8(jw~g5;4C_DIwKuc+C#X}MEWjjP_ogOL#kd&$H4q9! zG}VIj3+|BiOHox<76bk7W5|I8y>T;C=zYiSe+fnqFH%8Ao0lIALP1{LU-yOT3X^Ue^Pf(^+URR77&X|(C4Vd)Y%Rgkku-^0<^<)KjvERMG zC&l~GA&^XereV$uPTA&>REMv2)YkTkTy2&Z(G-l*jt_kUTjS$-hkvM5CL%-n6)(a} zmhfmQ`!_OrLWi+%y5)DX+p_)r&qL-sa=y>_xp4)@w%U{Jb8c~R{`%xGg;kNZIJBhB zTQ&GR;BS~^w0o!)C<)WdG4hpO4ipe8&+l8$Rdi!o3?>W!NYIe&{8D5>Nih8>VX-4v zN6HCNwWB3BMoz=T6kZlUTy&7ZC64u9KE?9A4d`LHO;s*=2vAOmN8immJD=HaM`rwDP%J!6n-1& zO?mTrd5$#XwxWu-d+m_z{GiwLb6JlbU!r)uKMfd4^WcejzY5 zP66tq=V285?ApR|^3$n6SHp2z_Z}3dW(}T7ZWnF&;cw)upfhP#;LL)RF%D z&K&!^3)NxE;5t^<^e@)eBIJ5&X(=Ky8m~l#8+0Rhd$#{d2wv=kBoooLEY?Y z7lbhu=VU_68>3ELkROZ+ELI`;oDjY?dpbUEYAzXwe{dWSV?V#g)ZgJ47(kC+{lm0e z(1nk|h9^2X;a3^1!;W=9&52OR6(!xWvBwn7=n%tgF?c0)SHF>{{vWRgK4a9D8h(r* zpweqr7wd808RD@uHIrk;12F={eV|w zFpAgC9uHxnTVG&FGOjZ?UDH?*^JTNQb4!D%1i(?NzIfQ$s#o`#kFCK>1M>Bt3eYZiJLPm`ia4CiIjy4H*I264KGv3-O}&i zAOC6T1bSo5?UGbcBriebY@)DH+YDMc2s%vh{J5MiRys&(;! zs`TkP|B@R?385l$+Y%=l-b(I@N)n>7qDVp@iS$k1*Cn(IbJhdF-|*vdv#B;|hW-+x z9Zf%t&Taav#01CUCW7M~6z0}zr!`}7&;1eDPe}DeGJbUL)v=IdSg~K{(41bKYc`qh zOU!T@wFy+3S8ldEOp5u543-U(;l%H%iEl6Q*tK4B$?3a?T;XQfxY;7f5QKM97*utudFGCGur1NLB8Q4F{Sg*xmCC zoVMIR1?h`jOp0lG=p$L!K;do^q;9u~e4uIy@h{KhCwb0&^!ScD5byZyAY>rN*AesK z-Zwe(5-MxHroE{QqH&V;T_c^YWcA!0lNn*l&nSIwb+iI)xCnu(3T^4XnlWS-;6kBJ zEjO17^hNcs80$sfC?{}@lFg;tAiA7owfjUkNr$269!t8tukcnYRd6wxz)Vd7h=;G3 zLVFOp@Ij~{RUeGQqbw&S$-i{`sJ%gyA4eXRXyR7-@-w!P)q*3vlbWK-fqG@_TP0dki(=d?*4&bEtVWfTePmt zOZ*VVCqOY;Ga`?gB}d+Xynhh*d#ZG%`eYg$x4^lPOn3-q=n#f2C7NpdrxLCQ@}4J5 z{QPf~e>EXxsz~JY9k_`pmLmTqnd)ph2XoSbD(CF3d^l4Hpvn^xg?w-ycgRLx=YU{c zYMEO6-mi}J=4pwo6eXADZKXNh$j2CEwq+kX7_Ld6fOX8rH z{tFpwBtB|+<-tXfmwx&`O^mG?sx--5j>i|$=bGl8Y-XB5(;MXLGOLCpcAV#pLcM2> zWV8mYzmFqlCNZ*JM8mt8gi@>Hr4u%Np*XtyAxj7rdR?hLv)>QfJyBFml7(9HH1ECY!^r>{P z-E&gj$fK29fC%TP@p)-w%{%@$S|fgPk}B7f|Jw$U^Tr|}7V0z*Zh66mGT!n*^o&)o zX8)+QF6#v@VNq6N{df*aY=aXg$+kOVgsuLKj$@bUen?21z%om(doLz@BD~hj>2#T z#Zf~8qcU;mdgPo`x!q}_SKfBLMRNCUZUM%fw$H|Q4tB(}hrcFMNLYDOZ+8eu1)0qcAUm}j2V;UH%1(oN#Crr;oNS7 zQ|ndKaN3MC-Yi}91TKCQ<1qT@zqAmp*r=9ZAO%Pa^6#`hxYD{} zweowq?2Gn{*e+PcbKb&vZ#seopzi+c@otQ|$TLfT-QM$q_aOr|P^V|A^oSZ^>o?Ug zRem{Lzuz4){8qvbRl5=Z`gSdXv9^nraCYM{H8-!)881)F=W&IfKk|I`#YemhNKE;D zVk|r7lUj6$d2Xrp@2qbn0+bAT6w()4=!^^8<{?tJ1)p;<97>s;V{vXCi zpFXjzqhy>SLDt`nRLY#)twI{K?8D~I*=17a=dFs!fD4ybjAzazPx?hbVcr>@@${2a zW<&8lhk83-k8&*Kgo>p`wBr4 z6*RFZM$XqE#jP62%w2RZrwDQ@qSQal2sU|LU|up@*D%%x>nFa~GMIKAvTaK(Q9nMP zN)xBaXEAcJW-LaE-o5h?da!d!!AR|KXk!JrpVh+c(X9Gu1EI6mwTL~Jn;|b!Su>*m zs09eGzivBz+_8tNJU@uuy)qY^_IsH!6D=lcE&g*gTi(lA#Qs2Vv z4bCg zXiQ5b#g+M%lUrXuPB+y04@T4Zb8}`^c%A!}Q`iR%?cV%44W#?p-Kb`8ntP*z8#wUI zNyx(YFrJ=Y%atvvLQgI|PF9KbLy9FBrMxDi7msFw%Z6K9S;OVB+rIU^TJvKuebcp{ zLsjz`{Q+aW-+xH_;eRFmxB!Xbe+%}(Or^UFpjC+*CQD7M0A|&^++Bg9y)4>2yGt(D zy>8T`UFK2h4vU}gm3J2nsH6gJTT;Wu1y957fO4;XydN|WD=i{ZC5tMdyxX6#m+t#! zR1{ymI6Ydmxn#%T-hy3%*Y#y)govz8ij zd|rtvK=p7Q1N(0!`-3c(+i!h0H0vMNsplmar^>j$<|yqPTEF4&(0l5j%~v-yhkSla zDJO_LiEQ`L!(;vz$^HGkWl{Ydth|M@W54og$aM!gWh(-`aL~Cf@%PR}5D_bIIWEPu z07qc<(XqrAHW6GqPco>TVb5uC=~7DBML{))ST*@IZnx4OGHN+FR|7k}gk5&M0%-BI zB32$kjCzU5EvXv8Y<-(I8UiAVBBD|rXr~j+x%Qir6XCW#Mzj+pB0JiQ9!CGIc{8*{ zyKL_h5vwS)f8D2WT~ZR*bDiCEgs=IQB@roF7QM=!4z95I!;Qsm%+tK}wk_B1EOK>> z)7v|HeBrvFV@)0oQCPzyg?i3fk|tG6mm@E0ko%+X-j|TE>^Y;uUsr+Ty5Rg*L+Lb} zA?o%0hnwH(cF6bDlsHM4rv6mz5t>Qc(@8=<#qyec)IQALFs=aD9pDKsTD_dtogWXS z5ukh4Rd3zCX5Lu0F463f{x55TA8Bm_o$>hE?rnu(c`-F_qyHgnjMj{@%fCp65%T>p z>7!0@?Fq)SbiTN2m2%PKrs&2^g?!J#u&|nt784{8i!+(nR&<#=8w@Xt`e;0IpEL^w z+e_TTi|9D59mZhtb;<8_su^E7lx^r&=CWyAt2m#cm&+%_RI{eX9cT39_^ok=a9`6J z)@VBNH$J^xK{~uhHWtULgXG&PorAsaA?KvCo>?9l+4bXtiWxtox7?)bVJ7)wTKyOS zTLnbj!{gASPa0WDog|3}HS=G6(Fb$g``7mMS(}^!W}D-8TA*lYhhXaFirnZ;x!a7B zWtmFR*anaMV}U!l2?BQ{sE~Hs*7DE1o zddVp{L%c{*EwHW<{tszy8B|BN^nH_%V8Md>Cb+vh1PSi$5Zv7%xJz(%*93QWcX!*k zyS_Wgb)Ea1bHC?2Pt{XJ?GLkeF*9rR>goQifA=&GE;CDC2%1xJ_kv|_q9dZ4cB=gd zO)H?bln^7k`>zO}b?Ep%NYQ=1S9E?Q+L!=b`1TOTvN~?ywtUM?1Us4uynhm0QAYMt z1NRp~V-Y4kUk_c=u~g*@X#XN`czd3*LOj2pXTK(bllI7Ero_{yO}vu%BR3%461U2W zjM1pp=I$DI+rH@lGO~uN=aH9~^F>w3@)6JLyK~$o1m_#OXcfdA5u*tj9=noo?!3UI zNK1PZ?YwHz@ArqTJx+udMdov7FcBo#HV9VkT45{H$87SJUffLoVRMD7_vGg|>E@T#+OJ3gQ~@G_%)e!pb99a`apTG2ap-XnTb)5#PG}?hPy&)BhlSyX zvr`y5q;e~EFY<~X-HQAdCLP+8lF5oTnoJ6l8T1K8xn}L8Rr}Ks@00926OBMIe(f>qbH1GvP4$1SzSedOb<_I?PV$! z;bA`}?E?I?Y6|!X)cu7|I2Y8XAs{*$PoW)t@4u?!Emwqio#9uK$Be9ALJr_k>RFkS z!r0<0#os5~cno{zxZths;nh9=hy4$aD(dB_(X*Y^vW$bS)1O_pvMl){M*FsD<-1rR zp^s^Y-y0i@egE6$N*C0TLwO0im9G)={@08;Wt+3(y1j*3|2WZs(nNi}y6f?US&4-j zh7d^A4;GcilT#jAX2TnIJN9^@H+j3xEX0IV6;)gb%|Y*WNvJ*ztbOR26}8i(Cym70 zk#U4BdrlFs+Sm-VnpCd~zs9^AsPE%T$V+8xx~aTXSUA(J{7(r?Yfd{x# z982SdCf$7(MReddQ223Tx7*k)i74sGGpdycYKlxNPbhyMEIePBf`X!(5Kn~I{h0De zM;*oG^qKHfD_#@uj{l+g4~C_S@9yrF(bD3%^0jRno|hS_fnzCRw5~L&zr^J!MTky4 zY}4zLDRE*`o6)C3wj`#1eBGUWb+mucX~R8Q`y9uuf&1{Nvu+h|5y=Rvd}CePuzA?w zPCs80cyal~diJHGoEeL<3$~!Bqk6+qQ-i!O?E$`4V@~J#Qg8`wr_S3E_U09GajR4- zEtodq;XC8;mXwAyigG|xJfS+S$>jHlwByH!&3nG4)bKZ5H5G*6Y&k7iiwmkP@T@1G zAz{Ig1>5)gizkEb2n^J}5YOoL%0^*S(1>XbDxq!&6vbUB{!|AQikN0mAX)!aN&<@a zI>_x^JXGt0IU7(0+CV^yUI5XLKA2S8Fn_<1M!e-$fb{2Y%6B8)H3bpjkWj^Nc)|*z zY1CT09L^Cm1P%`5jRURIDOJae%au;@Hbr$=M@gmPEpSFnltU&BC21WGYcg{gd*Uq( z$mpr(mtWNnMpQX*dJI($BoY0xWb(j&&+P9Lb#4o+!X(@z(RdDwj;7zd*v>*`bLti| zrfq>}pZj_-f&w(=KQ76KjytORNA>sVDLaQGV~1oap7?sA<4;hXdxXE#)_+~N4_$cT zs3^Cnamd>HiI87A6?{T(qOMneqx(M<8g~@()E_B>4L}Nnpjr@=xv(LoW{`wT6P8Ct zMMXvKq5w(P+g`C!a^UJ-b7%0@(Rr6d;#l&QBb606Qff;H*h#|p0C6X^hFE5UY+mcq zUzM+d1pYC`!bypV7=uGYq&HL9kkQ||EMBbkouo}Ha%&rGTdQ{96t#_pZew{;i^i;<9q26JN=pb+0w?pUTJ7`9 zrLTyMJXljJ0xr9(=bTWCG|xk;UI4{fzB2<0iFBzE8sYnubQa7edQr}=A@X^gRt8HghYXYdIS`kX5t>rWsK ztGqCcS%l=@b$J;XefQY>z+#LyG*@nDGKoX*R`RM=wXlMM0Ju$G8A>$|`{8bJ%`4P? zNXzr)f&bt^8U+je{OZ*`K6Y{C>53O&%K9?#fHe@*lC;WwLxbRLOJ<*#od>GHdn0yt zwuA?*_8wc0c%HE}D{a1K?~KdK=b5Xtlb-B?mw2No^VEltw#uq*p5P^m3lkAU;jm9( zVHIA1q;hYIctK6Zmehj}PYEzYJr4kPhK+MkgcV9oQQ9wS+zPN{8s{*i^!k|l1D8pR zjIgh@`pxH;MK=O|zYPb^146MIfMA2DppM)vct+$3RRz3eQ% zggHm(=PLHad0MsoU&K5Yr5#av{i2BNJO?o`l|Q>84b+Egq#}}u4zGdp401e?+V6G!$N9LAAHBdqnJQ0&o03Q)tpJ(D%t!)S_Kx6TG z^^DK;x8o{_*uS2v^vP)BrO=#KP>({d4LpyRCP3h6@ps9`l4`x==IL zL5erymekKC79ZGA)#u|I6Z=0u7CCap80g$21D(x&gnb;+&TID@l{m#(e`Li-(oIjAg`j+kb}raR~W>wBJ5Dw*U7&Ul4BlwOh0aPU^06^vGp*1o|zF z|NGW5jnNiw$tpYMy67_X7*&jPA&0UiXlmS)5i$9F1DNEpt4*OV<`m*5EQokvVD)+7s0MT4o z?#>jrZ`kpi6QR^PcZbPh52#wXmh9(pi=-!8sNklGR@)*&sVR6~UNBtCRGN+_LA$lT zR&zd7rTJ|CGceeW^s~piiPk+~P=rBe+Bk|K^@x~I3AT2_busu@X%p|`Zdzwai@+QNHICyJ_UvFCWVACBq|V@DNiJ|BG#BdH6ZVpGkZ89hYRw6h~Y()wL0|&G5jm zBqp`((8mWZk=<{?c{)|cYk?7e+a}f8SO_cQs-%isORZi`^Rpjplgb{&w+#qcl@m2s z+FOOYMLF4unXCl(U9zV1=?)>@HYr2p7-4m~UEWVf@$>inuPH6of%6@kv(WwtamUw=WSe505( z!TKp>yFm8lUcK3&bbw!ALGc-;b3ThXK~80^t29Ztv`0uGTp?ZzQ5@hAlW{;BCdfVK?(FD z2-k!rVl&Py;z%nmx0I1clmx>{!{y!!!KA&!h_H+}$p2>uop@#QQ6I-7)FQk>(An#Sd22iR=Nd;hkS|{}qDYERpt=MTB_`f}3lO z58Z1vksn-*f7y@g9}KfL<{0}~0v_L?@Ram%*H?gbcJXb*(UaBcV;7`*BX8i%nLXai z4Pz;+eBR2Ry+_+H10+?XSs(m!LA|iY+CgOzA37V%si$(?8v&#zx1!SOb#x>j0GQ@< zthy{Z>30n0uoz2^PkIDg4utA+w8XlGV1}snBf`oRKKySKaa;NsZ|H{y8jBc%pp>&p z!lK2N_GVahAar?P)I?F4!FQvtW=)Hi9P~aDLdj=M$OAk;-1+L;=1#cL?t-gvKj*NB zi^x3zL$KSdrQY*kpNoqpN}Jaf<3$;b>EwEN9VSRdJzvt_ves?avme3difo1Sxjzg55&3V(9}-h8WyD9!sLwy!N^bT$B~T%)nQp(=sQ zqE<8)g#_W3OkbGrYSiHPxyV`h2q+Pr)SlUjSMuPJ^|m+x!0+v;vQ&Ci&rO=U-lRi5 z@PftsI3~yQqlDbBxrOhPdUrfxY@o&C3CV?;=V=EyxKxcN^oVxIK$`lu+wl_}b@tF? z#zd-_@&G{cKYYXgqi5`c)Ca|aNG(R5$q(g)y?DMd20cN9H?Ayy|vJNWZqWM=HgiEwsHXJ`+=;0+7&2H_K+CVi^17 z3L3-HwPY0R*5>kSIc>_zs{J^qgZF~0o5>2~lO_J-W7gM>3P`J+OcN*evyE4F{E4j? zx?!z)vV^Kp7$I6N(Fj!#MA7xEwBY-YovD6rk$hp+qw z=s`1Q|4Q0hzL&of{Dop2jO z;u&C7=L$mmdf>zMXu$8M+dK-%HOVEU#SN}{tXdz7mS3llmmk|%=QZw;9pe@?D)|w6 zjTA18gbSg~eEq+h&*aTy>_nc%dhSquCVs-hTdPHM8wI*MmZu(cv_jd>LfGMmUJma$ zfQlV4wgp?_dV4Le*f)k@S=+-oZ8YiKbd~InTDbe+)&I_#VFi(1CV4>4*s9k&5KRH}qaY)$gr*CHhQFEZ{zV|suK7n`6w z$rPW#T`$Ml61Qyk{^|8-#mQcCCh6?;l)bJ{``UCNx^$Hq+sS;Hp4iV15mMm8r}reK zuw6v=BgsyNlB$<|DK1G80iVGA{G#ai$g)?v6zdHf#LpOrD(`5`xQ*UFf6^Ti zu5~aFjV}dO#iM^%u^U?fE<83EoL1eQC<>_Byc$NE>+grN?wuUGRaa(B#fK;U_X(UL>MDbuyLs|_$V=~c`JD$an|I%CrQ7x!>qy3 z;(uAgy`I*&De?NTPc=xb`Wt(()K$2)8F|^J~ZA_K1yyt`(;|+ZKy*lu%Z!-68Fqw!Em%1t}AXygoiu z%CLx$S+D{U%;K;q>G$Mgytl~dUSB8Rj-kv@A%G>k!3jd2sICGG--^N>)!9@w-- zlHcn+fF?EWpVnMk1{3Z%D2+0i)EE^P$s@_9OCFvEjzL0MJ5OhLQ#*H}k-|S$6nRfa z6Kh4I*5l+EE$N|%8h*@OuRy6)i}WpA&-FGN z%4}(L$g4SpCtfLv{7S_xD=nCT?>tvZ<~uQC$1yz4#`Dr=1qgc1 zrb7fuy!Tv~z`;UO+f284s3df0`#u(}I}1F`UN8g58`(5R1QTtqfKy^L+tKn3-0u=f zpm%Qp^l#5=H!wdNZnAKV#IVzt4we`j+tGc4eEANYOYE<26CdT)Y;rgMGh=Rh!y9$a zE_^n|3>INm^`{zYZykHT%7I1HLE32y_9a_M0(b8vIgq@}Ue+cmQD zCF|*G^nrx;QH<<*CvLjNemtkh`TZy%wHb}66+5w_hw}8f${>FCv>f>67nr(ivUTJP z!Px!o1W3btNlcU{;BZI&o&pn-wgFlWztw=Hqaw*gTq-r!v7OHo7UXP@z2y+B!PyhM zW9oshk}k@xiLLi4qLiymLW*2iKDoHK09zR2hoZmoq+7am`i}7hwinBn9P92JpT-8y zuqA0RU}83P(zvv&uZAn`uA6Q;x%Xq54pvRm+OB?un`&D6aJIFtmK(C7B6#7q0Pm{1 z&sxtOl!r=&47~d69 zR8R^gtttq;fRIO{)VijfB~z+bZ`w>Lfj6A-(d@jzsVX0Y+mPMl*+o8J(O7zAF#|Tk zl~YUC>^YOjhw8iJJ9f+qPP&bb7HpzI(nGPA#?^iVg3rPt=}*;D&tM}c=2Vo#H6kyu zRo{ZjSUytQlmcs1eo|;t`Lhhh?QxJPah0-;GxW+?wJ5rSDh{Vhn|%$Ept}u(w@haD zPiv>-)IV3KdcSNS)yCU2PsaGUU{Z-+cKZppbxFzZzqvVD8X|9^FK2+FkGrZBfJfc7 z)=p-X47@0u%(uf-cb0v&c*LO>DXx_Yyc3rTh<;TZkurDQ^)qyiU7^zc>GFO$IoNBwh}U+1!sA1Hw4Hw|lnh56cM7I4AVO;7kI2 z{<`kpAKlb?6cBJ<>7<}O<+Ebmef-Dq*q8|YUq1;N$ijl?FXjCEOadC=u#-@q8pv|X zpg$SHE6Va+sQmT6K);q?b#ZY)dPiT<|1Go`@CB9#0{J622s;1IFQDG^xBDUrEW->3 zys4aD8qv``Sv)=4OQz$9Z0)kDQyk|!F5&MWWC(;yQHnyt4I2^9YishY1);2y7e*Hc zaJjO-FOlRnp~znB!>8>QA*fH~1EpjT0rc-r&BgH95x9mQwh_%&l@!VVBI<;|!HWS- z_vizuIk?tuV*Sy9&gP#{;!a;60m{a#pHeMj`Qb>&86i>vq1T2{Ivo{cawJcCv+saE zc8VZHulF`JHbh~Lz!O`{-}%2^FEO2>Y@H(Rcmh^!M<`NBB#9)Bbn4WleSkwn!DIiT z<&T>{o@Dj(jJ!SXbT*W5GnpOfZp(r2yhZqx$!ZJzwJKwFqfa5jg-WX}p16qKZ-Gmv zU9`_1!gMgA%FF8`I>Z~+vBR1(o0pf4uQW%V-_f0z8SLvJ_tiZI2^VN0T5s%l$|ns) zEMe#uA2Wa&vs@4FunEPTx7Jn*6q2KU&uil7nzmII{E@*>yqG@>XyPmxd>NRvp->Qf zva_LX%=7ki=#NPNZ*w+9Rj-*VE!DeQ>paIs#ei@l+!s(#gxzC<4Jmi;jfM@z)!AxJ z$u8pqCtNl$uBTd&Wjo?)gNUrc7sotDDiEr(rGa-+zRoVgExvu}^)dIW;MK|rwvE-0 zG1_DkAl2!T_P{v|rzL`u+E)Fgn{*||GN`I4K>s~1teUysm^eP88NA3XT6j(=h36X< z6d__N>hN*yaHhj=4m>8Jt7IVoUf)pn(r_EdyA34ndT4e|Dy$6o6H#6NEWSj|<$c1c+#fE?wnQL!BLE zdEq#$$2CS9Y>=qIHxG+vqyZ;4T`BPJ3?Zt|XUf{z;Es;%1M|M)RVM7B;fiZ;h|a<< zHa(vq{K%T5yrwZkWhV1&YV$-8-vV#fl8zw^fm*->Eo48$s(Ysh*dwSQ^QB#FN^rkjQ(@R-PQGpKrgfTba#^KSfs#@i95hfR8igYqU-F@!56r1b zy6^y;O%$=%I}K(E|9BA@tE3;a-=ElBdAg-_nzWA7a_BLl37so5QWd7s<)QEZRTrf# zkCiW1RU>F|!DRT&EY}buv46~Z_u!(h=-|qURYcKm(3jqsMcm#yAz1EWAe5+EqZgknH=$6VTTk=KxgQ2!KGQRApBsvF;KuZh z15m&A3L~!T_hRhj^-T=;S9&zJ)kMMTry3wKCSVDUvf=?L_qCV+?tyEk#f@1lQ(*yjFXB08c?dV9-_naHoEWtHZ2qP#iZP*mV*@NJIYd)q{E-PNsQt{%VC( z1vzg@E_p0#3SOckn5uuZf6FGT`FXMl#S#0P)aCxM`=W6N@4ll_uX+)8ZD95+t?MIf zDsvh-C+PJKT72ik_p78X&O$`99qYBpi}XpHCe{+2Q+tuTJ203)NAw3HM4XH*-iD+*nuYuiMlzwF~F6AILD`B ziFseQG87}5-uzUuk`P~$5_Z>!T9t(o)b#9mBEh(4$|WMHikddc1MzbcdA;ksTgBrL z0>zu$ToL_AGd9oWj}~w3@=A)5@OF{fzG8mQYhZ$xXg5IxxV!V273J-Pr4jEJy~DM{ zCtQfJa|_w)Z^f0ivQn_VR3o8fMQt<3ds;A;W=$hfLl566!TpWA) z2i1=VlKznFGCXSNHJm`jvytXVNM*rnCY((tD|ca&xtYe66*AwA?WX~aQSih~Xf>BI zZvZ89%88L^VQ8_m_O4UI2<%%j&s^>^rbw#AVUJL8=i?v`!M>W&`{i5bHXUcRP#1XY z43_{06G~M?jec(>Cm?e@@>2WD12ZrGZ77lUT#5iObU=^&axKJ^eNJ@_DV^Va2hwytu3U+BLE+0B> z%wU)6mppqU@|_gqR~gz&ZZVax7u$|ldQZ~NBP0A60aY}!&~;-8pUAb6cZk4Ifl zc^Tq!H}tD*x3?_jFk%x0ciAeZz%wZ`T0{aM>A=D)#T)_I!gYu#G5q5-o9m|A5~7p= zSW;i-QLLo0)Xpx>JG0q}N{t2O&EMT2(Au!7o~H#RuAI?+1ij9l?%`oCV~<`jCv+1* zd$Y~6E&M40(Xt6>lm6J$wo_C=qgy`4Mk{vS+o#SyWnUdY5W<{6DKCiR)vbiy^h`(8S*C{&LFqg3}%oEPY?{lrPz?1IxIv4iw?CPD3;C0e!Sbv`NoONgu=@@TH=R@RxF?mr+8hS zf{fON=+lC7RSc0_j)6|!h-G4r(GB7Mu~cA5u}>1#HB}0h7^7t7oy1Lz3eQ%A8O$e3k}BQh zCsu+U(pWm}_buh&j<|HN_IxG0-EK`3dw?BwS1-!rlhqNB0kj1LcZ99IZiVJOk+h|w znlB(+JX;xTn$Q9-EjZcNR(%aG2#ECIQW!)QP@mC)P7^AM(pW&v2tJDD)^*;S(cBv9 z>}3{`NNB?pgcO4{M(`Yv+q))*vY%PLSG)n7bvcO7TQBJj-fHtXZ8e7klBRzvH^DHT zKDncPF{lVJ%LITAjfVjcDDeh!S>$eQSN94w_LiQqtpVf4be(zMRYZv!th;ja24BcgVwWo&!^ide~ z$lx<{uwf}ICpqivPRt0UkzGerhOa>C&$!#=rc$W$^iQ_+kL3zaebcgL<0}i{-jK2r zx;gN<^$uD&q1ng=R}@*L^u@_l)JlKGl{Z`gCb_X%|K0v}XvV zHGBes#)a2OHx#W}yjXr|1Ns?oQKC{8pVPoNxzq7;s33w;3r^bCJfxAbODy}eheU)e zf&1NTMRy?S!nCsD#QdtSc+IB4hmJM_$O;c7|6L_a;qfIhN()_id!$>QYYcit&BB-O zezlgsIBCiWj7-}(k?kJd&dMgw{>Ye+BJ-KElmr3WT!a=>_4{qRMnzql=D6(a_VYpd?-1jtriljUwt$mFMltuc?$d#RJ|ax`bb~ zxF&FyoHy!R>@mS(apy%G7P)gho-tb!RQlPQ0-OXHREsvoJ;PS|mI91mlY*Ddn51{> z3&|_8vqn0=@a{xNqT*2^dQ=5Y&ht0)LD5!BAf!^}81v#4l)f|FSjbFqd%H6M>qJA* zdfK(5=S`f@hs;}wXm)!1k3HMY3 zNp$l~z(SqCHYR>{_w>?{5+GW&gy!3!#-^V(H+MNx8PxZ;%c=`C8DZG%ju?4LynAB^ z8IIbM5P@r+Q<~{RV}~evi7Xlv-tF`wm@$xNW2LOXxMjYmXdSsJ(ID8f8ttSYQ?>2R zX{_OcY7!FPQWE$!Yj~ZTdIwrt7_ki+mK1L8Hif()1Z}LW#%U)bU25WeFi`=~M^;uJ zK05&V!I-R?LjS!KC{^IxO?;CW)ZgkG79}Nykd|BPmA%-+?F6#XJb^ob>eFEpl+F>wB2wE$&N1U4r8yxCNR#LSLhpN6|Tc(IkT{4+7xj-zch zMB&R58_=x}GXi=<@_oq+wzN9_N4u>r5@H0pFI=6^nJpLZIA5#dkkK`^D18$r!dfjM zJ|hJoFcflDhkKwpS{g5loD=Mvkk(tNB0)o6Lfy#7NU&sYB7gZ3MEZj;W2^*+;p`Wz z8Rlb232(bkX-k?lcmjIGyMiJI`l{zCUQt-Tdezv{Gpa7Sc1w$b@^UExg1_u&Gad~W zSJJ}b`0C{+&Co2!z7jV`T;0AmH#e)cwS{)`>Cw$%z?QWVYm@zs(Ec_*P$J6ZV7#q} zR{Reb^yjO@{Q$$K{@8yor@yQfQ+fb)jEN3qVN2vM%F|tn4{87mvgeqwD4~46dXwp_ z)97gbzy14PCt^&aAguVeV|5T!!vOSuJy_42XfSU?@`DZ}S9i9T#7Gla+o)Tj*h{-% ztU=)-u$%v3^4?^kW4>A8p^4MjtaxMlgf~W+6@P}puf9iB)Z?sxD}HL^1YP^9at_U> zf80|qIW28uo_K;7h*2T=(s#F;W3(%Tzc}xn&A%=PB)e2YI&dJg^^Wlt38eh|qztWk zff#8Klzp-Cy1oTtp%@j~v8&t3%INbD<(Z)93w*EFySK@&Pp8eUg0eJ- zMfRC2{TmbckNG8H>MrSKUuGg37$-Y|d7ns66Rxxd+3kKKsNB?h@YjbvJq_iNW1>oV zk8x}S*>SGH%(2|8)jXB*!^s(7ysjp~JHeUVZD z0L@&3B1S$@l0`1FY{eIbCe7k?Gi5ERSOZNXVyy~BcUB)WoorbKv^cIGVN7s$B&{ni z{s}h@TN(&)SwGRe?N3kF z4)z(G7e*Ve0v8JrOGjrM#3i0BbgT+EsluvIj|08F!Nsk9yw?9@ zsmtOW@s{VMf3z2{GT?J01AlDtodczcl@?NSZ-a8a`3|FveUj(qkqE^~t}^Bf)MSUu z6q`7ZXzhR2T=zDH+Clif%ZKJo#)O{3*(xf+csf8_YlQ2d)QOSuiRvPx2wu@9pf1XP z|Gc|L@Z-^GXhj`5n#R@bJo(}Sg%^dr))A=xBJhXtF-N>X_s5gd;Nt78BlDbw*5oZt zUP7c5_wSE>;&w7E?8wuKtQ*Mp5Cg?#Py4Is_bjD9}Ise=1d zztoTHnQi&6p!5Yf-RhTLOZ>5xHJIQ9z@DpDzfkLobRVYM9u)!k%1z*)-nL zXW2va3e)w{eH^`i2BTm;r8{DM6snzUkW}##h$Jt|NL~JzSSIh{=*cb4$t#Mv9 zEWw;M7)^&7DI3`hCfn?A8Z@NGGw)*^*f6_&+vg?FmK|xOgOURMwlakO-PbtCK_>Sn6C$?)aoBs+7Di$*i2zA$|xW$FtYsI%UsvupNBX(&Aq zo6K{8>#l|RtBM*qZU0tv3qseCKQ&vbwGd!p;ZzG`5%~~CKN&c2tdP4`TmA0cO4zm< zC%O;Ur$@Vpp3dM|sK!8=@hOa(EcqXK28?T)*&MIKg^xE9?ybK)HEA4gf~N+=GSUBE$8a++73?UAATO58o4BP+^1EXrEp)v zf@LB#Y^bJd0<3#}B3O$k@EY+rC)G(;BRJh0Z^-m?aXsp=947488XAFfa9HF84p1v5 zZ8b!po{uXyM}hC;I3P6Il>RHw$`A+gW<27ZqQgon(vRtGF^>J9u^|57^MQT5xCs-| zsUA7-FI=T{LrI=67?`0i{y<>6dy?~#3PE;fxZ3ASNg#^_f8NB(lT$68@{K`4i4&VN z6v4ZrLq#~t?#TZ56d=(oe5$F+`s`#>&WX#`@n>$|bW_kWw=zdW@j= z(i8TkHCmId1#pbWyW5+-TyRtXnrAQ6PijT!WA<@pV(Vb(NIS!-Dt!W=iw%{Zb#G9p zcd}5;zHmQ?gg}&Ez9aq?cBC@w8@G+_6gkO5O8DEs(_=25ar7j*xO(g;$u`VnwU`<#l*kCs|?gRQlDj6~Yw zhA@@b8ZlFMoPT%busZ6)Fc3jcFOw`CY*)R{!^-|=%*nqBNB)jz5^08YB<|68)#UL2 zCsa93-D_dqN;I%*o27UDh(~#u%FN^TLV&i3nJ+nA_$*{$I;e}w7~nGQpP@m9RBUE~ z(>(gqGt1AFqL8P=`M{_|m|OVvyhlXW72!!|e9K;stV5-YqB=Oiyg8J^P;|T_J0>O-#gh&QEE!5<2eUrHKAYB zoC1F|)PykJ7qHoIWgNg`zD=IdfLBu|*|00QCwm+%UC%GRVm5B^(@9cP(&_;t&i=mgbw7v@W;T7P} z*2P`f)!p^YJ$;vCJ>|fHpz3*2=;Me4rlQdM@#{m{9DR(vZ%ST4w~mVAyn~-yy$;7E z!c0ykd$YHKy0)LgI^&=5*It!K(r;{e)@oxekGYLWXayK%e~{b7?(D)^?zgDGihvu1 z!c?TA2Ot|odYe` zNA6czd`iZcVTU!H3EV^S)fco=++ytHd!lZ?nhCrRyGWZ)`s|bpDfI`54Omi2N+_mQ zpYHRxbGC<>`hO3d#G+Ms)|zI5r~VKgFUY?eR!wl^SIntWN7CXdYZ%G93uDWqS{&_HRFt?<#B6G%zPK?}%^W}r_b zb0{1kq~{fj+LC=xnutbja3zO@z=2-n;=(quFhT?#colQN6&togp!nX=X;$HKPkgEU z;xGjF%4gh>kOERX7~@6jjT-(3nt&0$Ir}pV4hZJd?Ogn@2g2qiUgmIf%6Wp~tSRSsR7saHT)pPgU88>M8}4=TYmF;Q#X!ed}4?k01VL(RWOns8T31 z-}~e03>mJ3e4#=YHzTy@64RUJFP27c;9WBOkz5t`Oy>PTr3T-+yN5DyB%d~JL%|!j zi#D+7RIJBKBCQ8vC2a-684(rNG3^bOQ^b2%NKJU~9$p{o3~ZcYJ5uebMSKP*$)U%6c8+sM|ktl65on{|p~ztBn4e77csu=eJd1Rg(`X*)jFEMSVd<2LjiTMAZ(Q74EJ* zKasHl2PUQOg9SL`(JL<|3ZTiT@_yQZb$#tY!*=Wm%Kg6(!&&w^MK3Nmd+|XKRl0{m zJ}Wn8ZkXopSwmYiN-2w=i#bBI0wd-0031KsHepeHKlI;Vue$@s+anMD2-8@0Ixz6; ztMqD$|4Gp2_|;xUc`p1TuC!ik@MQA21Om3WW_^qm%&O|zwvje;UTbr7V?4Yo6KX}f zORm9)&@pvE?!h3-5oi`MMd5-7$(KX2ze&3z$>t-^lR6I-co!48uhu7q+X**Vb#g@> zh2h7Z=%Xlvvsg$b`M4v4yh(SirxCz_7SKf}yfOqd_4ODpk&0j_aIaT75_%sZe(hbvIEIFxbn6Hvi%a8I{kNTWX zB>^WZ)ro%9ONj;b){EGMrF$a&LmUsw>}d8_x1e2-Rc!+g$G0C6Fs>Y!WL4Q0elJ0P1nk8&jwroO0J<`mD;yhTlkU4y7 z5#3b6VMD65=D!Ngf|4YyD7R(!;cxR?rtHZgiw6o7TKu;}DC@TlMYUh}!UqTl!8jsz z<+%??_~c{$q=VnIDU~sE@Ac?_gMAea&3_<_yd(&zG5kgJEaQbcdMzTk`@o@Vp7wzi zcBM;EY{R>3pk#81iirCRxwWdlCrep-eGK@OO!ilbIhvi5Q&d)#w#qy9^*uXiSu-Xs zKjL?f7^G{e7OuxRA|R~n`mU@>j(rO-y(VO0N!lj+fDV6L(60Lh$50Xn)>5|GT zB^GpB-GT>{t|?ykO?AY7hU0fCw3#m-_(B*8`O8iHKJe#b*q-8>cj+PVzZ`_3pCV7v zO@jEgV)~zv=m)!BW7PqhWQ5->nTLgc>5+e`?7`JJrPAt17`mI7+svv_i-K0s=sQg3 z&|3?c;m3K`ODO$=zJqH2U#?+Oe3%Z-=}z_^jO2{ZYIVfx)s__Q!Mqsnz51ZqNeg3i zbgf5f;hdq73u!Jl**k;Pfw@^o>&9zDe`@)OD5_!2M_fEjWMSZh)7^0`jB7Y{XvJ+R ztStipIk}9X3Ve~Em1l&}>^r%qS>8*-j?CuA5Y=|E17F^qpQ)CPZFdAsSPsy^|1&a) z_PZ$zdpZ9L6XGmRv^Ezp&Rp4&yxH(-B>gkj3efg2c0BDdQC9*H6N~9P(&cAm2&2nMQ8-~J zJ6xW5$bkXTXgNIT9+R4(YBix-`dk9AGs^Wv_PUc^rQL5~;+#z#{rq|dMQ-%c-uChn zV@`36HM(Ewn%{~`kiY8W#VG54ZUu46T7I^fL5P-!v^4UPxhzr7t{?g~MNj_>sw zz1gLtttW}6*l&=yTi?={?eiB!y!Wp@*t(_!c zFU{2%s<{@<_G)Ee2rK!5sIzGe3QA4Z&_Ca7B7uC{=Vs>gR9N0d7?>i(M5Ul$94ITqsFCA(n}WzT*+HDKap()oL<9;(E)QNtCvV^ z%d))LIWokC&j@!*6@G~87KY;!64(3S=1XbPLtvKLOFfoOW@MNpb07@zo!vWqe2(Aa zUi9X8Ub@I*`wHc~nKPOhYbib>iw_upv6qjQJ3@*k_IT^L%-Yo2|98 z(CxOPD6KWb3yI3UQ*pqdW}b$7kdnl9GV{WH{~vW|0yG-5@F9SrTdznf+VcXN)59l2 zAp1ivV=Y7cO=dvlZc>|}-B<98mrXA=I$JDXBeb=brobyb4AyPgO)6+IOS=Z}@!s_sR<75&xiAdIBzV=hbu*|N zZd$fwa8AKCV*P)FopoH4>(=*G6h!H6Bm|LW=o;w;1*E&XYiLA7B!=#iM!LHj1`v?$ zmKtK{A>MKC?b**h&w0*!|HCjJ=4S3I*0rwh^;>I=zEe??$gcv66kk5Rbm$PS1_!R; z%P8;aH1B~c@(WV>=hdp9>8gmdZv8?y(j$X$f|oS}R{Hk~!$QO^$x8Oy6OzyGWa_Fo zmShhqgz#!e2+MjjCqO++Oi!u`Gn{kj`R47ZEPVMHit4b)GhzCNcus|sJ~q?HnI1hA zJ55UEbh7!moEc*IeF}c9sRDO#*AfaF%WgXqo;CWu3C&E4*MTIG1JBEhl6AA>f-d<922)3uMVzcMJ+0<#lgJou6mwf_ ziCo=N;`GOTxlyfKhDKsbt37omtjj7Ew3Cv%Ez7H4Uveiq-M1h1^8EyCog?xvc-96f zI8)0gp3>BvDQk0$D!iDo`mXt|!=kX5E5YIPBPEx51JT9&Z1?v3#zv2alU`UbNovpF zzC*JDmKPjn>#$@E60TSS;ODJ@v7rK+1JQ?^8RjRt&(v*I{|E5Pz>a}wzWRHm>h3`( zwkJ0&s90!-?WIs()`+z@{u4-n`kEBiSKY6cqx_Ve3cWA+YI9hr&7s1(qq<}7^QS8h z!uV_$(~+H(9GFC*`NvZ z-`SuTc`So4KbIdUZ5p!{{Iw=5w^+}K3i0E&H_~1!mK2)RNpOOM zqdDxRl#+>a0{glzF>fRPQ}JcG}JGebaPDBARP1W znDJoE8|u}3F9Cr#&s;(P#d6vMA67bt%%{A^x|t0Z&Jl3lDlcx=wr#Zpsb-yw%rRf+ zCnq8PShE`vY+R+Be3%saLoG!9b5}5hV*F(I9J}32=*-+?g2-oF*~MOwElvS?0jPJ zsOWF!U~Q_#Wk>l>=ew7v09mEJ5BxGd%!JZ&P_BR&x;%wA?Vc;eN{Sa<5tkQKX7;%9 zFnpJ)s>Yec!2Re(fyYBRu(j3qEt3ZG1O65vBqD^9x~DJ`=2afGR&_v>=aALe=V%*$ z#WaZeY05i7&GPaZzJ7QJZfm1VWzC<;#UddMTt3RRBtLK=dHpVQs)}}G`S$Fg6k{1* z#Qy1npM&OyQL7@953*CD7lRANn7g-3R?hXd<9WwpeAxM6vwm5w-48zYzPVpP4_@N5 zM^d^!P`VsYlDvVZ*jKi@f0z#_iUPbWA+q9)GSpu>6FZhOSaGD$z3;|<`?l9zUEL^U6cOC41TF%JhW$mVI=9wzL&CP&y zvfiZ;E(u2XbP6w|;vEXfXPYAz**|Z93JY4jrJH4^LwaiEY&-dt@x{m6t|KN%B*80cj)cqS*a~3uu;@AHretmEje1R`sR?-pe>DP>1GC3v{Lk}v`JHyKtf~{v-8Yngi(4*W z)8Ut3bj)a+WxlC)($M-uK!`9&t3Sy;o7lT8sn%ckkn>;pSrfFCgGW`bE;*3Ho9Aw0U&oY}gjZYD z<0@Ssk7DgG>Ekp<7%R)ppoMbAJ)h)>@|LZ4D)Y$l@zOB?a^Jluv<3yO@ma*%diH=+ ziRU4L)iI?xcw5Py3@pV&_bjrw-$(4&R#egnjgZ+rUyTU$28C@F_uDjjwid3Mm`Z#- zCy3Uc0}O7@n)nd>Ex>uo-Yr=DeI5^D{H{wz@mXg9u(Qdl^r!0kY|X0`5~G;yb;qou zFA>H_i)?S+OX=$&G#vks*SY>Fuls=PtAju9v8hhM%lgxwpKALDCpr=?-NX;I#xb9O zDZM}qAY)71%h(7toskNx%bq>ohs(ulUkCh;bdbd`!rf~GsUpi26wzxB$#3Mu9~f9!8lB5 z;m%mi95T$jl){1nDuNtqHevbdODk^zQ5f_=(e{f3f}R46dXNPhOfgOp7>4rHw$ypr zvXNQeig`J8Hi`-$y1Y>jT~#>OzjZ~_3_yxR8dgn^loFI$|#SWcXk)}Lm` z{V0H$Du|n#<7Dx^8lm)=nyCjq{~sb8qHG4OU4;%F;V5a>$mqE()NA>@Nu5H=x7_Sp81l6aA6WJ`YHZ(IoT~U{MUMOkD)v6LeDqAta-Xanffjo{DSTf@ z9WeNBuq~x}nj*(@8@|yiII?RBKK3324HhN;+~+C3M#jb-8@@|e$}aaSfHqgP4veEGeb)Y9l&m{?5anFJr z0nWZ|Z-2#n>KwEx{?-EgEB^EGIqH&~W#;bF3?3G<_0)I5x)50Z$WzfBVM&q6_HN&Q z7z)WQBw$QSjQ{_DN5pymfJZcq+gw)eZNq(f7nS@%NfN8bE$4LKz9GMTh>m1_9Nc^j zSDPwhzCO)!wfP{&3bjG6>s~0Qy4UwoQ-MA`0kHU#t z%cAaN-QHBmeBA^ps|-&h)(b48hd5{-XFS?9X5xxHh2Pp^KUlX!^G5R+t9v2}etSdxe8!S0=gem$ouE z6z4C5(wI|Uf6FNbQO5uYTq$ig(U+SvGO$NGUvjsUoW&-9b;;+`dYUi#$UolyErP@-(2;P$oknktEsxVXvd(1?h< z#zs#oKTRH0C2DG?vr5~ZHzpjQ)cJKOp?Bhv?btnQ3Wbl)=PxDlB9q8O<<5upOW%%5 zl{zmSo6w>dWGqVA)kF*b{wf?G!Pryms3?v{G}1cdA87qhkPcj9_pg!s7PVy)SZJKm zU`ciUCcuIHxP*ClVt z$H(_2z$lX_j176KLCE*7d;IZZ!^%7z4mP{}*Iy%E=p4ugz3GhzaQApNG;L?{E>>)l z+;uiuqj}eCyc1GXD|Fej44J05As}5B`XTi9-RS%!jp@VbtEPnq#jHCmhJ3@9?OC(8 zzh!usVkK6`&)bJ&7Jyi#tkR~ZVSN@L`t3*q+b?xe@po`(EzL~ZbO6B!mh zlnCWnZr(vmwxos)Uy3CxnX8Pu7+cerC>MvXXl74QEuB$M-BvQ<#b;1VRTXvw2UI^F zzVC!)uC1^LKV@r2qXSJ+XVEpH2`35OC|yKp)P&!|ngXja6;^oH>fzhqiX3;=`?DhQ z9~vr|3W`CAx}B9w<+e;it%~q@*QM=YgyQdK-vZ9qKvaTXPl|+42J4qy_6+#_rbx76 zGo-CWuix}gPZ-sN7H&9sKwoBeuJyR0w=zSU!P-%P92b-<7+4Rh;^~Nr`gqCt?#PkKoZJ`kIgG|~QYdG+{&S1=ef!8s>AM5&4I!bhq=$N`oOG<2 zG%SIW{S_^<5KRin`6#g;dQXhMsZh15KWPdb6r)r|UHMGoFt9<-E@{FszkwH~>8B6m zzCAsgpSJZ=$v}a;Ay}wP4$KuOaNM~-MMj*3&?;6HET$+;uz@J0PDMGoJo(;FD!9ng z?R4;&a52JYe$RpIbw`#RKmd{g(j?iP0ZNbJ1Kj(1bivaVttsDi#oY|g@aB;{)9*uT zHcL&-k@=FZtYTEa3QF#nwTlYwVC1#3y?8dZ&-kq$hC?xrZ#t@I+O$bpX-#QY){E)N zGLu-h5aow;6Fb621Z!IsJA2!jf}Rk6-Cv&gOz;u+uSSa+J4*bXGfJr85`VaMrptb_ zajvSyijlk0MHQ&0_cf1h*_ITOT`N-4F!AT9dg z=J+D*6Mf*RYu(!;sPhe9nEm(sO~tgUNmO>BHFhp!rH-omzUP@6;ks1mjrTav!lM}aM+?A7(@%dXNd?+(+<()eWE%=sCoOX+tmQ}Du% z{6G0UBR2=8gw2QG!sm{2_D z;69PIc~y3|rL^Hb<1f*5Ox~=&E%UZhp*Redb^V>my) zC_M!BkG~DgtHdSaU#E4j;~*xbq@p_4^@Wc=BtagX{A#cII*H+(%X`ANZxwQTRXZJ8rKPWAiL-= z8X*JqOC!ClZQ)9Pj0SWwX?{jP=dtS>h=N@GYS%NxFgG}FQ=G8?Cf0pm%51q{XtdCo z4hUa7uss&d?uaahX*`fVz)FVd85 zLFs?Z9de@C|An_;^ghuiw+nr^!AS?{zFJ_mlKRp5sjr^*jy+zTzFqxj5XX#e zDt~eh!viU@4#qZ{$i>i01@|gim&h*{8LK_T$jA@E9w2mzu&0npAHsH? z?6;jxAF6SA>0b+>urw7lFrK;Dz2O=d&Dt$vJ?iYE(M-0a-E_@ok?aiK2(ODG`7Smv ze?Ls=lsuA=LhsymV%+K%v;31kA)gW;Dtbhw^-2m$IIqce{MOCP!NadM4Pt^gN~iK z@#1oCk$(Nec0O`ZP4sxLZ)A%1VML_|a$KY7w#sQe8DUDS9BXJuFXrFw+*p?B&>EXYUq}|64IuS1o3qod zduBwZ(x{O@X9${m{hcr2d|=fX6C#P)20{rJf_}}^#MgKdA)$-rWmf@FI_@l(#4Jo_tmcBh zE$V+5>Nz*y+H$<94(eNQQGPTEwD^QYNEkMzD?280u_n0d#;t|B$Xbew^nU+xxD6Jn zf2Z$zJZPxZyT3Ihu^Nn00FyC23kNie$NfN4q%kfHysOmt()cL_iYsQ7MY)(Op_*pz zJC%g~9x+@(JDC z24_69WkK5~e#k;LohYMGfZFn2^#_KcqQ)aL9FF1kZ@db(FG2K8EfI~1DTym=qVg84 zHhP13O-0Y=pLPrlJ(TZlm~nA+Ga>~X9dj>!4zxb#&}>O5IehGRZ~MGq+bhY&?%Rqu zls$rMB)8J_d&x1-c8jpQOIy7xn%npf-t%BrZj-8u?q^VaM_k8Xxz>$1I>5w42!|H~|* z6WapbPe3%EBb>r^&87?b8N`r^syZcX*R9vwcYc|gUg6{T<00nE!=-pEvYsv#&8 zZNg#uv5qyS8)bf#{$|3Jm&~BX8&53~%e~g#tdwb$dSgZe#%)+@<;Z?rCKtZU3-oFy zN_bqn2ufCZe!{xs+&8AMpiWnrruk#b_d{BJEFUT5YHKMWXx)JZ3F;S#XrPqy=D-d6 zFnZ@PQR?%<93iTZ*$9efu%U%z2}`uO*;h!ytG8>7X6`D9uAc#gLz+=)eplz#pJLJ} zLS|!>>>MxHE-+*IyB~j$w>Mk3y12O+kpuRneDu(-1iO6Q#rkc8-Q@!&edWz^OxdOl z$KGnmrl7m^5hr`v7(HtK$-tUb?`I!4%C#hwsh%{B4EMg&4;L_-$)gSRgS zEy4S#Vm^8vN`&FiytoQ@c%l528DFMNKlmiP{VDYgdU3L3GQ9=h>GX*0e*HW}aVh^Z z%pdPO3(8up~;LWvgT6ZCDRvzCoc0nP((W$@$Qo%N5h>ks`n>{-mSZLnSNUE9c zk-A&0L6+7)#<)Z7)7@L17CwIl89q@|%b;A;9nMJVNO$3?`3~rvmNY*Q5oXaI(H$Zf z_edHDH52FGSw&v#b7mkf1tqQ0(mghwrr1#OVv(6i8Y^C?{FK;DdL$gJ#QNLtQI`Vf zFV@k$&C0fx&MG`y@K46*!?(GsDT+5V^q#xDp{rX=mjC`4ncS9tj=%hvj)ULkQp6fz z`|4C2az0Yf#NxZ#(@}kA=QgeXxtUh&K1U={_4ESpiP;`e&h4>Txt+x0bV4iU$XIm7 zBx{Vfpyu|oBt#bya~%uyx1zsKI)phBv*}v!%GX4U2CTdpDZn+DVk3WWG9>83j)7QfNU9i{Y*d`uP+ zc#G4%n^RT91hH^Rzo8%Z>I;6F@FYq4poXr|P7X5&4HcT!5ID+f?J@nQJ4Rke{uzNV z4=vlYieKixcEDbAzP;dW8@pyxTxVPRM_ooTvY*?_%0Bs&wJGTJnP+bysY1PDiW|V? zp0iyyoI7~A_-EB;vmRF{0BbcA%G)jU6IPP?Uo|QL%)jqz4iZM08wHL;Y(dNIfYL4%IVRzoXe&FWC(u7$` zZD>pTRZYkX<9%b>!a{vb)p28bgUZstJ`Bp9-xrMq4KnoC*Lf5bK~o)ed@gZ|k8+h` z$4;94>1y#~9~p;oAUi)sl=>LZrs)`*BK48)%{$jF!gcdHWtE8la`L`rX_TJ#D$JdK z&5js)diw3g<>g;ySCRw?>^wg!-_D8D1dg9@O+`57ixh3L*r{93ZcDyU0G$>LA|@LJq6KzHkl+=ZerOtuk{_I5a4Dw(Kv^R zG-@fT=uHKq^6CnePDbN|6z76_N6&#Vr|9U8mcZ6~}j>CH-3z}Wh zyy```2Uydr@6M~MNk2KE+B|r@m1driZMTRVpPyU)YAUBJ_tQd}eT6{L=Pgt+LYISu z-peZ8!n!;hj089qkUq|oL73NJe0o;Y=UDiB|2EQ?8H(Q5q)w>#&An}~*0Qe3)0aB5 z)7DdKx3J*neRD*UoX26(eV*Gee|&ClbS*6^rdMS82!SI0d*vy?sDTW|x`B7orsnL2 zw~i>Qz{c=g?bgA7iM-klm?M=`$($Ajlqd3d}O7hraFCvf0(xL6GgKO z_o6fI?J6K^jDU)F;c|vpj|bj&s|^P?Vje%P)li-v4LdoC!BhJ>uY-qQd*TY%V^F9e zP3FUcTl9XspXR6+OsWSNCcbyYO}obby*an`X9qG(a{H^5saaWB;bCJpNP@6ypzN(} z9pJ7}V2{A&?X!?DDkU7KPqY*vdgXnC{?U@m@D$?nNrS%xb)}{0bNW;0lQ9Uk)w1uX zktGcf!b9pY*kC_mV=Je(s6dpJM&0~ubeyO92yS~rt4vjHHAU$m3 z!G0CIzeH{PZvqEK@%NRcrJkmyVf)bigi-p$o$b4x)IcflXu2iWg<+c67-GKkDEihW zS$H5@4Mh3p(?qemw~U^=MZ-fE)H03w!u-Rh4UMp*|~KKSJJ_nrnjis3aqy%b`s;{{^(uH1xC4qstkIU)NV^T29Q z+Io6DFoVQ?dv@aDd9;|Mc}w1u&IEh+P*iS7eilI!uKlfPrGt%XSLUGQb^+>`U+LU% z$VFE;V_GBBlJ|;u8{tAuR@alFi(3QxHQeU^X98eMl277P%WxjmiO|5k;E^H)b>6T4Gve=4Wv zJu@CLy2VB4^*T*5ZAkBry}510P&N-RUSmMl0v{kj45HPUsdq`xTCrmXe89F;vrTC+ zS5gDkJAKAlFFFh-j(O5>-(f>^oPe12pL1@M?gwf)wtt|-D$!xyPx#QP*{bVj~xX>f*ehP8SZ#4;wpHas6dnKT%$a>8IiT$ zsj*$i&yD_}wzc7`^wI5JPssM2A1E>hmlbATM#$kYYpwo>c)(Y~6+U2HuG2>N<@X{} z-+@HuTgdajxfmux;G)FlSIol44&B)G8(Q)=M33{Bs5_=*&X#?L>@T?3iQArBq*L@l z9w45w}yR+ICIABac5lseAmm#4uBK%d(fz&Ansxmm9HDO2yH0H%6V zE)+TUw}78>TuVIcf!&q_HC`~w%7yx0->ZMaTLsX1iIQzQPvblKeOeFdi0Br_#qnG@ ze59T?>_moW@(+wf&2Kz#n%Dw~(?I*)a4arK&gUGWqxc)w*Zcv9Iu>*-Kc;IkpZNDC z_sllCgH~s^uVAal$YpyPGp8;W2J?$97e9ycKFhV38(=YdKS?1(X>!Zw^p+WvZtv4n z&=Y~NO?xapmp}~5)8z-XK4WdHEeE8%5@okcv(62Di1)?Cd*`oocj+D2W*8$NKOW4% z5Vg82Xxhwh>+*7OTipqv_I@h{=exlTUY4{Sh>{Zm2AM@kyGqV8E$c7h(!?-raPXQU zgJA2Q(@15cBY}6V6GtYItx$qzOFj|6ZTF69-l-+8=g*BhQBT~)XWx#Dt)D?48uFrv z^tzLMGj~&PylM@WV8P8+zpbzGhtC5)%eBJVG@MpRB`N##uXywX*njpmJoLbcE{}~H z8c*U82qSJypFwJIspWdxc)`3RJQe1e%VF>rB|He~knOVP{v%VH6`G+hT}w$#EZOa6 zUCj)q^DJg#NrGiZYe$xYGUFA(wq$K}S{yFMSmKAR9!Ug3C9bL)rpF!W-Xl7e0%SD) z8%=FPJPD8AU93JAY=hCZKvPrIUlsmR^%+yV19)fF#m$Xp@87P_e9<0JQs)rUgk3II z@vU(l-k-G1^0+(;P~u;{>4PUNH<~9p*X->5G-yA`X@NNf0gj$2nIqDz<@7*|8Z%Jb z{4f{OY*QI#hf)r=CaeIpwmyk&+*!Q!s(L(wFVtB9iI6g(PI6fO*wL}|jUhr$Fzl*j z9ud8mG%{GTC&Pb7CqW~axtbv=*-SX{P3M``K5FCN6T`nx{Qhnkz#S*P>~``@k==ri zfvLb0wuKihcJX$41!|EnykbCT&Io&Dd0_Ow-mE*PVg)fI+;T8SZ>FJCay}p|uZhKl zXrl=|_vmlY&*l&X?Ao8V?f9lz^3{O@*_l6l+?c(bqA*etLBZxJHCt4Vwq)Rwp6Vbr zDb*Q>_aZ6uUBxB5Fe$g-Z4JEG6GWA*4~cWsQ>B~}6PdUQoC)Oop$$z-Syfs)Sl$Z2 z$M!(4R#wsMJg!PZ}6t!b^8szH$e`eaASM=>b)T#IX%k^|a59=%bjR%_Q+pLhr z$(qUH=}tbu!>gOHhGXHRblz}bVgX=W=}XC8$LXSCNddIWcdss3QFDa%O!Zsl!x8e9N;I!q##=ESam-b{fU50c{0OYb(F$8Y}%3MFN$_x{3nUz zN?{2K+M2{&t~7r$IHHHdHdj!e98d0d$q8M@@p?93%g3KS;@WB0VWc0YS*NGe>s(ru9spDiJq2l-!8E5F{~CAmj2a_r=Wo5cd`cef3S4hh$n= zS-xxQEQdC@ylyotrLD29K;Ve}&SOk}M>7_9gbPh+`wW@&Dii_@yiI#Qyp-TO8o)X{ zH{%k!c{J8Kad|dEwFyNeVze_?%9YVwx$o+-M1`E)d~Eie9-Pzh_AfSyd6f}V{5kOY z20W|2OSaiSe3`#E5RZ>dlz#zRlk>~2U*tnJJ)-uVSY$#a&sn=Q_h2syc=&+EKi12y zKQNTrd3%l8*S&mm&5bkbvT@G)CJ`Iw!}fPE{trjQjoi_TJ%!ntsgDpgz4>Ga2bj^f zt~y29oaFB736{bmrSwa6Wk95ci}pK)B#(Y;2ZWKfoj-NY1-)yy1=T`}+yH!QGLUPp z2EIx#uDwuKk<>^!rRq}GT_uW#ksR_~f~lj?wj~o2$+Kq`8chLwu$ZTi5k6q14GuPC zDCHsoaVL#)%Ntf^HEPOp zGfF?0FdGMlc!eY<1vR|j zu(;89%cj$NUC^>L1tG#mQ`_9wc%Z)!x>3~!Tpxrb2=h$!O~X9ztUT{z;Wr)+aO=9j z=4gc>zAgy_?_3f2efU*Gk7v<~6=jTirOb)WTBq{pC-OjSGZPXZP4bZ+M0qHD{$pVe z=1$Mg16D&4==~*>+<~>LL3NT6aihPr00|FoaZgch64Fwz-|R-?-R#qy+s@y;l%XX2 zjrEQYSWkxXFRVA%oR$bt{ZLg!bSN}H?#zAEF)1}V0pc;Y~A zQzhxcW1E{1f+=xVr~NbYOF6qLxYtwApM>!`asL_porp*V(EVHNZU-W+5c0B}S0M#m z&6uK3smvJm3)lfy4N}m}o;o^q5G{i6(#RZ&h(@NWs%Pn<5DLGXbEF8>T7~^qX_j8Y z@gYW)i8uHHzOX|w)bpI8!k~)z@o%A>n3!*Q{K$*!7Zg?l7l*xEV! zSZcVA=N%)C79dF1M`vGW%cbk1!XHjCS$-1w&qp%KUwQhI5KkoHFMlQPeYb zwp+F1nNf9gza`(hOXAd&MPn|^H zMndKfcRNXz&H+sMZ#*l#wngUi#Y?z!LTJdV!1gd^??Y0{%j(#Zf%CLf{`v3;_VA=a z>zP>YTdTY4mFtFCoho?TOj`a`^^5y8A$PLHZXZ)J;l0jEj09ohcPVgGw>9N08}E_B)x7jt_^jY-JPqLtFFh9J#s0Zbb;{QC5EQ=QZqoLemR^s{0sEg5svA&5*uA#n7Iy zq@jxFr7@}EqKHl;S3HWD2zL#Vx&?REA$vF-skL86Qyg?Or@=|USqP&v{zBF?(t5LW zYZNjX?@7A87hQG!f--@5yVUf#Wi!OKJxrQjXdx5s!IIlz3}QuWSffIW=DB+#_5F2| zH?H>Ex`cdpyjU*k5wo=3j&>-M0U06BaERc0Czn7B*owkJF4^qs7jpc7D|U}hwl(4T zJcAS`aSybkzo_ftI!hE#^)!Q99#Lv7-}E7c2Pk5Bc4kpQRejpYjXEE@-pS5Q;E9y% zPj*BxhYK^DM^YS(wi9Dh0pUDRV}@PyQpk)0!}dY#XozACE23wK0Xa4r13J$BgX>Sk z%yQ&&?QQR@9N+v9Ss_q7Auuf3GhdNqAVOn-V|6iv3pM+(eChJbbrHrp3z}kYA4EjE*cS$ z`jwJHs4cOv*4HMOFo4|H&sn}|7E5(#)? zGJ7#E7nfgu>R!%6NEHU}93{}HpL?|eCM_a98NkLJ3-R%7)_ z%%Drls?JKU6((i9H!vICUCCZ<7P)&#)Bhhp92s)!j{f$x`$uJMEky-m#zn;#OTboS zv@mH^er(p4rFTD$rRS0u9UbzUX&3@^4j?-fv>&|;iB<>`-sG%5Wj1c!RPpN(5iZn* z^cEOGSty+QrO|tT@`~$8+|Mli+SQp1zJ2ruK*{6Bd=Pk?ezC5w-^}Nsfv%cCVaEoM z(RF1G9Eu4^A^fEIKA3BxVRx~t(su5kI6b33%ONE_-t+bAYxalq+`2)2s|`TT3OiF0 zo*WkXf$8VSUOPLxS+&KV2e*n`k03qHRdfA*d()iWjUV2Js)U3p8m=Ax*q8x+%Gj+0-f{iP9efYiYl5eE}WB-lPd6`#;=|@*il8(9`cdH0|O1v3-@;j@D$bCzJ9aY)kqQ| z?;7!nz+U!c`EoBSM-XHKORG}f%smL9fQuRVKe$?7110uOzBsi?8a9#0+6R2vD*+;l zvTT!S%FDea<;K`L{3I7)7(wK|`NXLVMa>}mH&p4TJt?nvwTcwQw8@v}Te)Cyg zq~%H33Gn{-{S(pO)Qc|d{PLHnK-lHIFMqrw)~{77z)n)l6Gf!f{MY4V`*!VLybtl= z4U(_j;C`-wcGf$y*7KFR8KT3l4!{370xi-DRxhlX9GjfaNr5aBh-_!ej^PKUr}9^W zY)29OCS7^>IpV=syu&$V*>PLfuOpzo;M8Q__j|FHn8?4OnR`%A$8T-iPW@5jWO<4{ zuqI|=%A~vVf3dXw_k*Du%)s?k2!Dd?|f>{dW%{+M(dRsZCG-R;Jm=b@Zt zk)T7QVx?4>%re5fD)7h_zheAGwDZcVINQMNn+GvTa?tHn^r+bT9pJ3mR_e#drnks| zj~}ZW9(xKLDaldq2XcH%RcR6-7D-yTm?4O6ndeLLi*1hg70i2rL&i<+H^Eo4CXnRK z0lLh9(o|TH-fz33SW+gpJ9ax>j8YoQ9O~WesS6ZTiS#5EL^JE!K7&m_C}P(AN9=q%rDUay?fjn*9eF8q{OUtd(`q5q`ujjaX{@ zo0oK(BeqxFT|nBVZkQQl$jg%mfYi)uDX;fNN(Z?p%Gj$asY)=cmL|9$?PR?XIe;Nl z`p8xJwr=@k-bX=0g|AgTWxxj0jW8})I0vU4TWTeGK>tLNxu#8KoxV>HKS-I z9n3|18jXP@3BDNyD=CR0Yn-8TEmxfA&K)k|th9jQ1eN!T;(aF36sclrRUE+I1CfKD zf}0x|m$#Dl?eHq5+uQxeY{%gFb}`IS(*qu8&RyYj|6a2matqVQR?EygQJ1dAcJ zG>gjUwnW4c!#*dkBDIwKh^H_;M4^1Qu-5GGjN#%IfNAQfFRjmfHF9q>5IJfw10zkp z&YbF5_w9{|{P-({+(`4RA>`<+o8o6~RY|~ji~aF=g&C9j;7YIW>rcxz1ZCQzl|P6& zZ{$6-tr_^Pv70J|H}``Ml+bS0)SdUfh-aAvanQ6AvQA{>*F=12W)hx>8BKb4k=&n< zp0e0?tbP|ht>}HO;(=174umYq(V$|S_RK#-(j8XyOYVY_qZIB}_wux|^q{rVzH*~_ zzTJl{z!M$$!tcf>e|6x6&muEkGn~wCmEOjlvg6k2hVwpfC^C)b|Z| z)o3t^GF}c9B#Y6Z{K~K4H^~YM$?=MpOS%?}FaGS(DAvZM3s;2cMjT75{E}lPS)*!J zZ)_^NS~FE3vYXD$ONXNOR%>wkY-<;XR9i5OnBE^Nl2O4lA}gY#jKn}^Jbu(|UC2x% z5r-?c{7N5i>=3~fgpIR7YSYvWtwroeG<9bm=YA6s;{@uj$*j0;+uIQ051kO{rU;SAgQ9 zZMv9>V{9Cw<;^-)@=Qal_I94vagf+ojo+TXdS#bCeNIKo9du<)@xpA&TCj!dV(r#U zQUj>(X?Okt{Y*@X!4?^%iB~&GO2(QH$pb(`7yg82X{3(E$78F_&960V)}wnmH!*GR zQ3cQ9Ff#-9fh&FC>%z>EqJ)RdM=8+0r1h0w+y6q1^KW-kWnfP=Skj|xXUlL!~( zufyswHHY#1=KAvrp5kmjiJUwIk%J%+^u0rQCB}Ve;t!Xk zzM13Zg80bncY4kfB@Lu`S3hlT8Qfp$%1P?!O%J|E;5?3WQ8W9vzUQBq67SFzjGsz$ zaPH{F*yl#^;tqwU$`C~G(rdTjL^cdzoQM}z_@qstA%+(R$6*RD$Li9WKd7K-DL#8{ zHQUS=wDDc&2iL2=^|w%1BIHUqqoQf_`-~+npg7*gYf|p3NkH$G-rJegaQQ&9hwhy)qJ#p<*%f6~nM?gwK7^`ZCBuzgTTR>` zb!jw|^)`I%d_6PphZw6a{ z8yylU4bG0(Z2~hKIT*}}rY#*QpzVBL5AllQ<37!V%IGIlSA?UDMA+(UUeGgFl)G-q zU||!JcX#bd_4aqv9Oj3)=Q+5&jIDM(XyxB#;p2yVZ1Dm`Uf1k2w2w!>2D?07HAV#G zEtDB|{U^|-wQTe1Ri@zq@)ksinoVH)=0UxTxHprpi*t33*^G!wQ?5U`-&M47cV6^{ z`Ma}eLXXw;Dq|OP(lYB1#!c6nwgHJT>yn)6ii`qH3YWM9N6)ZM?tenG%=>5dY-@z|++jb111j>VTPL}YACMTUo(z?+fG8VgAZRgu)8Q9Zn zaOHY$cD|=~1*448vpv|y_~Le${~G3I#G!&ZGO|_)55Syq%qj?}!Cn>rnDm`9pey8m zleh=;MC*9V6`yB`93ivqnD>TV<)fO5#+M@M1;#Wl(!-Z$JCh3(BU@1KBL%O!p2AJFw+LU4HsavX9v(`{p;fgbGPrH(2jM#G_|t7!FPh`bX0;C?RKg-T;^gA|_`Jz&(& ze{PQ8#thPq>94n2)WkLsBmMN|QYTvVFISVL|DS%p&YZauF7T87E5kcvH3fhslrJ47=4#r(-`ncx0FllS{>X&4R;1r?xOOSfl;nh`If^P&5>T#UD6}bocLCm)R?NpGMZxGh8f|jXDN4#Sdv3Ia zMY@`q)5}L^TE8LYz;DYYYcu{~W~&uBXcog3|@d3=_Q^BACb+_G!5CFR)FUp!sehc3ui|y3zw69N2fPJ z+L(HFD|5djZwipH^RJ^z6WWkFrCrT(sAN1nMLs_>fs{E*pRA`8WySw3oNENen8}yD zw2Pmvu@3R}Rfm~xnaj0=I|ALOC^ptBHy3JbsKU2Qp%&OXIl-hZl%u&W^>lWhViK{! zbiE>h2Mx5A7Lrv?LnKBx_U&+K;g)X-zo)2U*Hus*-JW|7vT&8U^Wn9IVB@o^pE148 zq*|D2PE2J_1YX3<+bPglh$CfiliQNdc;FI~bKkT#F!t5VGw>>lg0Tm`H1Wh>{Ul1^ z&^bL(oD;AO%hdb`C+>>p;c3Hv1kk9Xel+^LhCq7oQyhc~r9e<`=N)FWNUCK$IU-ga<>0Ox zq~(wY9|DD>*ujorh?a|+?y(L@UFSSue*F2rE{9e zP~iPMB5j;ECSwRa0(68C!=#@EPMsKUr1N%!e7%2$0kdog8bwDOY^l2bAvDmjwNaQS zL*{9Fx*qGvTK0dvDV(Y1K=V7T zh>6_wxoXP!UVS66tLv=yg4ZU1!t+TPA!us$;GWJwa?&^vCKGuo2%BHEzr zb7a(8_W5k;?iVV+pKhpq{BlS}Qz16Krd*ghq|AFe1yZuxjZLI@l$3U3=M@y{W6^J3 zw_OQed5tqAiDNZcwf#01J~V8&l5*$j>nruDCU^4(XYKd_XA-wD2E$GjyO%7(x1Zz^ zqq#Nt4s>?z{ML6)Ykq#fq{)0p=N9r*0wx%octkDI0vVL%6J-VkXrL0RmKH*UI5Q(c2 z1y>E$-~NEsYyLJOL*~p`Z30r{urirUn{#(O`H5A?%cE`3_wT$i&*D$P8WK7th5os< zpG!IGA9^)RC|%)F&xm8&lZ}&exziD|8F!SFSZ;~>YY99Z=DsJ8PrD~sLMk{L?QeRu zzUiLYX;+b;D=4HCZoJR0_Cg66dvFw}f$@@`+amRhU{d-Cs*T!)j$lZhRwZD`-^4;!o0pIyNcw6k-gsy`uIVu$19DWUt|s2h7# zz_J|Qa2cn{_m?1!EYtg!o^+|;(N{S7NVjqPwg~NagoeEcdZN`FP0ughq{sJG{)M?k z9u$tnl(aP3iA_lHJn36mdN3eCK3ECfBvIcNlONY;1pO#)7L_Nx=BW)dI(CuW#wRJy z!v~oAzYUh@U2!Uvj>@HZXai7ZueCf6I^Jv1HH@$)Ur+mPE{3PNKckOEJI_F7N#i{g z+>4)L)QTw8?VD!;ReHz1IRdh=)g8_$Kavg;P>;p=M|~VgrzLt`?cI#8p?4d1Hsu-I z9wnI?%`LAFFjy;yKnxN$%O$@e%Sy5}&qa1UPFPQ3Gm zXFWXP-LAoh#r;6^g?aQF;^>%zV3oS8<{12M<$v-EJ zB%Ynk$mrLTu&u;npS0;UR+vZ2FS!@uF+#_0=H)+w#$p(}G6SMpwl~)Fj^eT$Evd zYG4e1012c&BKX1TO<0j1W$}nRUp5k&d|kEOZ9_n@lLs%zeYIl04@VRI_+D`&;~ z`SRP#3e_VspD)Wje(;b1?OPRakPtgARzjpm=GG)QJl>d#G%{)hAjMgkexi5B$uite z%R1CoHIuqJJq?w*aIf`+d&~91OJgV1Q24@DkXz4&3`;)LjLSPDZdhZzuGlp?aEsWy zk#jqA?KRJ&br)Ecye#TehQL6kFHh_mjaM3`UaW~h*}5-ubeqZYN;0bG63clKM=GV| zj3e;im|uI;F54yHq)i)&_HtMtKL4k+aD8l6)@Uk=<%^?1s6RFX{hl8qg`*Fumm=Fw z)(-x`3N`nws=+0UW0lh@Rs&bUokplxCNQOF3t^ zEw?#Y7#)R1|B&O1qWaSIcfOPmy-X21IRgC0`Hm?30|O0JjD}#%=yz-XQpqcW9$uC< zIf4Qb#>d|zg59jha&w06)^g6O>Dx1m0(T4=V6L+Z{>ca z*?Hzj9}}+2$}2s1Mi|N9s(bMj#0;wi-KL}63Usk&wblp~y${D=5-B1+cJ~86m^pgW zul<^_{B{#Jd!rPChD&7b`4rk)*-}0`wpZ{JIL+2wdOJq-@Nj-d01?Ppdt?L2jH1JH z_w#ZMEv7&5aKAr9i$6LGX&ESHD@UeAi?{YD7q)ZaM(hQ*g4_Wm{OF=?Idd7pK=;T~)XRkv8N4^upd z$(N0VYPZlEeWH>AwizD`aK=Jtb+w#;`ZX>iHahL=NmfBfg|Xnk?v;PobM8d71qD#7 zc+f{yqaoscMjTEBZP}IM>n%H4#1!c^fOqIX8s~_^3C<&L zGe{+&zNb4BFXJMFVZDc#I(TLKf(F~efuzk#qe}fjR>hGPxuP`N!kdDagq^^ud_RNm z@L4yK=nOo5HGQP%;SAL2!_CYHX~HNR{@OSHux}hvsVq+c7e+_e*u<600sEQi8i=d6 zB=%L}V2Lf0>9(8wv@bf4qMeieO06q7(8D7PW&Y5MA6}n0DetvDe>>$mkCQj9sLFrT zfCqOTr=D07K(^lL21;xd*ZOZ(VA21dMtGv*=@$qJcP^ zyF)ox6H0L9qH&&~+kDR1hvC@_^0~}x&b){<>n;r;9?D65Py^6`r0;@VGn4N; zdS7^YI7lK=NaZk?v83}Z_ldg`2?=vo@Q$fzN_0k(?eQeU&sq}qcA@MSj4hRVdfhse zo!Z zH?k27uIG_7NXiHIC}e5Q4-gRYm$IBTn0bx`aIdf;dsnvFY-n3!g|_N+jYcQXjCygt zJxxTf36>@j**+z1bb5OX3OZLWxf3BzC%|PXg zOqE+%jil?bOreq+*!O8M$4hWMV8D*NH$K^1A}wy#B|h>BnbwCde!8P<8#Fh0#Si`I za1C@b61L3!vp9ZMPJN855U#NlKMmer6zv_6{dG&<0!a>9q|Eb}B#BlXR z;r>)OrI44|(fq}BV@{*~S4d6edacolI>#QsvC!=Upln6j0_dy6y^!=V{?kO&Iz7Cy zqWr`m;SA~eWYX%QlBD_JXOjVkiiqvyMRBQ&(U@(j%B6p}Tp0{V5K8Y^HKy#}H@=wE zXLj+wBei`cfBb#3Q|$&&ccnOnG%#?Vx!UdffF#FPpNhf9RwfA%8Lw?7#wLu2X77AU zK53w8G#Whf=BzmV1_}}x14I1t=U3Xa1vB3eKcY+dy-Cgc5N`7e2gC1+e{zX)Zh>(X zDGe$bnqxF(_qeQ9!L|mbO?WXhJ|DhxSi(S>qxeWM!n@uP$sP5w;a`QbGo0$&3gGS9c0lpdqJU z1z{xSzx}*FDbc6?rTn`A{i;I`K!4mN^L|{a`C=lH@A>3V<*g3YkM+Ph^qt3m&^)Bh z&y3&6S265Z4uwp?zk=QXoNX&7!t@hCrrsaxs^v^c_i4WE>};{1B4TlPSh9a@gLy>C zbYozw9UCOhHWLk3Y4Bl=3WmI<*dFV^FH7VS%HD3Z24IEks(1K;5U}U)*k8 ze-$#hGxNGQ_U5-7y%?#E9-WmGJQFNYbA-Lj?ol z{pdTkDGGgD&oAVTTy80cNAdaIane|;r^6@^2oys4PACS9K{696CLwxV5VyC#{%oG- z-DMlPq8lVY+QC>`;W_9K`|<5+-j_0t9ejCu^6cVCOX5)tFg)_Y>C3sM1^rkVHF32> z1Hq0sY&*T4#*KpJYZbf9m-BY#2~8;gu`--~Fm45WQJv`hD^H695@+Y`^P4`Ac={A+emV#UCflb$=>ws-j&UK&!M7LB+uTvw7d!&QBcd@3WG{Cx$L@9-9+bni6BN6hmD@!ZswCtaC~#9JMgz z=}mb$uG>=DxurPBu8%+to^-MS2;X+o=2MWEA1!q2#-p#{`KUMrC1)5JnHc-#?wnPv z7DW47`A&3gGC-c?ZcbhZd)A!svvG`W9yV18Hr)$9aDyOm-LR+7qT6{8xc$jPM_N0a*iUBwQc5^R(xYMa0$L!>Dn4 z)BwE$XLvK}U(wxBN>N~&AHQo!*#1a1@bHcre8Fb322YY{F|0hYV`_vt1@T+jpPxW@ zbSij>YbFM@0f)ZTtr$IDMv|aDG&9cg!iVA)Oom3i?qn~=DA2&B-~fvEpSHLKoBp&M z?JQ}!UOXuDO_3|cMN!oS>{&-_WfUhzUM}@iHG8~N2jr|+gVp%#7nUZNlS~wPp*FUs zDJtUt)FANK-JNFe=&oc2N-v)(a$2{bCUMQhHN>;#$lAJ=gVgX#Bg40>57aSw!?wPq zV-aW^ST%NSJvH@(=}6~(i&#iAVWaSYCZo|caf96>++Z550S;min| zdy~qrQkxXyzgn*@h?k8b2kazq*( zK58&wX7P(goWvc1aLj4On_g5O;0k0oKUpHpZH}^l3FG{g-aT^}lU#P~#$>+8hWGF0;+bj#mn)^u=j7~7dK+`jGVqxuei);5N zzF9t0Z$$f{BE~@XsY5K~3okQ7ioyKt1K@ToobI&q7+e^$#o>Y$#$jX}1xYA=P$m{m z*wh%Y_(EQB)#GC#a=NesJGe+=-s*$<$jU>(4KsQw^EQnv=?pRc&R;bOyXG*+&gD-R zvo`vzpjft4n5!>8_on^o6P}1AqSuh>=UCo!p9p+ieBCA|dw^o4eb3G(-5~wqJR7=DVys?q)^E5Tr_EnbHtSea3^bAASY19ZovbUO)2ZHiYLoLIjg(O| zIDazd_!cc;e9l~q%}qZF7C-nPRo2!Rdiu%;nawxpI5DC z;biy$lJ8a$<8muus>W$-U-=YTS6I^o&O(nPPvy~-9$_fs%tO)Ekm6XmXDH4wt?+E2 zi2KC!45hVm!83E~I996A${G15c_2xQ&xMLtM=u!-3iqsB&W{{e5-QZ^LHBq~NPx)? zcDe3fjFoQ=w2zv3PIKOpRM=Fp)e<1=M45yEk|y%~Z8$o?ro~&kJXCWxn+OtZPBF## zc+9p;-@=hYj^+jj+lC9I@U!<;d($N!Sbwx#agWkae6Jjq;J4z$wD-SI^By20TO{)u z$;qJvpg0fC#hf9I@}&v)gE1k?5Xf(pOr2vW#9F{wAeg-CRrzr;oUn5!7;PFSuFDY-z5KT<+fo!8M7 zdq9Z|QHCNfwQg;Z+sB=ncFqwai$*ohF6sHhU?92G2|Uj0pTN(*A-lco^+StBUW()9 zG~8Vb(xp<2t@N5^?~88^)Y`I5I!R|th>^39hPiWs zN*4vCtUq{*23qFyMFnxDRvW*~7|glYD_b17Q`*#P4fllDD>|O(b+Va>MQ}eXRjsw@ z`)q&5sp!@6Yg{gCTGCsDV%pl3)vrKH_7u42v()B@7HUqVk<0#56RWV~=eIX_ZJzrg zvT7ql_6nSqliT{gLQ8uEmF5}XaXE%G!g<%WE^~oBiol|X6fqF1z}9rBvDd?oS+k|a z3};O9k`T2DjXmk7m{XFK|Ma)qc=V8?z<=Cx zPIa|1bl!7d%`KYa#3JXoK!?Yn*&Z+|vDvm-JxR0u+-6EcBU^ozq zQm3o|lzX+x<+bU^hn+;LFY;A3D=)N|@;>+STZ*V96(QK50BXX^d|2)5J?KGKKZMXVVn z#RbjoW&)?cu1X;df)XF}imCXM)X1Ejosp5iEjkQIWAS}Lk4x>M?-vFiwql27Uc5r` zt9EwGEG#VxuIcvGpbAU}_%E&So+!G%l*EsFRXg7|Gz}O#yM@9lM^_nB`~oI#~udQuxG1pc+^dA;0-O zF27$Ga4>(N3ErJLMQ3I4f%X*)J~7y_K^DK+sqFoy-w8oiHIW4ROLI31yB>g7$Uip? zT{xdYQ3<|kLj)pLWfbT9s@CFCYUd)1bk=hDY4A-SK1txuRSvPkk+GgCcNlDpvSf@i zbSqsq1o*;X410YXmRo)J-gGa+u^P@W54q)DBy$Bvx*z|E4@ip>ok-hNxNP!z(dXn1 z*LNFYkDBd(2hiyCWVVD`m%3ZbT_3=myD2T8?dBa6Rvy8N4JDKRx`CS2a^$$Yh=PqL zaQHY6Fd4FEwRq!IEG>$YS7u_n3{!*|uQSKeX_9_T!CtR2qO{LzrJkr75| zT%iG?2R=FKoLjo*0m}wlAyr4_=!+WP&3-iNhs!Ose)Cy!(_cj+q8;W?3 zSt|rv568ElXW9nfj4cygN{KRGb&obonhvq|)H^HBwRbMU#c;}AU2Tt~0NLB14Dk77 zxWtDQ69>Y9G$%mYo13efk4V+Ss zjUhi&K>IXf;K1srGZ*W9DZuPcAUrJk8wk%r|NjTV931}!gaNOVnFd{~H-&F`_i!?s z<=b5)K1z8p?*UN9_Xv*-Lv&?b-1w3#Jwl@fNtuYV(pmd|8-Y)Ta`mUCWic_|5_LHd z1k{7C#I7aAP^SNigB?|W<6z0ah)FTdJCFOZOI?rqP4p;^`8NkH2XJ6uR8P~um5f+v zh+lt+)RL2qA|^Y=B3Py1729w;on71@U9xpyHO2e7rU;KfGRYw{XDx3?9fcdadxXPKrPEpvYqL>+R$Wm z@O(>!W7FVmHXMEOiO(GZ*CoVtQIDs;ff6PbvU z+XL4K#sHT^i@PSUqQ{C^?OJAGQ|4*^IT%2hG3$%h@c2%5?qgR&-BX~e6s}=-`J%mD z+;WtTn!L`)&FkrGze(O8qaOngDq0$NC6jI^En0EBucB-?J<6UIxkAx2+Q$+**O;u? zG7GdQ_}t>dwh-d#Eil(^gUx2R>4H7I`zAfk$Lj0!?8T-KE8Cvl>S^o=ouh-DuOU>H z%#XC1&Pd#OQmp1GBjX*9mG-u=DWA-ZNIcd`D6;3)*I9I-jS8T~RMdr?9mzzTxf;lb z;zEd^qD%c=R+=JLYxg=Xi6`x}N5}K$UP3-T{A3@?dC=BYmCIo&Ly~9ls3mulFBxd3 z|FlgUvI)Q^m#Kj_+7ladELSI478dzL|UJ`g7wAFhVp z&;#AKbix{)8#$ZC516%f+Xv9KIJtaq(}oO^drKu%g#W+gIV@Q)^~d`yoOsIDg9TdAbW=aMH1uyZUq9ZU-^~@?A?C zz()?^+uN8*W~>0!&fUq#h_duONqEA-zohd+!>c~*Jc`RpsU@K59uRkPKw4WqxVHX{RCF|nGI_F6 z-O52;#}2sF%9DTNlz8K!pzehkyq%j{pSj!w_KM~bHmox8`8`co@jTBXX7TtYogp^H z2b>E4a?ZD8oRFC~z9q&PB^Yubnc8KFMQPh`6qTn_kCo7D|{yR8?FmSrkxwNx3`Y1-VKsp;EjdH$H~k`04-j8_?g;WY-%fm=XCjYoNU1; zrnD0iY)hY#;s!>2dwtP#WxA5j=58O(tuz`lOR^0dXgEI;+AMZjg;m-=1*o}$r0=H% z8iY1gy~5G)`VAHra7K=8e=Usn`yoei@V`sPFg)7E)*>vNyC#!m-3PyWdFx5LoGbv2))J+=J|hk!@>CtZcTBb zcB~sf%kx)N>yLj(2FC>G5#ws2E~>3&as$7AH-Kl%VP7!cpW>$Kv{qnQ+W-YfR48hU zhbS?ipqeGCq8%TY6)35NYF0!}pZdo&%*XX!veFE2DV$!?!`nDsOdh`tuy`c|C#Ce} z=jAT35p}zo0t1E}$42i@Gp^Cc9THuS-JUGpn=8sMWw?5$9gDCRPwib3;t`}oVQ->d zt0~bsL4u2r5|K{AJq+t7)~#S#W`oO}J;W#ZUX?dLT$xjExL8&xI^3{Fo=?ozGom_I zV_S+tYE(cTpuLON)RDOkCGrl%Z`sP5(tecnciAE|K7@%er+7PfH}$e#h*uQF+`_%P z8J22{JZ|M@0txxU@k(*$MSV?vU?o44f6suN(_!T6-7agns{o`MUMokUC|Rn`ps{Ql zUdo#WwnD81=;pH`54w>&(_*RZ(tgPG6w0d=RkTHl^h zIPmQ^tOp6Hle5J3KeYfK1hL0L#B~Hu#^c^XLHXq+Tp_iQ_;_MMro11V>p7wsl+Z-< zOM+?K&i3VR&-N>pEk`&U0Vg@HZSdo@xN_({`mi=>{b1L#OJpj5Ej+T5zB%P7X7k<~ zd^ris@JGIHb_&W7;6x#Ul2H{OE!iK;$*_-yKXuo^1PBNmAGTPBGL+t;`tsVvw5F{L zEVvm;2zkG1!bLrHcZ;0J#f5-(@}_^ixtF9K*Z=l{k)HmXw`l0IK7p6sqYZUG=xRUJooyP4CDkYWMcU>RnmL3t!3kjMeM zA0akYBMm4&CXDY`)2_`mp($%*uFaSJm~TB}-x3qkT^F5%#8)XJQFOxnU^fFg1Ny^Q zmFXH<=IKBksG05hZLWUuG9Z*-nsvN5SDiV~l(Y~h0TNI~Q4Lo|B1bI__o`8EV}=m@{AB6;K-6rBt7Wl^59CHI=BAv~U);hbQM1y`9=pbSn#Z$8{B* ziOio+Y*=+g@6=7%Qs58UE#maSmAfT_H9V;DQ>?gN;2;t8c)qjqSl*B100;&1#u_~; zaF#Nrz<$?6o?Mnk+Aw&<(a*S6jCBm7+TB;r8t?jLH>yO`HxwawNcBCtWVV~pmQq0~ z7FxLl+Gq9nwjV+Wup#5{ozC5~q>?!MJdro30`cLxVZ_SWeK{B zQXr||=grA!w+0f)1v>=g>(}Q+s_tRH*w_BG?uAOCBI^VY)`M!8MmGKyRy{F8mfsq_ zK(5xH_1>Pb5_uQSe`bAq4eBB&=O((E`h#yvijZwv|I|wMRXkgjqAGuLv)ar%};vV#COQtCl)HThX`y2m_H7o4@oi$JV z8*A1J>Q%JO&e`QGEFLs&AtXj6B^Z%}9jmF^VP+ zJl=ywqLzRcDCcW$3JxOvFm1-lU71o(5`N07B-}QY|1#b*GP6b_!U*I8etFR@gy8WW z!chw@BL$U}{D#a~!T$=GzyBXXW)R;lmaGg!gquvC4+$sOXL`pC1r2w^ZIb~tj*hoS z3!raFL3pjrl#0bK9uV5kf*KUt{_Pp94S8$+||hi_1T z3Zo0vVv8}tTAkRfs+QjQDm1!xDEd&MUdkEf{u+sQ0JU0=fiz#;h4&1DALffgd8}Wl%tAvPuw8eCnc{`SQ)JI zk7Ov8v3oC=r)w%DY$;JX>UU@mgHIGSIsMWoqRZAdimVEEDqd}TY$gEL_6-q=gjCco zBN`Hr(CDrhfqNh{-EpMrOD;1)y)&+Z}lY zQe=Sr(~A%LiEW-}R}koOTE#lK$iq%*y_@gMNn`;)xpua5?1xP%{i!51#n}mga;0uE zHze~EhC=VHc-6}lfhurvd*;+jL;%PDA*O;ywwG8zv_+8V%NiOBuG|RM`jreaXUV|{ z9CVk!;r=#0Jsuc~7WTZwEm?l#VEg|FCqJBR__QqJw5kqJQCo#eueBDm%2>%DKsvr9 zP`f(60~Sk|wHZ)PWxK@^HOr%(NQsjU*g+1m%jH(8Wvm))P`Xe%*&DOb5>oNJ&AUep zRB=g~)qVa-OgQ~o(lX7q4RZJ2z%fMvCHM+@Z-3sKXHK6cY*H=l{g9^<)}VSk(PPs$ zI+}HU-}DlQKkE5>!ZjG@a60zC;N-{u1t$~D|6jq$UwS3rH0c}~9q>ZKCp6Mn5g=r( zcs`~MMA`53>5ph$K+~0zU9u*gMR^XTf57oM|8Q`9U}PKqwv>_$uL?>G z+qfoshFW`mImwETP~ zEbh(AX=bRBzVge4;}4sklQmIl%G`5oNK6MyS5Q=DLd6kf3s@N!Zu^}z-@nd&p|h`+ zb#qlcYQw*Q zJP$cC@kWnoFuPi}Ho3?RX@)I!JfojIA_#_`LPS(D91im!G__I99Bb5%;`e_(33S>Ie1{7pXJ z)+|VC)F2=M&uGzScJor_Bu+pZ0+I*~5?i=*8{eua?-XY{&zIp&amV;Bt=R!jZn&v)L}Aw?)lq1y9YdUzU6w!bcBmI=AKkWhIdr}-OaC9qG_xna=KU_aq!C^k*j%u+SZa&tpXg~K$ zE9nRFl03G-`u;a_H8qb48KO@-EkMdaADA= zgsR7ji*5^^!K1I-d6foMiJhre)25Fw6%=L}yNB+|+cM=JzPBg)SA?vy;r*AUcmd<+ z4_8VhaY$Z}%}~!iw-IF2Mb2rp$uL$C9RtPTOVlBmhJjx832j*T;f(r=CpeR9^rOqe zXY|3!jy|5LjwQ{vV(p_V_z6C#STuca_=$Q4$ebZ8iQuYnJQLJ-n}#AqPL!KlBIj(S z4$P|2eLAoMk$DKZaJ^3O|4Dzhg`4j6;^e&~`Xx;=s}eibS`+pFZ)}MB-k7lz z7bDRX0}@Cic>zBREv=w!d|ES#cLY_N2p-t=+ zLEJgaEog|P8)ZRCtqI$-Lz!8q0@vj%N7Z5m2xZoSvfQW_@9*At{>ZvRSJi8qSYW@t z;ydp>k77v2_6xo3x19UQ8kd`F_r+Ug2jcOHedhmsjHY4~Jfc^akca4y94&T2iX+o0`boF*0HS z!mr5`5pj=b2>+8R)V(A}=Rc@#fz?w-#bFe_J+$rHu9+5h1iPi#>!nW3-9c16ewdg|tylMg$*knEG$pS>r8@wNC#)Uth z=~#)Me7~9^2-7NW4L!jR?eti?zCvi0T-cyQcy_26lPn71kPaNnWctuS=F zsq6~}O?Wpc)bu-$4v>g+TlWu(ZEc_2$zBkLk_PYZg-Z@@5ZUQv^a z9m}*qUG)6OIyY|wBz~U2FoFz@EMe(aX+ua z!Dq0{nbe6H9XI@Nb4f>d_>Eo?aIhs`BbjsSd*UX_Sdkxxy1+wasWor!FrfT#L~G>k ztr_Lr7sIU)E^fAW&k;~=M&87dLbPq3=S%~Q=^OHpbjYr}U3>IUD!$$cD_hJ=ud?4p zU!6F5nReUYsjCd^lTp{fUp1lWUC$3*pRe_ccsX9Sa6cQs6gWDv+iw%ncnfJp*le98 zacD!*6C+mY=XL=?>#Y$gXthCSPkN_mLYHc$C`H0HzW(U7@0JBTF@(}^W@`=qPK4X{ z{zioP4eb!Yf%%;6NjA5Q@R-D^v+73}2KVYHivg_zYVFTmni>L~>?~4ZkM{6rX+UP!XK$8r|0dt>P01HT}8>z zFw9H4G$Btu*yNxB6qW+Ey1Iee|#2%y!j*qXs_kXTAEH zvX8U#qCOGW(UB@j;7B8gSJ^cj5ci;niL#f={@edR@#`H zdyz^X`ae<4__ciZQ~bfp^2a@Eh_gz63>;|^K!!3XyTUZTN2UVDQ4PQLW9u_^<;HIE z@q4$tYg_&N@M@=^XeKN*MX>S~RyM*sC?xb}g!KWiGClX*Yqz3oOZYn|R5+Nzy_<}U zO+ashyNw0;nm*;lth~xGM%(#^_kYSck2$<= zq`3Z8{-Kq|y-KD;#O8Imk95j(XGXw7=lgRNJJs0~rEDcAuwBX1iTx)4uqnOVhc9ipR3)8`eK2M6ow6(YrX+<4ycj|$&Bk-> z$bZnj?!|#CBfe}}lYM$N(k{-dy%^9JAEkM039R+XW(B1Y0`v~D;$f>Kr(%uXsMvnN zzwz`r`!z-tz}6qyx|vbop^o#;afZn2ISq5DD&EoI*oU_6dY$&X_VYSe2d+YJCv;X>mVJNx%p@KAv*qj7>L6w#5Fhi@cv3w!vC)l|pbGsgk_BUfm{Q$5c zwdpr#1~U%d{XBG;SzEXX@S6N@crT6f54@KSIgg9xc{@$lQlUGZT#a_d&B0b0Im7y4 z{UZ{-`Km#N=cH}AEI5V**IB}y?^-vp04_Dq8vPEku-^PE*dU5{LQmj_qC_ibRw7Qh!HsTCAlJ56kjDF_k0SNYbGCh)SVu=( zuHgl+q*YWh>bRSWJ3z-1&t$n}#YF6J&`a^~q!3O}dKheXGlqyVqYCT2;icp7uW)Y( za_TR*$Cvq!75=*a)%HPA!0ylBb}Mr^#|pin{CRYxd34gIL+JvKG@D10vg7?1@u(Xz zgmdLx`Ts0^WWIng?6#Oz7=jHsvA3U|{6iqhD6^!ZaBThCpt?W(YPG*%R|hq#K|Bk& z=PuYK&dSAmz z?c+6^Y#Z+XCsve2$1dFGak|_g_lFI!t3ep!XF;d5CT}0C_tZF%*~NaBGfsbXMZab} z(c;0SWhQ{ow+-}E#I%+o=-vzmoX!}|X@>Rj%tquxA|e}LRhDF6zigQPqZBmq=f6ln z^Ouv4|JaQ?_F3U%CmE$z8xk!Aq%>7uyeo$P~4CaBNf5RYc391qflMI@9i~? z=b(s(G0LktPBK;hPiToUeU6+@N!S!DdgH#r5fCwEc3BwzpqsqWL1t+)^7eFd$*FO~ zrz`kW-^;Lj+3PrudhbWEnbmRkH;*+#c#@x6j=Ik!d-*r}7pjT!)^eow=dQOtZkU%m zSU>@VuXTqT({fby24EwWtbVy0c*|q=#5O6~ZG($&76Vq_KiK~fEpOmSio6WDWuP6!381G+tzS!teb^Zn^iagT@ z(0i;wE&vLxJ$067Hm6mWKhp52d-$iyo*)2778L>`>Vj$tf_$ir%?lyh^|+7vQ>jJPb}Sg%xfQi|y^YGqu^kGQ zShiSQu8N)~xV&c#S&>pnKM4iFDq~@l1Y9(`?}jwD(X&7c=G@USp$FBi?Zze*rDR$Vq`tEpxOlJcTT_eK6#(!4gFN+}mD*_eC1C*- zD5jn~qsIK4ezj}H@LSOVMsO6)c8LhS66V)r>Aw-Q@%J?!WkD)GcP;ztR^$ztBoMwt zHNPo_>bd{N4mE$X?o5N-k0PLwsp+U|XjiRlZ*cjE>{0o>eL?)x2{W!v!D3TdVPCc9Nt*BW zo_BEgvmJO^W}H3Z40g_NY85y|&7GHz;|oJ}#@D%e0GABA>DKe}bB!jK z;gDXZI$V!CEIDx6jI~3x3)9lMP1Iz~zCRae`{>fH+J$4{(xf^|PWU_Hzv=yn8l&JW z!y6>p$qsq(basQgCuGW(L-)}5)t8VHg;VNdJ>xs@c5wyYv$>JQCSdsieImYSO5FWM zTpro8V1w>bm4I_wf*FJeS=ww|DJ#}3#Je6cUI&}x4$N<8jZ=X zQ(J%DuKw0v@?(C9Hg_17peLM?;P=OWyfDSU#lsSKi@&$$Qn{;5)rY32V<6GZc#suD%+$+KWjcWe_RDNHw$wjZCn6hy83+WbG8s-a*Bc3C&M^Fx?|Yvj1AbcZ zXJM*+>d6_|@^~SfS$Xf({?r2eMzHo>)c|lG>6(82 z`MdvJcY2h8A_zTXGCB!}-dpa@`%XtuJ;!jD3=NIYq31l(T+5WdK0?Mp^s%b$^>YMj z2VZ%%i6*)`_{N;yWrd|Hg?daMt5!nDMH3?eyS=gU_^$j(5Lw~(cpBWr3D||cNKpxT zl8}O)<3IlwS!ONQvobhWLe|U=J&Dw_IL0RLZc4xSH5_!Zn$)_f!Qa4N#O&O8d`(8h zm?pa?F+gO$W0%`8%mZ{mcNX9K(j845Ddjh@wdcdORt6PqqOL+{2_k6Kb$W@ICciu6 zIOZh%R@?!cEHG|rvVP_lM(9iqBKe8|yKyorhjKbt_5O%rGlx%W?leG$dJu-_S|0Z7 zodW~oJ3e1uY=r(@8h~R(6*?O;nB%5+Ir^_^}z*rZQ+Q68cz?~1?k0A11y@q zFYF;`CU<%DJ#(8LeO4SH@ir8}A-Ep>W9a{0+-KHotvufKu*qVjo+hCv&EDQhdg1Tm z!I?(EclO$scQGjFMHk8E>57Lt?M!y}u5wQa^kPim~bYjpMRc4yWsRj z1?O%=8M;0ouQ<5^8?P_%A3cnh7k86JB)Md*dP9Ry*l=}pY{&y^pQLOvg>rmG zsU94}Xs{?l)AZH@S$sCzPHnw3XRd2}6Y4+Eof+t|n*whs@IP{R_}YA)*(-2&)8LNz z=6{2k-3yey?Dlf;b&rQxoP!Ubd`(f}xvBe+tQ&b7)TOG|Q^cf}64Uav8Uy8OZ_?^{ z1C(BMB^At(IyAknk&+=P_?6G8R#D3#%$w^<$?C9esC~Mb;_a~3a3b0+@lXUQAu(cA z@%Xr=n0vc`%K=4hg(<2#Txxghr91VgG$E;YUR6z^RKZo%{;G(kO{VKt#+fGe^P{%2 zcK6_>>8Z%Z&f!KzvSW^?HGj;nP*}Sa(@OT+uNGai^7L0X0<~#j(Hkxw&|L>)2*{0T zv}V=CLqdtU*YA1jK)KUK(iIx9*F(Y1DS4@1-?b4ni{`87AiL3jr>- zJ8NM_CS9GL)(UDmb94A>YO8;{!_kc%N2F6{)=`Ts~e>!`Sztlg84KyW8GA-Dv04UpjO?i!?Vm*DR1(zv_31`qBu z?(WX*B=5|8GvA%L_q+F>UaUp0)8|yxsoM3cXFt2~*?@vj`w*$m)#mH{7ckiPthXu! zA4-2K?;$aelmo2=T-Crp92xMl1=p4~*Y&t0*x!FZprz`}0X(UvtDpol=Eo%mi>I1a zj_aS2lTg7LCzLu?r~sdb6Wp|nKhhi#DCH#<^0o!oO1huWa$XOza=Vs~TeBb5D4<&v zPD>$qd?7Kc+$}48v}oZge|EWpZSA8AtMs_FZI`!}17t43HT_ z>x*`1xrf{K&hAb<1&P&F=p3PujNE=t0C5emAiXYmlY8;gR=SEt4On=|-H)5*JDMbY z-DfN!zS0K(@d~td`!UYoPibEn=q$uE0d<(|tQ&99-#1Hq8P)vUx8E-UKYKfd1Y3DU zaHyr)poYIl$x)M*uJbmQf^n9P)OvTfN!Ak9D+m)ak5s3ed#KR%=(3=5SfaMVV92o| z$9&_;F??bbFXFaI#ZjQj`SOH-cyj8CC_k@pN!o57gaA-4NU=seh5&5z8QY;y$9uy} zt!Gz)@in#SXZR$#fcc=?_NUP7r{M%Pa*rjm_xg(o1+s9eN%-QKucD7t2bWs68hDTv z+7AXAQhH@M?VBBJ@+3(=uww~E;JYTE-DM~InuvQY8J3}^x73g1$bF{_gJOCgK zglx}H5HX8MZt0A^!fJqXuDnnI!#_->@b4n|E?=T-BCE)?)+^sOZVoR9A8l27s02#6 zn({s%X%H3Ivc?AhDHrO~crd8!vtHPwjdL0LFEQROlSQ8s=t{c1-+8&EI>|6!6B@j> zYPf{aa$`KZ2q_QW zCSlNzkg}1(CXd>bEQwmFVCm}W`uh2OR)m>G^xMth@TJfiOaX>pe3jh&Mq|xT^f1pr z7Ss9xuPn{*WPAl&h^RF!dpV$R3jFv6sCx&1B_4Z?hB9p^# z`CfY4FD@LVb?`?5IYSlGF7!x$Ft`MRHIiB}q2% ze9K~jG4^aQomoEV?F}QBDS0EbVpq0!v@3>gRQ<}TJT*2F`^#GjlP%>2P8}`jb|v97 zNpea?e+rD`v^I@t`$JaTCRDHXjD20zP=L!aC0lE)zgkKk4Iwq0@s;JugE&?Ms6MgW zoi1QRax0b3H93ZSRBn7b+>ywl32v zo5-cbL72;~&XcaL`+IE?nv*VU6oR-&*+mV?mQ5ZTd`*iMCNxary>a>{7a?8l z1_pF`x=NU;2klbF$=tMVcLap^Wm%KUw?$O@VXyJ0ef!eR(#+k1e2xiZ6fVN1{leAp zZCt-{AgDo|F^u2JN(Q(I{n;6mdE_Mu%qGEZMP-~co64h8ih~DFmoheh`?-aXCH}HT zvmiK*ojGx`N5oQ*%NamDHcF2Tp8tO)?cAVo3I#@=tIisVr zb|2rtFmzjW$BRJ}hS0n@xH@#cv2a*%Gw~OQbSA>}$19m0w|koTQ1zZeto~x5{HcQN z8~y5`iz~4tKBp*=5$9kq1%YJ-Rm8=1Z%X4eSu&^Hb`J^tBt-5LrYS|1HMmHt2@3*q z#ANhq<^AvjXImf*cix)aekKm~5CU{uriq?6Mh&$jTRoC(BSM(08z98HH5^WOzro6Y z%Y#96>0yp|$sJTbr}AK1r^vn(oMdUXkt`^jhB5??VZNfa%&g@e#E^&`MRq8u#3{sL zYah0~O?x>%J{-#WdAjs7g%RIyaCmh-ZiZGM`S0yZ--thozG*NY`DI2OTG3< zu{FwsLryvjQC<@lE3Mo|InfZWnX1WD9?$fPr>2>E%hgoer3j`i%h9Gb&X zIb-G^PH6qc%h_Z#HN}T?#If-(QfVu)12(Nd@pteKKaiy_wk5-1M=|RJOjr+;dvu#r zZ3Qa9wSw?!1A>`$`b-r=sqOn)TN*Vm3CQRBSW?1KS!3otoWy0#gHC3AOHoAz7ve~8 znfHTfC$byo{rjlezU#q~bT~b*G~vK5s$Y6OX_3d7lAQDUrFsKq73N9R+S1K6I46f`||*m|$PCYuZ6 zX!0UqY%&^qn+to=ceXanpdXsOj?WA!3+FcbYGoTTBX4|1Ka}V~1Kea+PBb`YhiGNS z)B0L!LEEkjy;BR!k6jxYop&MbUuNeFm0(Uumtpj%$Ejm z7l-;!)z5hp4j&VJY}0kG&hziAg)m6BluZvN7@&n2ZH>4dwC@7D%49c3ikm1GuVC&d zrK{YAZtip!-VP?G`VNnN;Gqo+pRjn`qNd)kmEKib#!jg^jhq?IU58>N&8xhc&rg!~ zKwzN>-_4_QKDuB;I!KC|3eZ{?h8rrhJnrG+O$+ToPPKoyI~3_2IU3Ud2_gR$g9ffL{TOF~ zjK>t;KaoWsKn z8R7oKU$(2MmvgR+u1awY*_)$#OqvCm>OBq8Y#Xge3T0yBrP<9LO~qr%GVI12rzxCx zWJp8SRk`qUHdb=t&lJZdID*8wRa$i&V=sEm=;Rx15QeI^qf+An+hu{p%VL7|r1(N_ zn=ZkfJhWH){sJu3%(r}kIv%ZxOevW#EL}Ss<*RzoK^fU-NQf1;HsHHC$x91~F+qKG3Pnj=gr%s@q^ z7mP0-i6(`C`;_IqO~Z!(=uci6JgL%mCX3@NGB#P~OKG>p zi#N51e-I9`o}9IDw4f3hjCNs2Te1f@-p)1nGB*3l+~a6!YD(mb@2M))xLNv+u=+ZM z%ZavA{b$y*rdBq%t+IUW^(g1*$30_!O^fES)$i-|tfHc!feU_LA1$hX>sS&t^?9(tCF2&c_^t+AWVysX|31Of-X5_Q<{MSw7Trx!-AEXj*Fe0Ou~CN?CQ z309=NB#&wT))+JcnPtC1*JcG6FYuYq8QXUPPPidWYH;E<0=4aAkb{EF=2-c~!j2(u zF-`h6H+i>)2F6|Fm-lV-l?>wy$P<`)hJh{1NFU;wn^UN(7(L75)nFl$>7Jr7jhexcr z7&qIj9>DGVWO8sMQi)Zjg`^a*RH&RjwOsilBHxff!6SeQO?m%9#?x_!9Z>t;QF}*< zle-XvX4=3>FV}i{=?>OgdMKFs#6)>(n?s2!l@d`4#aV??g<~FT)kiJ8@$vn&T7X;M zdLu^QBqt=Bf|hXcrax{LysFS*AI7tbtG*+0^Ewk+OeOoIkS4lcQ52 zza>>>60@)WE=u+0ytc(^lo>y-fIv#XQ;h-D_eN>wtH%cy_62T#IV{8e!3d2;9@1x?bEd!=VqAgw;uDsORhh-LhvPy z)g6uFo&kR0+N?a8GagI%j!R{I*W#sv{UdCpZak(y}^7eOSn1 z24JvOWb4wS9QN^(8Df?Ply@~_;JmC@t~B{P^g5TS-Zu49`1;sziK|LAcSxgk)Eiv< zIkj(;9F-CH!eWiA?#;hPM_^_1TU-6D$nt1_4O}5ue%eP}w}D~|4jX&ybXypXn4HRu zMKmO&B*+!xW<@0ib#)DRp;LrGg7<#?^u#^GTW4)I(?<$;An~`~iTr-%qH&xtd0C&9 zMhN(-*@(i~$vyP~?vA|3YWA?SOT8u^!WkZpu@ zP;kVr>%lj1K)!v`AHFsD61k?$r(hnx%x!r%(Qe*Th0E!_5}^&stZObm5eMd%JCeHx zGoBv^2cMwEetx^+GBnsnxD=v$L+5NL-Aw_#t%%C{6xpu*{znk#h45K{ zksny=k52GBP)&0*$HcEr8%BmmWsR$~*$W=LEf?~~w8Y5XQEK=Fkq?%`Lstvg>*1L1| zjBm?dEm9$)dDI(=EmWmaZW<25hG`58xwgWW} z58j~!x(fP*BndE3x+8lt2qp+Q8(42h?sQo4h+i#buDTBT)jSD?+mWB0^0GGuxERG;JNhe4QR`@)bp&kvgD=nrMC|| z;dU3avKG7iq@@P)@4)Y9X(%#uYY5ZHGc{qVqodr=)2;VlYRk@T0JIS@fk{rkl5}qp zq&dhv-rw?O;{dZh{UsZj8Ni~hloLbGlpGlOdALYO*bIN`E%bb4eq>*|M}J<4;Q+sLgy3nWWCaCgtdUGd@jy&&P~XxX_ePq&B}7zwSt;;ROi)p>x} z8_4p#qyG8HY~{BVR?9tQB}goDoR|8CxqJ+z!or50Burc$C{KaxY%7O(7wGRS z`(thcJN9H<6UVxS!AbiYuI#f@j_&xbhPdgi%6sg14r)}e4O8Fpq4_>WSE<;|Dm}BV zWGH*Kx(?TS$^Bc<=>b`H+{+*IW36(Bkd!GWq)+^<+jJ2!L59Tsp^gG4Kw9uKV@lhD z#Y~?W*hXOM6dTvSKmpSbu$i=Jvf{ZV2)k%sQ~XuKT(!Gs9yJT9VcMSPmYU$m0NhzfyLXSMd1R+24v`E{wGCgs8OCm zV^|@<_X#1=)|EqFHkaNSlz4>pScSbjW+JB?Yq>2KHyy>|El5dMycR=GI!K6Sx3hzh z_(9Si{k`=bZzs5Xyzl`n&Rn;1fm|f{>=j+RW1ZtiX(IaZuCAIlhjGRn_GM`VEQv{l znDOR!i1D!&EzhH}IH?;bzlKD;9+a34m3oG2G6n2d@Kq2Z&XRyty z`ld1XfvPMdzBPhDUgZf9*&=wpHM&G@NwU!BP}ehL(M*#tH5lL$P5L?GE`^ErBhD(@ z!j@PbkMFBLzAeKfSpTkE7dTPC zbx!2jaAf)T!BD!TM<32+AgMNDVMw3rLSJl@gjfW4Ud`rwAu~h|2|DiS%(%lnA!f?) z5zlz^cRWwAx{e=9eenEYd-G;l$w<^WqJpd~$5l_6;}~9$vhp7YE|UdOlMD@JsTc zKf`pM|G3~zYEFVqKtJn~rM^#`hL#>Z$T9C%f6M|DvrRIvww}H|z%2Q|^@tZx+T?m> ze~|X`pV+UEHbF6>M^C@|9t&B;ncsUAfa*YYfdC@2X+5FqzeB<11MhyW0_%P&GD#vuF}?vm_9Y>85wt$jLLn%z*~hry0Hsw1ELH`LZTty0Ct- zxTO?2bJ~_lW6Wv=eOFi4J2*J6BGe*$*l|(Yce0i(ZTIFxpPG`KllI#`!ggRzFo6AqH&G5mb!=7JwiX?mB=;vNJ$Xy-dz9 zcA9g2{lYlof56`pLVd9D>WQ6Z`(6LE?Jvw8v%>@S&+0MIe{-yIqMyi;F||tY&8+mz z*DqH3nxf>&#YY8jOd@bRJ>#tSQ`kLUihrt#Iv;)U&|Larr$mr4`-#ln=$#RU-3Y&N zgg5^yMf`_xi~q=O&0|+ZK0bj-owD#!v^Y!<*@8Adf?97ipDN2PgPIIIKWxn&7?XC- z`zw}YBzzTG#g>}4hd&GXkzT0BW$z6ZT!o+bBmYecaDmC_QvmU{^buAWI!F1R0rL`# z-QNMTtXn@<>+F$(9Vu+}JOsQp=yC?Ujug2^8JzhLr^m(nA6ji+pL zKhe0H7`uD&%*a$Va{nD-YP563j??`fvTGZmj);;)J^A@4dG{!1s}Z*YK9DCiPa-Mr ze^kaiDf#ZMUa4z8^^w^XaZY%_X3a;Ow*rjT0H4;1kGKlIHHJ?jcZ3etnh(Mf<~P64 zmf^W(Xrmt!6T70oRagB`d$G5f-LzgCy1Cu8LP$G?5|!OebNFmcr1dW-IlhhAj$nNlaK zFDf1KrJQFlz!eJKsyL{`&F+)vp6wZzs!0BfgnTuWXtiiKlT~3~Z7$@WJa%0Nf&Ifn z0dnt1WTu}CmtOyZijn_@iogFx#T^w1CfA&_c;L4q>gcxD!1_c#!s^Byq^Ey0Hm|g1 zMUCjx9Ov^!L!Z-ZdO|Y0Emn^*_U-f*DvrVhl*N7QU z3ol%J=UraJqpq1%&o(}l#Y9f#l>|j`T9h>vVfz3hW@aufKp4Ga*uwj;ZPB@Ycgtlpd}k@798PP zA%f^`uIH9y(&eumx-T;CFaOkqlMOlsWcMqGoc}VTmGx&j9-hrGz9Rh?SA%8piECv3 zVuu6tGS-Nu(NeU=#}>vx_PM>UF(zSGCR_FF)M!FL6Z_SSDZos)KjOA0kqD}RMXh|w z8lPBH7499bC5BJg+7xp~;QVIaj93$Xv!*ainy7ilZoPq=gx4D^z?iYJAW^{B6tIx! zi%>FD$$~WzBF|PTRYf+makaHOqgOZSq-^KjYibt}#2bsG2u8#?1t^MDO)xIZ@tMsz3PUV0+5?}a@c4US8Vi=A;m-{Fs2`9gFKlpk*%goP@vehYDYkp-8I2Wg#t zwR_?l^skK@5p=nx1$Ir{?_Ao$deFV)<$~m0DT>N=!s+@CN~fl3faH0RIDpKCiGkY5 zjPspMleVbl;FCvv*4nMDsalQxtYnyXY5XePh%2|*EucobvINb{Y_2e8v-Xi2z2L%H z(_6oOw8=-(at|ecG^<#`4U>_NtVZ0!a3JX|0YzLy!4C`MFgRiA~wG4v{y+Tp%VjKT}DS=?6qKa=Ujcq@B(8FR67{kbwshj#mVM`Jo?}Ru8aY)6-um10bk0yzX#_L< zl_!o_PVE5poyOL!?Y^IH{OX8_C9b#^dafEkmtX3L8AxsYvs`<vJn;V32VKf`NF=>P|o44?PP=LjKD=Yj!^+=Ge`O|6OTE!Uj(2W(c3@qSAN zakOR##*WWX%g`Yv4&nOx*1748w!BE|2LxeFPbX)xtAd+`WBO-uX`^6h9_Jjt(gxN< z#7&~GBpe!eULJ(S5-yL7YHG_adqxj#U9&ozUF9G&qB03Dzglrw?(37hiHxfX%!Puk z^Z!O=1}P#vwR?P>Gu+n(8c&Af(1`5ziT_+iFq-eCU?EIOLiHM$y~=iDd7S2I?9n8} zW+OrN%OmX9%q#C(@)=Ez%@27pDViWH3v%ws{12v1L{-S1yf=&X+O2}Iy|s< z9eY2hDc#;fd{J~aIkvLt)VyT>Tbm$3{)d7*Tz@)v2ijFYpM^qtAl%tETjIz+>9x4L zv){3IZ!Uv(Y#}#fAvil@4kO;0UA)6Px!(@s4mX|;o2`XDg zvF~4Q;$83n(`MNh==QPw2WL>-x2K4`_Gz^j40iVy0;kc=@Ea0MpxPN^aBLm29+kt! z83=j-a$M_DTG-%{z>8k`>Ey~)VHzF z^(Yk0uCNP%NosTXr10aN47HO+mc%K7cQgTyHne7)3)=6W14jv;ekcKek}2j_+oNYy z(~EO`jx>7A3%?%!ZvV=#m<>d(-Ws%Lo>RIabPv9ao4?u_Q?i|N({u_|@t-*BSD&q! zf$2CY6fYJe_HEp6E$FYnf06?#y=3$3dY@2PFLQ7){~r%}`n5lN;6pxg+h;QO-pjHV zHl;K8+I6GVv3tUkeX6v!fvo44FHfG^$5bDI=zkTZ0N-)mYwX0|z9>I#;F{F=2ydI) z+L2h-HU=9tTI+a&adB18Aiw{EI}5C*Z0WBZ+v5&M(u=VFHMV|ThCZnW18hJk`(Lmg zlVo=$YW><*tzo#GVJ^O{?vDWhI}8kF%Z^UpEZ{Brc~@^1#rLqT!^Ar2Xaf*ZlypQx zKQe#LEe3nm7ssV8JSm@>HMy5INyxY;{?icUAA8f+vCN1WLuLeq#~!C2aW?>xwBN3p z!6`+KHeX}p{v>FL{q0Bv>44aLhan0{B!dR&_L?~j=p5Ku9v4?Ui#5i4@A8Db?{yPX z%PT!~^+3os1Ol2eL*_>&fUOZ}*>sU9w)sD!UY41$tYz~vD%58ugt4l{Tz(m*9EF%Ivk za)3Lq*a`68qwe0@O& z9k)L=kr6F5S{%pC#6ft_*rG~YB_Q$iRw_Pm&w(oZB=>bkq`>Y3O!BR4m&)y~t(&bb z{j6CCyL(|sV5~$u?=4Lb5#V$ooT}+h{HOOCkhV1>^7~EU9dUZdLHaJBqC%mfZW2*h zq0^_ekIO7E04Ks!KQTcdpyEV9h5zGN7}B%`-F#!@wQ{)PJ6J@a+?Znf8Bye+fp{%# z3UGdqZHBWJ!Hu!sg!P&9<9&PhWVYA3W9lc6XS`zZvGIK2Ec+ZuYx$oSh4?HEhAN37 z#qCN+mIM)e8)R(6@TvCgt z?$7^9~<>_&n8Z_L3Lo~@g?$CbFztSi1H+$TH_M5vW$lFm$v%4xAOJj7%f2Mjvrlyh@ z|Go8`CV#Yc5(ve_G~E^b3Dg-~6*ddv5c9F+UO&)Vh8fr%Z+8uqkVhkZdzV`2kc|uZ zE-aW-Y1~rMr2&IU=C%C%{nBJf;CQ7Hy7j&Qmz4awO3I6*divmNChe8fTkCR9t6I=m zC{Ar;+rq;foiUY|^YgJ-!gTRNFRbLf`>>tWF@cl|IHUYoFxu$!E^j zNrHKTbOYk|g!JblkRJ=1{j&HCDqg{=orApV@#|7*%*Z%=QI`(GYxLSIgZ%<8uUqP$ zz!Z@|S6`Mh&D58T;ug;;KirLcS9Xp2H*~zok}KyvsUYXvo5ejGdtu&9qjX|g-uC7swp z5I*L>p-2ip2NpaDZw{`JdnAWMSXHQyc6u^U%dLJ}BSMU27j`b;`oE#2xt%c=oRo`a zn4Y`ENO}6^E^BXRKB@3K+;SkQ+jlH;?tQEuoQt_H{{Irkx@PFxnz6*}oY~idtgFfD zm1HJR8u>>nZCs zJ-8;K_}jUaCZ=Rgj+v#x_E94#ck4i$kwaU;2f>30RjM+(W0s#{aW^HGW0b>4&?HQ7 z2A|RAe}ayE;3$i2%^=So0JPhsTw(8UR_|xg@GzBn6F@2{a zw5`T!=+`{scWv|o=%E0Hn*^Vm)(ZJ2Ee{=YFA-Ln70Jn0F*`=?ix1eIfuL*1w~A>U znFpF09M`<<6idQF*B>#B45MnF4>rpNHo6i{&c@epIG4l9i&jihlKr=*Z(Z_1*zI$5 zlMa%?FbKp`5VcR6YFl>{{f_XjQu zjW_I{xFTlr-85qyNPMvtdHZT%GI$-O9&aBu^1n~cb5-pgW=%R5$IPVS+%B^V0RTCL zg5;Dv62ht|z1>G+Id3AHeh5@(jioz+jCMw#bt&E?y|2>6gVMSBrEj%28j~PdiRE*1 z;rSzEWpFwx`3*{;d=l1w{+&(MyM2ZUBc@g1FE-6|PK8QnO<`l(&xwdT!mO0~J~J&Gr+8aOHp5GX1q=FqAsqhGx8?qX)OlE_<2}fGmfDg+7s? z_&d;h@~zTkB;N5NV}>qaT$UL-3j)0!tK?6Ylyn;@43%-8>iGuVq>f4vf6I+za5trh znn%{tW=^imgohKJ1u+0K%&iox>MAen#HT0A(l7F_MOB-l4Sa+&$G@sELxjyx+iUcT$j!X&iiHWJ%S?O?L%-q?R^~5& zm{BM!FBllgyxf>=nUi>>U{zTHN2-TXjQRC4#axyiM>y)6^aK8K_;MN0ca(%x$9Fbq zyJFAJbG@JLiI~rWF(FV^G01XoEOiG*cC&1RD4PvA7-X&liU}T&73^#zGwA$_HFXse z+8RcAgBxqD`(*OCUG@eMwBnMrz7v4GYX{F-Q*eWroy?Gev3s1Qx6_Z8dI4XYz&8@X zR7649E~cIk&cPm?#I!j7GANAh@XAisrYf@TE=2Wi>caOuru^(om?b@0GJ5yzp~kf2 z-KaD>=MAM&iF5o*l$wOKBK0y@f=(iw?WE7HXtph94Vi*EId^|JIZWB^kAo>}H<{3K z?TnrN$>3+BmV;ODG4pom6Duf$GH)ht?LC3C#6?2OeNywzQJ(oM`DQ-%!1*W8PJroq z3Nss2MlPSrh7X)#^=Ap?C81;P8TA+2QfZgDjI7c3KgAzSbUDCTuW*=#av^v zT!@OyfIHNsT7XZA9_P4{6dk3Pw@5M9m_TaFrhk{xz5@+MD>o0-$zYq9zzrEEg>(Q6 zcnY8SB3c;N(g1(_a$KJ%Z`zHFBW|!EwKAvWp+5ZISRvBd9@YHF`yHlRq3v0xwL3f7 zDF?KuXwiN6v?lkA7!bwepIkFN7qDNZ@qCrxZ=;+Ke1zabNS?nPM9%8}^~LIFlHYt^=laztvC3Xo?2NdeP$ltkk|` zDsP|cxsOvF9%)Gl{mjJ9xmU4R_~}!&9$vauxpsSxw)PW3t=VifH&aqcE;g1uG(Ib} z;#Z8=a2HRe{~chn&w8D{EmKdh19bG6YchqopmAhSx7MlG$|{+vzSzIkdp=({m?{Nz zEURML#3(kEu%s^E2|Ezd=-~zH9iD@uL~t+8{9D241*|K`Bj)&1ib}e!?z}l<6EG$G zT8WBINsd+I>B_;)w5cbE(Q|ub)S$7K5K^kiT&WC`P-m>IHMMS^pm$i-@q4{ieWmpz zk3lYtULiQ4A}e`t0b&A;rKy>Rk_r6Ikxw^+b|$}4`2&p02i!*2~^B5V_q?#7(i8YRA=g-o0I77keK4A+md`^V%2{!0)nw3@Vs zXwFDWPR0Re^>2ugx{O>rnuz0lJ$ZsV!Td3)Zh4X=(0H(y;AEi1;(0%xf(J-=g8n_h z_3V<8k;!Rl9xc{)wYoOCR^>k&?Ig7JGg-$qt>pE&aQnpUR?LimLI z%7PR9Wl*?q20I4mJ=9P!^;3_6D zEz=4QJ;qwU@ji3L>AUeh@NFZqp|D~cbQ+vI^c4|E+__Syo)PzaiN@e-)kHy2y}39| zhF=GE!!Q<_EIX83#c6Ome|IM@su%)V{8=6nB=Ru$1fLeKE+kek_>TKJruoeQNDdK( zp~5kJolq_TT7K605F-iD56h*{-A`?vTIAgjI-qZ*Z3f|W1Wpr}WG=m9CI_7zEmD0L zeCZOt(%V68m7!i-?tKOkod(ChZ!7PnL$+7+@0?daf}HV;iNgs8QkmRC$R&-gXKs-J zi>9=#t;(Dk?R!TcBxurf-MB%;*>$~t@u*iFjSpyX()JT1wG)&velr^bp5$Zfq-WXy zB@0~!E=YI?^ZSy&)h53wveJv__cl)?<~S%f|HT=&y#5)lV?;}-nH`M=w172_9WmUb z!y_#b^Sp_ihJuxb_4Ovside!ziv8Z%e_3`VZUC+~y_qjmL<0v? zWsB)E&YJ#+k05runHzD?uXSGJu0zj zRBQc9uqfjPwB!F(N4qvp9zs-im`odv&&6sEFT@qeh`qjV3BME;RCd7ja{1(1)ThI^ zY2SbauME)qbThD&5NfZUD0YJVbnvLdkTO__T|yvHe>2v(-)V64(1PJp>4s!ys5hQA zKnSRlCiLu!2vR+0>y|guH{rT|)eh1U>yIr>f&C{5Zj3aCR$!sF1|lwNX-72HSCj8z z%C6KS%G4aS59OP6n#9#PEO}=Tl)>dE_`kMiw>kg3mBv3I~8H5K| z64z~j8irFLt$+p8$w^xTd+GHN3;`eM$J?FL%a;qRcz(}f+4_TDEH%JbKZJ@Yo_BN- zcb)R#l<&62E|K5*Us37?um7=-iyvSa`9BDKr=T-T1Y>C0Vn~f#xVD5HD~Z3nVu`*h zwh>Lt%)y!-l#2 zW<_fgg-?gva)T_+2fu^G{CamFUSJZet&k6RPVAI$9AlUUCp@*?^KBT@>@OGucFMG8 z(AewNFj&=xNz`NAHtF|=SDMdP=`Pf-+oY3U4AMF3(PQklfF~^QyWfHW=?Hr7&vjzb z_L(7lOaa%SH)6)k>xsN*x9Mnsvu7E`wD~ zNaj+&)0oiJ=kZChT}rVy0N~5N$9=gZPZPGA+4Ld9TZxzfd!A`of* zYAORGy4=CmUg_W1iF2epNJ&kTo143TJ*_E*1xM%}4xokKcCkRor?W?iiXNDN&LCyj zM9^B4{R(R0?+!ITpP}mj*J`>$W5x488J3dXDtm|)g?+-O^Hkzz`yGRK;R_<{UlRKM z62$&JgWv-LRs@!l8R@kSwaXIEi3r1Y6f%#?8PxD&uEAQEVmh2pZx@}aKU+HaElLJv zu7Y)ljcUe*_s4Fe79x7A*A^p(Cjmu^4Q_gT4^%A-@o3fX(YuHN=SQ>?T+RwZ9;{Z26Y|7R2w*C(3$HoS9#<(cjydM^1F?%E^sI#iv(`d?{~~PT znV}hReE)M&zRlzAP}d(qJO=!W3S*9h87ou#-xxBq{_H53mcBTxa{4F;dB*fPq7__f z^X~8&oOsK2gJeV8>dwa~9MkB+LtQN|8h9Eos`O1dXU}2;%YUI%ZTOWFh6xz-4yLE%n_bO}td>>t^1}e@C#DUzQ8FXsr+K=#FDk{)Y(LdCC91GXq^J z)5&8jQV1SF-|UckEcDp0>}#|in)T^hNdrCpcR3BP0wKpX1vGmj*f8=&Pc=|z24c5`UeF00GI-P32Att zJ-T(3=haN4&z|_g;jz_vPj+&0-t&t;?HYMPo8a@XstCtEE_sAUtlTF))}?HjlIf1p zJesU^q`RrrW~qyiJ|M+c?Ba^%4qK@er_-ca6qCx+7xhp)r;D{@IGDtYpjs|nW>Gmz3w|H1F3tQ^f0)sr&+$73R|m~ z!VY-WwiYi1Z7#|8uos23RF>8Z(8_~c_rvHdc{$NhjBnMiut(7ye-^u< z;w5yIU`V6lp1*2ea9b$FHh>)B<>~E`3EQ5i#xt{7f6o+i$ubs=UhfBLwGD*or`VTt z{3&xH)!%4#q+2nCh2TJoxnsLx`H{i{b6|)S6+iRrg_j~n+_Cj2^f@LLZZ=Z%$P2Ys9Gl$#Pp-RWYvo0*fG7-Zch+!%{Zp%ujaIKe~%GYO{Y zQJ!UJ`2z{3zDW`p_!2vXM+wj#8qKsquC0y22%Rfvtd7XRd?R&Ulv#*Bcvt z+4W(d4y1GyZj9Z7teql$hO~5lmxU`5Z$UvBY#cjmcWj!0kR;p^`Fb<*`~^iCUS6zw zi@C$m;>83UflG9_xsXPc{I#?SZ|L`LWs)x5_7~GmWRjxslER`%&XwPn?)znwzh8NU zLPD$2?bc39Yd(-GVD#If{?EX2BSjz#ZFG<^zGV>PYrk$Fn&mbAn6Qm&UC1V}@&*c8 zALsf0iM0g3HKE4yhE&2^Y1 zkm?0O5yJnCca_lb_qS=I6WrHF?Y@pD%yI;9xh5y9HdG4xkI!+&6VZVT__>*YOg#Gl z-c4!c>7`eL>26_R)rmE^;SJ=#;PC$-EnoVn(bCof_RW2t|K9B@b-N^Ie za?T)2Y@^Xtddxs_H?2PEXiC_%0h#t)W5tt_0!KVTdv(Dk7ob%nj#{6GdX1!!O^>!R zEdXuZW*w{;&O;)qZjX}EU@n8Oc?Vs``(CUreZD(sf_<=kbeZ?XT_Ya1YKXc%zYABX z1y0XbWb6VPU8lwB8@*YK*TZ?b+GC`##;Ip49+y*i+~}WA za$R0r-C}10L;nn(23k5gfP&eaI25hh)C{Rl`8O_zfzJzG1|P6Rpz5i8%%DyDk&YYA zxg9e$q@aiqAF=XEx3@gi+^6+N2kCC_@*ryv+uEv2;~X?eshCpU)^f4Sj)!m5DK<+1 z%JI?BjL^OdNjnlY>GgG&d;I>*VrR~@lZKtg3 z3XGIPoQ&Zb?;QBny~5`g zeCg1C+c|$fK*{&up zt@Y%x#q)TTzsK2VVue@dXIe&|+j84aGG8l0a@T;_n|jAqDXX@Qa!$1U;`>I zEttId&EsUj(ucp$r>n=W(Ji*%r%SeH-!f85 zM9Ck1-?U$|Hpu8T7J%PyNV%usgJUvJH3FcVb;?o`xC-6Yl{lAHm9x5gB+Qc{;{cBZ zpT*7cEO#6+ig!r4*p1tE@?$Fd<@7l_4F<|q_Hq`-_cIXBesgofx36`s>_ygN1#U&B zyD8GFSKFPpi91v@nJ(FmY1~Pshm#2y$kNeN*6Rj6y4iS|)MZHtVH7P@37Z5d@#R#) zSm_R`_6qmJLFe)#W;mt^*#w`a=Z;E1NpOxUkCQuNZ0q!0JkgAVkOvAZQ|(C-U~`!A z-otaqW^$puuWx$MeWHYUylHO7W;>r~#V>z^O}i>-p%vu7s@2B)&T)XJ4Tw)c}U!HR<@+~%xSlevVSjs`LhrDB8M+DVSLcj zN9)427B;?(KUC35~zUp0n z+i}+PV*(*xjQFx@l3#n^%A7rxZ=WhBDuY`=iCLppY{-Bi<1%iOUl>q8D6$~pgZDg; zERV;~#;zjYkAN)jT%=F4KpiP}NSZ`yXH8#xV_8>*a3gPcOpq~wh8YI0_;Z&5&cLB$ z=X!p|@?eabSYe;X1Dd)bCtMuqT2NSjNEq|{bH}AW7&WQjcCSL*t46AqLA2T{J`ahA zj*Fu|5Oa>{xHoRObwn>1WR}vv2{prFB)#;Z%gXm z25-4A701ufBLKco{#386+6k#Fs-v4$ua{fso!cfQcpPTwjCM}H6+@Y8PT{DHZJ3EL z%3BvEI$+s~yf`0tjRvNdKmk^aYnZrBQP%x{+~$X8MH2`nV5P+<%ROa7aOA1m+yS>y z+B;%m?%AtbF|@gtx0Fja*a2&4Mt!G8#~q#e!9{c1EUGX;a6$>urGhH`doo6AC4fq; zw1~K4v=D-8`XyOzF|{hxCDXpa!1LTZ2RLsYGef&p*(3cs{OLxUak^5XyrjDDPBEP| z=qj+b$xauG8C2hBE9c(jNmm99{zCXE30`SJN8);q%SKaBa*!X+>T=vU!!Y_=}>gEdSAHIW(H=f zh?F5FRGZD$M5og`%MBI7T&T_nG%Hd0A3Q`slpSx1t*m=;mt!7D1vC#nOm=Y>*LtDJ zdK0fj1tKtyD_(MOiL^}fnX?+od7!E`QwHfi=@RF4G0{!HO)7W!2v{1;e{$TEz;`1Ik#X4siSLwI_&-lt)LKiD#4)mCdYDXR>)mI6T-+L!skl-8Fepeg|_>-OmPphbQ z7>*@NQ3M&ijmGFbf@$|NQ(gtu@@nNX$nZE0nM5CvYQB6Lvk(Me3f=J}LzTZkK5G53mEtXEGJ{Q}!5+q%P9vb5pG`Rkr2 zf~_FXqVUbi;{JkT^zMqU(y-*d>z3s$f$Bi!IvR!yOFGZ(_Kro?sRx-MhsoYrN*T{p z{^;k;{CObZ(!T!C+}%gX_>Nb;zNOvZRCKz*z^Uy$`@G?W7EtoDJWQK9fzfO+_GkaS zbJaa6hNC8WmXe(B3t!<|V^>8ytq3*@nw_F+?S?1wP*Bsl9du+v)for|f=ymu@=NO#1Egqdcg5CIPhWA%)Jh4z9a=stEcLE{rTk+9N z@2!@vUP0@HJcWd3sjguc<3%^;#@6=5ikFVRAi8=~5iv3FUf^l$4VJ=mcmO@}Cd9=# z1IyMJzyU^Ny9xz_h)+F_}f;HJDH5mW9~%QWO`5`7xiJc`;kgu4K2(a5wAT zY-Uk(_Lm#HN+S~I^#a^%sx!aWf{>^)-<0*hJ>{w8DD{ampyt>fM1QZD_^0W8Ho~jn znWW!_M_x7>{zn1&>PyA`$yz^%C)jQyB)0T$n#BEg9u|x7Qpoa1*buftFQl4BTIqsOt0>~94MAooI$ zqH41pLV_YZ${$PEnNkJX^Yi!LiXjX1qV-Y6_wn(Kr>?2m$f9=U^$ zs~ve$@qZL-YQo~OQ5})C5dwPQmCLk*BpevMFwotNap^8%){h>On-g2#xNEho$M81O zM`p&hB-Wc7&PmTa|NQ(27pHwX*%wq&23FbTduCIaeyY3`71dn1HLDhC$EITOV^_5 z*gLTHp7!lcSm{9#zc)Gf77OOhXC);jCi;l+vAAqL&3_C&5tSXypTD5-swqOex`q2B zgu&a+Qj|q`cZ_*oz9$H}zS&ZeacirG+rVGj6E5|NQK^F9yf~D-Detun zXser-2fevp8}_D`eOiMua&xe$IEKe8@x-F@dj0Lj&h(CFztm1fu9Z4tKxY#gNm!x! zX34cI{ps?XjhLpj^J8XytB6X(cvfk!(i-S>49%g@xf&7jJs_?-hJ|j=EInq*Xg}SbJ@Z8XyWYE zyw0)VMNHPGG){~XwZ5+jOnxp!V8wg|+e;WOuAYLO*2c5$n6pN^;^#Tit>fUpIypIc z=$UP6`?hCMkWfuMyolS445IHn^RE^3>&17}_*tuvJfy{xZfnN58TRf|8k=Jyy;G=Z z?02#ESVXNx^dPe^u9Ao-cL1ZME!F`=xNQ^phtS4m9YNU#xd@l!j6hmE7_ z#YdxRccvwtb+Vw{Vu;p@Z;;;wIoGw?p0 zq`-G)?W(yqk3KrqCAx$5dlN6lro5BN@}SbGIa(vptDwnm3-~Gme&*`+Y%eO+Ak2T6 zjqD|1;2X$%j~kN*_&&b>gTsj3zN&Tjy#57fp*kwjYZ|z>Tk&h9z&_;=`Tk})R>7_G z#_iXTGTk)Z1Y8m1uGM(?nwXG}~96($_844H^xW-^&Fc^uiYV-3>AFaA-@hLxB z4;`>HPbv0##2*&Rwh8Nk>F7917cp(9e^T;eNZ7j{^MRo056&uJ0QK_pBvuHjwb_Ey zaINjc!M|tYMg&g#nhK6SO)QJZ*hZWH^D;}0_D!*7TX;jo%C$S^ju|D%lM)}%&Y3tY zi(V0bU#)DdT{ri+Foa?pUxxu)7R>3{&knG1B}O4|tHS+GkGj!6+&-iE15&~Vajn|m z;&b8L*KR`AxHV)q`->F-{k=(i_wFB`V@ou|jTF#c8ikd1OPJky9yT|E8|r5D3Z_(s z6W({gz8Vl%dwL`~+HDtMOa8QUCpP7$xt#Un7Uz+KJ3#CrYxr1bfsxaVvRN`VuRQSW z-gBSZCUt6HX{1dAu`xyQ=mDBA+0hZ3hhq+rnrW8dL>A!pcG)nyt;i=>@ou*Ejy24) zbZZYK?$TTSIJGqtI(AT3LYUI0RXhGuSZXbIKOAB?N#6I|N4*~M;^mbMDycVc#6Nnz zBJ-q3v!SIe08>AZsp6}Eyw4xXPWtVTPQ9LV?rR2JZ%+2&&>Sehz_0(p42#%FqR?jl zFRx-@33bx6X9^_r!4k5^*{g5IXsF9Wt0ApH9D#TZ7kJuB3x@zLu)L_XVK4`lBcaok zJ!Au@g-{lH`eEC8UAt3{I7OrONGZFS_5%p;51c8o^tfO4Kl|7_%6bRL(Il|7##n1;=JJElkrKWReGH&8)N z;l;!vu5(5!ZmZ$tPYLs9F2MC7Pk@O{C^1;?fi(A=+3@6KGg;C}s}g%2yM)R(yPJfRdW$bAL zc)g0p!7_SIV`vsJd3^%o;%&Phg!N(12whU6{pgx+4)t(Sq9Tqsbw1D=LItZ3Bek8w zOa6S8v|dl!>oh$jwg&JGds4Z9P2n?e!uSt7r3N2JbMBf z9>9`tDG#2S6duQd5=46fS3g|9bKX$!^N#u1&%s#E^uUQ&H+7|lh?*<1$dLJ~+2>Y1 zDUdn6=!&}TG=U#>qb_s<_kA2qot`v!R?D%?!!jKaoxa$E0=p2uW6TBmZXZLC74x;h zDLEr2*7z~7=nt~s!Q!7}K}yO0Bnu?1MraD=^ZNzfqkkdtNiUAz`6QTE#R~AeV^~?_ z35)I#qMB<8ONNc%Zu8zqs3z5y5~JG2r4(DtK)M+}&ZB{*bU$TdAMPhL*wr>;;MSsH zAlI(~XSeka&&sl&JO(L4h4&NHor`NPewVq-gh*a=eS;utROg_H%gW#5Y#;oBJG|6$FdpUK263ILCb^ zU41?%1uyxIcOZ_xN3!*9*7=@TeHDiw#XQqvJ`c}gWP!7+sOLGCceO|e%I%jI+?nz- zKa_E;htZOa;c0xgh`?Uis~yOJpYC|fQu05s{}%idkTwq``5^g=u+&3-hpy0o8z@Pb z{{j8KpueWG;xFaGVf`wL6&<=)knAi05Srp!I+kJ`UxjCwQH*w=aoU|qx#19@8-Q&1Ie?3lv)(MT%4@iEH7`uryuqU zomBfSr@gy_-l5hS?ZwBsHl-%y7h9iLT%zr7@o%hskhVH3%UO=PeRl=irg-wMm3JEu zGMm6#7<@u=(?3BVrKOI=rrIf9U`(1lIXdg6Fvd<~&AU?mezv2%s-xL4F8LXF(?(5!$P3cF$I!~*BanL2gwN?MeUZX@J9NSnRLdlpG+FEt`w&$ z933-gd|ce}tu}aOHx6oNM`CmbjUX2E>xHe0GHN9acJY-lQSA}Fq3q`T()spoKEr>y zn{~v~V&w?GLYVUfQy!ZQjwjnW8m@cb-mA9GJj9Cd1JgMxYE>Zy7e@E@Lof0{1o>Zf zSHjxTIBI3)muK3dE_e0kiprAp=ci0R3tYXLwQm!>EP(S+=9ZK9ANj_6vtahs-05`l z?yle}zJG8qr?}CYK-Oa#X&~3Rw}}^q6csH*+K)3eNuILbpGaqgQM9Lcu~z= z>7&NZ82Q4n2eYO1H;3i(E1RQx%UB;&pd!x zYt(*!cWqXy#rx^9!QCTz@7G>*!E&ysnbKsE%gZBn(kcY zZ2MNnPMGTjZ-D3Di>B~ZNs7qabwg)b+xz`g-OWj+-Q#7|lI=D*Nv7NX!5)mFF(^!f zfbalj{<|{*>PCm{!gt<1BEjZueOGNU!-d7F;ZHU9x%P!tE+AXZUw+WS~NUFG@Bg!GKN5l^WJVum zA?fW(N|tt88WPJiN_ukkhO~m6DfRea=W>jSee2S|){@)j`ZjT;(A7UGs;p^xZL3`Qjdwhl%SZ$ssvN_IHYS~Yxb5?_ju zIS>E@7*UN^Fz>-~0FJd0-axJcC%i9acv2#7$f?I5T3TY~ir8_-D`K?MMF-wdQNBg` zhJ3Z&aM&CQ{JU*g2!%}t=p6>>pZ?UxdkhS3srbI2h+tC4ASjq?K3qCJ3knK{mLJut zJJg(N+TI?MzbApY0{d+jhem}(=B6#9)2DxkmgkPPZplYa%eVJ|VSj5VBz{KJrwEXe zH`fiMvO}7~RB>>JIbPm_)W_cw8H-xbm`Dtkhe?>>^Wt=D#OkEv$;v%)T_AP@xRT_X z<#OC`Az4H`eVv1Vg0eAk)}^BD?jY$?cc)Q;u(w%ibJg%p(|hD~FKVwHLlg0p2YhC4&F&5EF|aK?B{%%|mEt$u{T z22r9l=TR_=OqSQESM1UM>9#%NE#PR4S;xkKVfoRx&U19&iM}dRjTR2UOL@N< z3*&K2LluUktQwn)`iPoQao+nB<3OsT_ZI-tYF8d>3p)D>`$3t$AfY+qVKQ(+{2NNz z+|m}LMcr-&_I>gtFG6Y8yMmb;CTRUs!`V#ZYk51cuK7jvyyGChps=t*<Q@IlJMj=nhi&?03y$5y#6e!LoR0c?GMlYVDZE|tmf zj%AUV^Y_uXQ!_4Gd&6w3|95)8UI3!nNJ66Ivl#i=2;35JZY7+r4yT|r&&@+^Q5>Bj z#Og;_jx5UMl<&gPE1fYf(KuYl4I_8q_|S0_F=#1v6K@?@lUL;A2R=E+oY47xRk@A2 z2lp2Jgt=EfcPr2P5ELp)%-$;{JG-@xc7ceI=lj){LhW{fcgph$J@X8xu$ZCuCS^F8 z>*RWN;O2g$tG!v1vrO`r+a|Oye|T|m_fJGyY+|95!Cd z`HaQ0Y`U$l)}|PE|IbTiSh_}!Q5#T;W>2ZFHsKA!xs;&^n~XWfLiZOPIX{H+Xx*us zC{^vsoZtjYU>i)}pF5}(P#308EIRg*=hJIamCxTpn?I?PTDR8es9-P3=jk#KON!8+;>_a{U2Q^hTSYCkSoM$T=s z;@rxqpP?pUt^CfrgDrR1;Ht<6e(xII!AdojUij&qiYY~Hkh7MNx+GBpB(?`#SIF%G zZ-0-&LH;!qw7wD=?aF< zT*E$}l2nnsYO6?E#ZC#7a#_6W>3z%~GZklJ$wbOhPwk>RrO6oBoj3nIFP@<&FhovG zM#U-)y?wczo0}_&f-Dq@8Z)xNaOMk5Of`3Z)T}bX5TWUKbzuNvDXZ{uV@rG7w+wgO zjSPCWKAogN;o-TBjkm*(_4$TngxT&; zaCm&N<;fH6uH;9^yhq^vuwu_&)*V2N4F1Z_Q`Rqs95Kn|xuJ&wuxT`RlE=9CDFDQ4U|M09IyZW~9h}j@P+nd)uV2 zsOV^4U4@#jqjEgAKAYTMtp`LEA0kx*W3Yp5It4(eXa zk!1@*uNli%IME;5g;Ubem7D0bMy;2p*9!Eglrz@OLsjr@VIgH z;UMS4t4H8nvZIv4iPAry^9e31W9566nd=mU!Sn59eLa52DgIClfv-Pb9m_9z;IqYN zS7Y7t!e3{Tq1I+a_nXV+I4gL$VDfmN%lXDPutrfiYgOF_PtNnbKS}Nn&Py|p{)~Kd ze{K+*GL8RUc+QhnCtB3w^ILvVXswc(XuPF?@DDi-oQu2+x*yenvZ-l+s~Uqrb(TA? zJGj>3R%Wb%+s+D;AqkAZP@+zaoVKip;3~1+J}w#QxVK!9G>GCw8zMjwvRr7+QVB%H(d0wu3zSaOd4a^>- zxbXr6K5rsm>n)b}83v=L3gp(UCg0KflmtFLxeI!Ff~6i1?3OeDZg9}Z>!Uzd+M~ZS zpayB8tTK%S(A*Cff>}js%RrbK74dgM&JQaHxmz!e(4MkjKsh2NwKw{`?6zfAEooW{ z&!xNtK4`S)zv18HFR;XCudR7gR%{zA{sVt+IX;WGbPYdgB&*cf@3uTG`wl>8LgmuC z`}bgoBCl_K3wU{JNvD(sG`PC#P;x-H_%3_g%9k~a8S2wVt5Fv@m`(X=5JxL4X5#!V zwBkk9;7WJ_2l`We!(d9xdrc{{_DB9}7d6I}A0W$(!B~!)>JfI%X-kJA=?cKO`60ApF=VVB zLOsQJ;?Kse0%7V;D%8ziy4#hx4yp^wACL?No^>pNdp9g@oV`+|#XxJpoez|(DR}Mw zT5n{&pyZ%=jNgF=>>k+C%XIh5hYAT)F8@ca3cUUolI5}2$^rU81_yA!3Sx<@ifh(} zyhg^?6wDN!2*B=dr;mGt3Nu_IpNg(?t5%LUBF)Tlv)=&}r?efiAlsI0exh5dQq+ld z6dYKTu&ksx5URZ~Dga~TOltE?rlmt^r1pWp%s@?h<#mi`6lWj@3;M0A#F!47IV zVw%d?c9_u0J{96RsMWq@TEkzKj;b+M#TLB*(MFICB?qeYC8TTFV61nUs6T8wnpoKd^nxMXZwf-8$gO)Sm23pyFihm|gM3OfjKhyoVIC|n&saL4Ty$_=DWec zH8zZ7a%8B%OiBM6w0eSbZA+%}@8D-o^nAWuy}_>Kw&~=)=N27e&EDEE=!FBfC%t^GSi~;>6Mdjh*ymF0Y@C=XhxT*qMA3?E`FydR8{ zVVL#IYr{MEE}V=m}Yhf=>jEaZ83rVO?|M3D}v-K&FsZj@fB}bbPBlsI9_VI-x7CPcYN<~oqo_?lX zz2yZvl_Na3FA zRD7h&%#Qd8rq@~>1*Tt+tNOlqoYQkRI-otl{A{s4;a&6}%FVhKd21!#9c%q}tVgmT zg=?YPEh&^6>ikcv2#pQ1EM!26sn~Nv=X%uqX%LXwPiljrGNSl*l!a)w+kB))x6|g} zju9*aZ$qwquAsqI@BJMlsL|w)@>Wc!_c+P#>lK*X&c~@$rg6glLv8sFClVRkhlv(p zO15hl!1eZwb^wE~0}xq6NmZ7&SZZ+jhL|`r%CpQ{IKy-KQ?rqG6rli$grzt(TbLzy z8>aOc|CqpsUX$mSc?vS$B-n8P(~+4BK|3_5YhC5~W=*WTuQFlGXNPkc`pIo(DR{^z zU`^Aw;)?Th$kV~fzL)$CzF-}ia$Imq(R=e1AzKpjtSFaj9^hL=kk2lmxXGClXvR(2 zwdUU-2D@bXjd`(~VIU{o6RTvbcK{(dhN9-AXc~C6XugG=Bi*#&*|S91bifqW~<0z$}lMwh(L&~lkHW;abA2yyizQqGFB2i|#Yc09nO-|J+YH>3TFPGnRhIFhG|iX z6Fk=__-J^%ePel>6^Bh_Z&SQucM%aJw;eVIgL;74!&?FL{mj2rc78tw7+bjRiq!W< zR9gcaULuB5b{IL*6!dgBvRVEu;}QmrWPGCE26V=)TYsD|%jU{T8p;P#Kqb#K6;EIu zQ5YW)$f%b+aku?jR-%-ySb6xtf)2RY%ShQU2RW@V{xbs$r`t}&Y(7{{BXdKvtn`1$ zTHF`ia8ziy^L#XOjW?_^`i@;XZcvif+_bE%|BNO|Cld-5@v zwN!I_vfCffyd|3AmqUtog=uaWKi9tJI#(i5TG7c`)M~z~hI;yu{9E4(M?4^4)>dubW#>!OfkxySvMCS0*PSIBn>O z_$%^X;a;mj%3mqE1__js_1m0L?0Dw69z8V!)p}ZxBUjVfyN@h%bH$)B;m)YaFZHUg zknhzB$NfLH0u_-%p3!q&U8n{p%h2zYB2*@8_f#0tlfeWZN@;umpk zYtDB`quGlK1nMLdR|I-#^s}*IrzU=k+jomFoD1$NbZ89BKq;OMr}>uzrlPw6QYw%lIPEG)q@cpjwdlNd(vHZRun93a zuja{)HQVBzBX#&#cYEOGS8VC;RXopi0rEcf3GvknCi98en`Yu*$MZ&_&_Xa=Pb;J# z_2d`VBe$5On7!;%9#&=Juw!I&oMqvyWek2Nz`zSXVr`yr>p{>|N0^&wzMTvU8jm~q z5s57o1Vc754Odk-I<73{+WyjM9c^qvz+V(Sez4M!rcWxE_($>Rq$)W42ZrIieYCYt z;GyxUkEi_l;CXyfsr%EXWxhXw&id3e13~L|5~k72t*?5=VY`##Vo{TvbsZ;0n1Ay0 z%|`fK5zqPLJLc9CTEJlCh|MtsXz`O*2%oNKb6{ZW6Pvc$p&;n!DWolyi$TEa!HX@c z#a}6x|M-J;D{y!iT;7%1y%#_N{|0c%z%ZD1nf0{37}Y{wjgPrIwDCOGp~C-InZyhX zfNyY^68``vK0?tO>EewmN2tSfZQ-i%kVRq#wc?prwT;d4IC57QrCg4UwHvOWHD@Zu zr?5h5Y?z(`9mdLT-$um$yoXMuAk%}hZgr3EZuheOzm*%0UyRX!SX|C?@>H=3M>XAI z4Wwo6^^GE1H`O9nYmb|p5l5F_jF@oNq?9<4-$xyi(6mckRNxJ>BDLm%gI7?PmAWLU zI7{B@C-=}~mK5P(jqbt#BmEYec!&UqzTSTQj(mg~`sN?ammz9U^vZjL+Dk8(!;OVo=z%_^{Z=pOn6Mnl5FiyF^b zp7`>h!g59<$<%7e24W4>Drw<(SFv#|V7|Y7hx&or0mh*|#X;HGtt9WLYRYqJL!?o~ zikn87dwq;(>pXqNE);%I=rwrcD-0$yv?=XSNyp-rS*Se@kIx47UrmuE7x-p`D-8 zQv#h8EPm6Ly=#JNQo?^8pR+~T*Pugg*Ln(cTsahtjNevp5T+sMMso7SfMt3e8WVpQ zUKK1{&>!LB)-Ue|k{u-hkB|2qc{!iZ7>-W#*N6=-I%s8gH#&LRR>FMgAS^A6RQl>% z9wYFS85Y`uq-#FhBe-&mPxE))a|##|KKL&k<>wLpIR1WfT;)M=q)kv?Ws{DCF(lG7 zEB~39%7q|geA%L1rWO;>?Z3}{Kz3s>uPvzxL}Mll&a&BqVvkFj5VX?2x!f3h0D>?C(vLU=Z_&ud3vowF&mJT|T0qtWd7SYsojKV%QAptgTwZvaQ1 z(#}TNKB!)mN-N8ew{+*MJz$NqT^3Ss^*{$)Kz9n$Q|g*h@$Ru&ViV0=6yM0eS9--c z7N})h=#q`liO`gx}KI1JSYecAFzI=s5oUi>>t>-bOoO zvb5%bR=1?%k4U)(Srzy!*n!{zG^>)(IL2J)8>WE6LmegMmJ? zkVdqorc78`U1+Hd?TLCmMu?uxQDy_u5>^;YP|Jy;+E%oz_=eVMUyge}5|fYwg`U4R zWcuXgTOVEE;@>FP$P$x0D?j2CP3I03%>TlP=UduA=1)6MP=Kx8`1m-SKU^K$kIbeb zqEBOSnQ6_k z;F)odZ)bR~WBpWOKXtBh+!yjR2=qQ-xW7k&KK2?_WGl5pR0A0`*ZKy2M1n#j-=Za^ zVTprGKxJeK3Jm^nTsN{`C2G7My5&-@)twOd=h4f^DYo!+vNPhru=vr8x`C@=-P-zR zc)Xz7SMjSL)aXl4{hOwm#6-l9KBkk-#F5n?68f1R@EZN&0$Oet0SIsugD;le(l_F! zzUlPGQZ=keZrP7JIH={`<+f0Ox*g#iZVR>6tZ4(!77@)$vqLQ|0QMV#1@f8Lv{WyM zfS0+hS;4W=D#jGG$RYCwFZ}DhKeI;Pb3;5Lgx2k`sduJKUzl=_3`W{`c6F z5QgdS(LT&rR!}4i_qyXw7D$lhxlu_RfKII>6G@0~O8OtZx4^9B2;U6FM#Q#Kwvu^qw6-BK_4jK*LqLQ=lP4)HRKp3oHRl#v+1DG~6S z8NBgSl%9=M>USR>_zg!Wh;h7cM#E_zJi}P4h1?v_h@w#YLi6?JyU8&YSd!G3a$a}E zU*qnX){0v1ht9iH%Tsd6PZYDHq7KV&|7f{hRm`HMFAhf@mror#S3q) z0Dx-+Uqi7DM@a8z#-a2R!dRsZb9HUitvd~;6{dElw{Xm#M}~Ji&MNWReJs1eB%n2FyV!95|I-D zjhzse{WWJviyhN>7ufV35eSf~$ArYr3Id&hxE64e38|RJ&xY2XP)*VYHDbGkl zxU^*o>=?ATl&)#>HADarQAUa-L#v43k(~Ri*iPP2MA{`jM(N#4?-3 z@L5gk5Rc8kfuX9e3vzbbIoG-`Th-1~Pp_+l(b43$_Bx#EgFXiJ;Ke;&%Gd7jT}rtp zcMYU%9vPv@E6qxzk@&qSV8ROhsYG3rFfM{nEG@J3n3tw&riN?unb=l3?RZQq2i|%B zGpTeeD*7si#j{J%L!dPfY*5nkNmr8uRyYW?=Ss0-ByNQ{{9o#s?vQdJu3jKLQQZt& zR_3|Un==!vHV_Ujf6hT_BZ;pv5UN-*Fr!DSpC&mZ>%{u-{xpRtNX) z8>Y`{y!6QHG20KFbgAe2ZR&atz)J2N74m=aP^zjIbO-haMRc3O1~!qKHa9FsD53sidXUThTOdeVwBtU-6j>t|~7oF-59; zJhN_5^1~;{MHvXU0FZrCRiHrIxyG*Y;!x(k)Tx5BTgxQg;yGg40cG|LdDAKPHJ$~x z>|@YU>r`hU*{sxny0B**%fhhED8q{|_$P=%B zy>mXLpl)Z_q-_7PDSYGfy%D9c^M)e(m?}h#h3f_S?No`Oo+vq7E@%0Jr$b$xf^Ff~ zF&bvv1+Mk7lFeeaxO@_Ks(o(f(${8}Q97=edwgsY)oB9W-B!QuF8<#)5*w`XHKQ4* z5&Q{hN5>18L^~GK$#GtLXK=RKTHO6jup>xnHCA8%Fh!ot+WUPQ59N97 zVX!j$Y=%!JnQQsU6vQ)aggk1D8XGNs zSghLY{uBl5zkQ30y^i~aC_>(k+u9?0aX!2*3rQp6KWj@f2K5KQrlArEaYTYWW)$*a zdRs~Ocv@?BfJVs9#3wamY+9D^E?ItHB54l-V)YKst=MB5NBEkG+4EMyJPg0quanda z3QcauD^uf}c5ZrNFZ*j~;Ju~YhK13nbEsU8HP#Ik8GD#x``zle5hK&O=oyk_@sxy& za*b&>;CZQs_L|UMuuo(TO@_B=<5I&ukFnQ=3*9HsBV%71M99`6D>QYf#M#};>+#!~)%1xczi&jXz}%BJHt@tXt7qyi%c?EKs%?~C0K)x# z#sT`m1VH%PCO2$&M!4T=dI%hx*n48?Y=8Ruekup$3)IyG5SGw+SkjZ1-O~fg0(u1{iua<|Ra zdayri20IoHCdqv55ww;hqqwyAyatls7PEOwNHwKxFh+ngk|w6^%`Iw({OOrATb-AT zXny^GFVpmE;5xg&3l7Q=O|QF}aKb^RUwr@kTJFmBBk7gvS|s5><5 z&vfyCzEVW37x%5?p;~JDX7@r22l>qU@+UB^xUFOLM^xpP3!SF8h7+sp#wm`@kDI)w z@JsQiGAhzU0kT&pDY0GPsE~a2jG4i*INO?2N2naGHIjk`ZrJeprsyrY9{W=lT!NZj6hTXDEk)WE>=^-%HXbnj_FHUv_1 z#B1td*)*2E1ppbKtuHn%mp958?=bDTfW4P@?i=S~=#2XE%g~+L!(i1yiwS-S2HAuXKT8rl@u-}f+$SL8Lzq0+o}=@ z6>mH)`w03O)UNt|@Yy2L9BE5ANxYKRli6>zYUK7{O$GJO6QYfnrR^zi8azey*!$8) zXK#8RL2l}p^kjOSh1}a2AbeUIeBoQZGoV`MLLP;(8hGiq%1+m)u}8^M>l>B?XR=Rd)tUuNc0dxiO+purYw2mb z7kkVZcuYW5yXbgoPkfW-x@TNwn?FvF^_WPybZ3yNK_L7Ht`K_|`|&M}0`$NOEDK-l zHD@?B%6K|!s$c6>uMH;SVu?q?hvzGqKqJ)O>$XI5Evt1>gKyCBjw~AlH>lt8KAFoi zBuT8%zv6;HFx@;BJF2kM!L?7jA$lXP!ZRj4w=gR_G8j%5V1gakb6BE#H>{80#g~%2 zuj*uJiZ`dqVGz$xf|1qs{UHDt2 z{MocD&?ZB5!^F8&o!s%5QVDeLOv&87A?7AaYH(fv>X1R6CFyuO>AA9YM0JpOKVYeq zk_Q7e>^tXu58#Q2orqBp_A=oPFfPRSSF*SSKsbi`RMPtAXV+e7LDuA(!$D-N-`g}1K%jPjVWa^}(I)>ZW_)~FQ?mqV>zzM_KE4U{>}65FatU*f~^wykRA3DJg?r(^z!u3&)9F3RyU+F9)46mn4*zz z&I2VAIa?&wSaZ<0TV*mi%A$*QF>^rpw2uiXfTXmK;*0wOs5;}@emDj{N!vEQPhT0o zrN)ZN4HQ`j)*na^?n|P;Oxmq?xxW{*S!7D&TvIY=7u8^RzxAhUAef3}7~xxo(mBSm zLgsQ!J(x@^B_m3HQU`{K}f0HL2$tL5~@v z7}L#_QH!jD_t=^MmR|CPuzHgKY5&AGt)ptQ%s`~@Oc|i|?O<=C{#fB}5CH!Z{3z=_ zWxec<2b7r5$fBqp89=aTfbqf+;QX%PPYdDWg-^T|B@ELOC34x^K z=q7;Q)Fpce5-{M)UX7Yv(leS7SJS_Enx*>&D0rhAoK@KdTs|S-49i#Tqg>EtIna;y z0N%^em7mxp?X)rb_qif%bO#C`VRMHaTw5C8?9u}kd}Wj>?Xa!BFg-VYXj;aozTCH; z;Q%4NO4WHy$ZZRXOq7A;7DZOMvC|4VCssLp7-1b(eAt2-SE{{}-p z_B`}yUQ(N1u3Do7QjHoJ=7wWr1ZNCtd9f*QON2F{v$&}egCKT2B&_W7n|_A*i}Kan z%VpIDnetgWMTK1lH**eAVJd9Q>>A^Hpd=JN-;lBWGJ7=Z9=&zew)&C? z|Ds@kM|Qt(Wpy6|vBSs~tdCV@d|joc2(=Y>(PU@w?%Ct!PEY+P6%=Ag@@9(1#VvL= z6&91E0@GI<>t6z-nZE0n!~6&VjXL^Mu#JZ~;aMWkCAUBo_e4TxTaZ<~&$(@Cajqah z`x{W>VrFC{NQR9pjCivVAh!n-jjJ_R;IpWeLVHQ{qt1ZLu@8cgC`YeF{`Awk zX?)+}^5pW{KZrjC-8a6ad;3A9NOS2uT8oL0m;)A#?_V?&K9z2nztEWoccB}3C*8Le z-#YUbJ5L(QzD94r`aJhm-7f?i)ZAX2#|OT#k^KhK69yY@&29z>v0L$wu0%sNPIuDF zMmqh)b@aM7=?VZ<_{CKzq+&-8_MLSILErgt_qc^4*~zXej0+0V&}d&yl?BvmjojE^ zl0)@eZPc19@Vw_0y4k-~fUgk*&kq-%k&snv^WX`SX|btroN{cb`9O_SWTY@`HXlRB z{^qr!^~uA$z7#?mAgPlA9(2;NNvJl@a}GE!yO)jo;x9{fcO3{rJ^4KfJ;o;e<62Um zzCG5eq>J7w+Bn-6iYw3x#KK#QXAh$e6O>YVi*4U1VCEO^A9dE7D~a^omTWCcJ0LBy zI%?Zjx%L6g^C89V1XjYby4cpzq+S?t>DDWL31@Ad5f#3U)0Lp?tzwiwNs7jE91p1O z%Xf91dglv%Tah*aYf2Cn4m~1fBN_!?DO5I^-ba*md-KH-tZfrCYWGQboMPvm~dbNc!M}YJtBO`K^%imEL zM@56mfRTc79Fa01$_haPwNI_lOSm_4rSCpw61=pYOOW8o3JxJ(+{uR|R|gte(+hvu zUcFAl_}T*U@CBzeyQG%miG%bKV_lw-@DeIn2}4PZ7XTw_-kUQX;zEKAZwO@Y_prTN zfezVl5gw2i6PJxpo^$$^Sc}9}Yr&$Eb&%hNbi0 zd;!U)E!tIy3%8Zt?4}S3UULR0sRs{HZgw`RE}&FId%=pq4~uyL?SYaz3<=^l3oe~v z?TI%Y+2fZ|Q(HJ-;Z1Ixa&t)d*qR1{XZr3hOW$(AIN$e1t7w0>oco9eFeudtM3`9+ zb981E33oIQ^DYx5v{IYucOOY@_e!{aRzOblFwVs{c}DD?&LcnOOokFz7! z=Am-Qt#^poth)7ydmz$~HYJ@8Z!{xK?Ti?7YGikSak2Tk5K-+O_KBnTUf|zrVRto4 zW|vIWeHSm6?7~82inKTjL`S|ueX=C2j=I~cN0&49x*B&xdNn9IAwl}Xhq3-^`(dWy zy_rj112|7MZwhVtH^XPK+NQkCcB7)Df(kS`ixFs9@@l%@m#*@wjso>b+YD8k5_j<^ z9pBC2Uz_j}_V;JZQSB%Xd7DFHr2!vtbs2E-if}C5AJ*NLCl(;TDw?E~xI2np8-sET zTo0vh1cbzvE!s{Qi;RIne|*}=G`%AB>$Sz}-%l+J*K2@VZRvlXINX~MGxugm>~H75 z-6w8SzugbNzt>GK#OfiON*X}&mlojH@2+M>CMOsDNe|&xINVc_oVw{AJZlzSmx8%$ z+1&$nL^jQ~B-t6r>f85pM-{}Gh#2NQA1x`nJJsFU@XhYi>_4uTSsQ7QXEs4B6d-6f ztDBKM%}`xL~hVI7GJ-10mw@o_0O-ft%$ASttBe zjOMVC09(VCs#crS4s2?VB>%oPt9Yq!KK&V+1H`LR0MJ!_bf`gPIeJxD4xUiyKq2h@_jsk3R4 zk$Lu5ozo(%o49&&o+dm88q3KWGMXdNF6xUzM&yMC@A07(3OrDsr{6SidhJ)^FQeTY z;bR-i%$>CP9^V0oMcU{RSk>6(>K9+aB++=<#aG4We-#7lyv*=KyOylKbWYMH?FgUH zTI?6PJ#V*?OKAI1haZ_3@kS{Yr>-cz5R*J4tLg}b{IGm_V_$I6A>=EYvVa>FRDtFR zA#O@qW7Ipb0hZ?*vcoHycFLrHHePb;S=TaLh1vA}L>a{X-ANn&Xitl&hNor=YJIIm zS&@;Xy@m84*~gT3JcBdsAsXIak&$0sHg8>nlvc3J07`t1H`vYZp*5ZiHSOdA!85&W zI-7Am372i;s|6KDMM#wiv_h9y{)-Qhig_1025l6BoB8#|G=_xX-f5DaNQB6{A$bSV zt!8Xq?;37XCl>ZlPA#`cFNe!kCW(ff=leb7CV9N?I<{Ec68Vo;Xy{%Ai&~x@1PX|9 zu|jTNH&$?AI|5&itz~f!55H}qB#<+s^PCUWeM*fkhZ%NtqHjZ|aukqk{aKrlY6D$=QoMR|@B4YI|*JBcH+A3@D`G=`L`HRWgdVvpE@ zZ-{KR(>@f{ZpC!3RWRx%4o5r*_d$b5LQWZqlzPjBkGzuE%~ynPM%h&?v0N`v@k5Tc z+5QO57-k>XD%!HT@4f2_gDS#?EYGe(T`umUV}Y;)dmWGV*F1UAoSnmB29(LKMOm=P za8MQ#>Z8O|WYbq89j8<*amcn>%H7K^%$h}hZ2PGtjrImOdbANEt8;Nq7_!z$Hg-V6 zR*PMhFlEhh8_Ey#K9rn{EtJd{g|*tUqJTX7I{d^tLrE!*k%C2u>taj zORwuo%O1LpYGK90BHSv?i>ULB9)YkriGI~qaf7H`GEtU8J!RvWr7S~_|}`(9Mk6B>Hgw;G{>KQ z+_^IEY)LnL8!Cs+i-7o}F$roT2i)?tGDGm2A>?K_c`4IWTAi2s89jA%Ts+}esUQ^= zc40bT<~G7s1BJIMn{T{vXT_GsCb)SO=Z;qm_!>iuCc`_Wj`xg@aF#Z@G zTn+x{1|#6-YV?Cz{8^dOF|6Y+$9e{&UJ=ntn2p(tIT}Y_9Q# zNazuIsZ69x1_Obu+f}h#rZht{Fl^Gj`<6KL_nA_c{n0p>+MN(zdtTG2ZT z5AZpnO$R)%p# zR($N-ys%g!ukVTynyBxU=yH_TZ97rysI%^uj=mK`YVEjBmOP(%y7 zbr`U7V;;1-nzgZZaHWJtKVOn@&Sm)Ep19wa8~Bu&GvyWaGM$EpOVj;2W8THZr6izp z#TsGG+tvU7%%e`R>NM{Gdyup)>>nqF;4yjShEpaMT^Xap&Pw943-^4_Y|rtOlfV8B|BE3gHi5!78_G90*`SzMw9_x zw&N3QYyhgPuNF=AWfMD={q{4iDlifn*98Re3M%aF!lfl)W)xWD)%#EEd|yZD)CKLM z`LM*#`@&IJP0+*02>$?U-KfhFzsY^-ImoBfTvJ>df;@hY&9vQa)amtk2{?IyT`k?y zLJLlLNmplz!~kUP3g!HcDtNbY+-<7x`p?cE5X!TvmQ(o8_cCnH+_;277}BS<(~d_@ zyX7u1(I&1xH^~S}m?+)@!+mfxzC)Tv_kr^pq%Y>w*pw%RcM`-@Z<#R@jJrD5`&uZ= z=~Uk)Xo}kJolA-fuEoy-x<+Z$Di2USBIG5kr_|gUIQ9<+o;;bJf-S4#9*3@#RhjT! z2>>NSR)*>`+)g33*)LzG6=t9{ZP8HaJqX7jc0ONWdGNW(jL|iBqm*XldD3MIx~%fW z0k2R%GFgbV#NqHWyMeT;#r2B;Xv(kImWhh!iJQ=vj}jB!*e ze@5U`%Hi{ow&{pr-1Sqo$!+~t-T#TWRg}_2$Sw{cqeVJ7qNBA>hXiqR@4%+gm^Z%4VyXBvb%Q<1p~=jQ zTx{Mg;KuhZk}^+<=~Dk;_g06J_*8i?Px1Xf*eqHF5U1TkfHWlV7l693Pm67c(VR3@h1Iscy5 zKabuE)mP#1AMeyW2nb>Tef#jhIF(Y*T9w;q2BaqP}rXlA@|Czgp` zju_HKlmm3E$d%BPd{xnQicf7`tLloZ(Lr_WlQ8{E%J2HnrrxEBjgkOap@wc!&7^W297uCL%meWT5Tbepb=tg{_gMQf~` zl0<1OC^`_@KV~3mFE3x5?A|pnNGK3ee;TwG(a$93Pw*rGL9h+SN}>F*>O=c*X33I;$YmWk}}|nX_U+L zSp0cETKv||rQ4?v?4-6Tk1LE)8(UEA_k`u=;EO{=TOG7`US6)^tYC*7wusvQ*uI)g(s2cXKo%iRPHi#?vM|ZAk11D(5rVuBoImmV)`a2e}d-**spK| z*5hlhaRx{ycGXXrq|3@saIhpC3_jL4+uA#_x$<5(vUt0}Bo-btdHj%0jmwWPawP!M zUib8La49d#X@|Gov6>Jqa@7^sXWQ%D4Lmoh*CwhSENZVy-Z&qVCvo0;I8S%1-QD^> zV_S8%Iy3A-!>Z>8{C!d&afA1tLoXCCNx6H!B=AavIS#4W$6`R-+N~k|Wm>Uw8_(F% zL2cv>U6tUS=^5T0VoXVsst+1S(KjOM zmwJ}Mn>>Q)RB$@Fj<}ciS{!^IWAlaw_==ob@eoIdU*z|E8Q(R69y&aMsCMRF0+#q2 z{779>do)YGh&4{X8GC(sfRW+e7D7Aied&^=lR~U*ihuLmVQQc2M|=~H%RVEZ_1OZp zP{6^LCwSkQgCCk!v!;5Fkng7QF~vc6tfhn5OL&M(c1yb&nnYJM#_1&5vuFCckUzek z`c2w@+B0fdkpn{=`I;TgdERm0eo?6EQR6u}7Fesx8!C5rLajlSPImWbHE zO%B9zlwT)@-0+BNl?NX$GRT_E$!NZTF#IwHdH;=SE+VRH4wZl$1gFg-- zKO3C(0&__GQ18Er3n8I9T_PVFm^nT^_F8J)dr-W&zum?$i&!J5U2A5QSfJBI3|x(M zP88cQsfO+FPQT039>SPK8v_&L)2SEMd&VL+`Og_F zAr>TuX7SHYIbS6DI9m^vMkdnop3Kw!T2tWLssvAGq>tNsy`2^XnVD^RHg^O883||> zL>pSIgTQL`QtsAn>jUI2F2dyCLvH)v(3<90>Af;*ts&^mm{I-BhInI*2buP@2g51H zH|yn1T}(1AN#~tSfpLE@NnOYfoQIs?>h0`|;uO5kSDLOhE9&4wt9|c$e))D_@+Rrq z_iv@OU|e!@tQd8xlpd!G$i|hObxla$SvSH7Ev#W92ukNCzl0@shYfFqTO&1b(QtaG zudl8Xi%Al*U=SONq@$+l?Id9a7rG%qw>53@&Gqkl#%b1{n4qfEC0N2Wk$PcLB;LgC zu$sB-|0_zsRi!jlfmnM`X~(i}ANU4M4ED5yfi3DO}w?^_}Gk+D;jFo zc$5}z6qfwDGqkN8G2iq9MdFgQzxB}6YQ|;mHLHItlqqZ>(M$6PUyCp=6|8fyBTKCx zM_l*)tD?-SUne!Ydjy4AUfN&%I}#GY@hi?0k+>jo|p=w@2TUY%m{SU+I+Q@`!sppM{ z^Q-d~D`zbuvxz)G9awWx=cdG5?)~l_bRSK3HYq?+yHmns0#o9HSpS{(4_@H4w7 zk2!FQce*v{VxxqmgVEAv!}!}B7`HrBa6V|JeQlE|?F!qn(TAOC^5k{1hd&HrMahg@ zF(N8Vc)kK}VrhMKSqeU+ec**IYIC0x?G7-)elGDPm zC-%em{oEf$Q(jhtY5sz%!Tt3b=rsJiV&iOw@L|Fs5{gW0Pl6iGcSCpsZR5t>)QU(# zteaT!{+DUFHGYffAOk8_lu`4QwmFP8uFB*i8Ot*L?MOQHGep6j?DXngx<)NxM<;Yt z)IBrTL;6Q9T`b7)m2D7c)+iTQzxofyTLHhgQkLzHwFmJQLKHNQr;5X41Q{sro&BGr zi7`|@A}zt4Q;(DllDQJWHq>v{1}4n;^y3F6 z>rZHVcS}V2Gto(Y+NtP^|9k$-mLfe8jDxZ!JvgazI?0e#E@}wc4fdhK;y7@ueD8js z&tW+$Au+L5!%xCu= zXB+nB6%AHd(4(=ks4;bT?m^P(8sPm~o$;435TW5b*4ilhy~}S2Cq;o6F~rHI_%8fpF<9 z!Hva7V#%p8ePnfLuW_9u`oE=-4jo_UapcU{WZRw@PgCrJ9M1PR8vKZ-TpJHqGq2eL z0s}fzg77TE<`4g7DXY$>G(=C08@`o>X0_d6YARw@%#R1G&ZpCA)t4 zlV%$uA|rEhbBU&7j8=X$Sews~9lL|cc_$qh8t*)6-S4?D4B`Dkem-p8rOEr()Q99f z^}5@aXzSl9K>ZaLAJYEqpY$V~`5ZkCkFy_%{^U34uku@BI04MSe1ryc9&z9=7-jd? zY$K(eUW1*Z=PngVQzcJx2W|)+1&J{b#@E zQ20!n72rza(C`AuC!Y9efUnK%%vcA$%fIYdRLdeO(|tDQUm+M_13N-rYh9$F4%Psr z(YwpTeKTEQpgsv}MHB;%n1U_#H`Z<<^dyQ1+ zPhf_NdPhGXM`wXfZmzdM3+6Ar&oqK&NKqsI4YGIE@b7ja&pw+m&%m&+q0wD44rXk; zK3cI zdAoWzn_@bETTWDYumimQ@@eNvQ?Fa2B=no}h{OTcrg_e4d(zLKmqeDk1nqz2f7Xtu z=APKc@Vaus!Unh+d5`sHVD@P2F}E5IN$-wdN|qi9qt;=!a@x_#qzmkFv=U_ZWXzmP z$#$Y~noSr=Irri|NT<`ep4d0Es3)!!-I;ugK|~~Hp&vBiycREUWro)u+I4g;z_>{e z-sikZ*vL$qP#7nKnY>TULmvbW-pG`07-~(cN-Wg4vO4#(x&aLzM4zIIJj}4;Nd?6* zN7kRbls>#dzJy9e27oJI9}`N zkDGhzhBU<&e&8~i9_uAB8AeWd*QqDUqT)oa$s7HgU*ZIyKN^(R{_&mC2=vvK zcI%LVCl9l1DKU&|zruHPe=K?|?zRCx_V%1VXW@#XX;!t(N_osi)Tnqj>Dy`sE%sXF zrg3&kt>9H|7m;pcjqTVcJV3@{a=`G&$F{9^GiP>PFF#(~m!>JY~EGv>kBJ|3OwU5?FP zdTn^zFxGRV`Ayx`Z2Esn{KiY32c(1Jq>cMMILIw&4?_*%)nxJJM_eaMXyaz7rJPpt zFq9ffu@>G>cck8Q)4C~bP_SGxM5ou}OgDj6WH!2jWq!&BDZBj#)=G@XpZAVPt!(M< znzH*#N*Z=XSxLJv@N<~aUWd+=8M|Z##;#1YK76V+)=1?jlGN>Q5L4 zLy9WUZr}R}cgfFRjSYFyMlyZs3jKo39m6j5gn63-dgvJqM*F;u7(wgv#uD3To33?O zx!6M&_i4P~>YFvf?E-WfS;=j0LFz5f?^dL|R8HO8F0fzmV&!TQ!j3G|aau;p+IHr&2^_MM(1 zJKKu};6}w2%|OMb-nKiim(|fn(=I=L%amNtBO$po%%ctBI68u*&Y^Z*#`BGEz(9DuZkFbR~68UC-#z5QX zxyWCRtD9k!7bH}SA4OfP@M$aeGxwKub)Ec!nTluJ&+<`hl#8BQ#z_Ex*nabtX>%On zf&T6KLXZ#euDkWST1TlDIcHY*hBvyuOyb>|xyrG^$2lYBldK*jBPYj5z%a{jFKE9| zz^qN?>!nMtVF;zlt1=^B{YzN!-r{*G)|=0b^S$FLwwV#EypN`jrb>-cHW75H6wjs@ zUfDossX2pU8+Z>~;t!`WDJb{}&SDeF{PX+7_3|ohQyM}3*(m71r~LwG)t$baH$1Yq z93?E)6aj}c=oJSz*>|jS(jGQa;!0%P_>^Y)VMZAfBj!hkQmDa325S>KJ_GIK_4V1F z?5n_6#&UtF`PHFso)I>gd-vLhgmlhQ(Vug`I~55-dK{fy9ak!h4mFCfey-}j9#tSu z)52OMm%LgvDHqY-NpxyN7EJHj4y2!Pv^T%XTiZ44nl^{`mYhs)Z^tneDyt&2Y<~8V z=FteY?E3j`Y3E;BfczKv9zg+RfF}*+Pb2k->AxvuiRrGQMM52toHUdiFk;-$T| zTjyhGqaW~a`JCIUUwXN9>b+#M)GpUwxp354={e)2U`>Q{e5ws9gws01Fz6`%NU@Z_ zvg57$XMkz!Uk0S$zqrj85fRjV$O$cdnVA*LyODDsOKsA+p}v zJP^JxAXsyf({nQX-t*^Q-Vj$Rt6%C(g~mAW4y;p?%8}G1_6$evOUs-FzZHM>yqyNoU!?izr2~W;DkLt%A~cI8{@Ek>m5SOa z8CepP7i{|(+O)w|a{@;VCDU*ZRAnq#jIbAL% zBrH)S5;Qyj_QwjpHe_Pdx=Ym34RAX36CyNZI($yN-7UAJI-D~?!O+KqDFtVW*o|ntZ1sKDn5#PYk2RZ1qS_f`&!!baPkqjgcM^rJ`8hM_6M?$)#1cF0a;7@|xUCY#J{}_(MeyPf0fp0yyaC21t6c zoO?c{7TDy1Lk=I9>R$wt(^^mUcKerlVhc(7-yh&wFZd`^Z!+Yu&LlQqcWkuOUx`0O zp&$`<(#G_Ri#`$Y5?jN&)9`Uptaz-hf=l5|?MhLW0Wx`F_hOJ57Ie0(j9YD_H>#Wt zAXAY&ck;YuqsYzhjSHsQ_rVXk5!FslQC0i`>l(khi^w1}P8?kP0%fgG9UtVWjL-4?etsz@>Oplm?*t(eh#t={2$rBZyO#o}4J ziaIWJrMFw3@8yT;-5ebiWoy>K%RGZt)2BDBKiHbh@a|433XgoY+!s)hNv!$oe}#a1 zvLL#e!!5i&Raebf?i*K$>gE@}BsNS+Tw?@l&WRTu=u8jlvbi)lVt8s>KLr~$Hh!f8 zIrQQCN+>)xukoYE^}V^Uuxv|8BtYf#1VUK;u^YH!ctONbMq@<7?KrvR@BuE&C@|xH zF9H4x6H3cmWJ13(qSGG<2D1x;hoB_Yxd*I$e zNlK=|^J3j@ODqUf$M>!eY1~s){!Er^u0l6Uq5Ui2?9M1jBXtIEDxsyQIR1VcuC(~| zwA%on_*cf--RczS{perOxX3U6$JZ?TtLy8p{uJ`RKpP}h_k3z0%QiHmxcC@*^<}VZ{YXEDjIVq zSN2JaJAPg?fR$1p;;~;mY@J9F6QZ}%sPK{hPb2Ri?2kZKy>F;Sh~I}4y3f;mYzRL! zZsCxP@$wyV?6%SOf&<3Y=#hzoQPi`SoTtUlIid3lqkKl#?}u?ldg z!*ZQxzZWxYXEfRA(9zGBqvb%bech73f6j5CE22JTYQ*?~#V1T)>p-XjCWJAozrGwx z%IRq4XXsB4U{SPaP;~kWL;PgC*x}(L3YIG%`cQi?FdhRH*2@Sw;XUgBS6c7KWt0Rr zvyJnW28g^Y`Eu!MT*OGp*c6%rg;4Q#N{Efg3wUh2d!(7EvWHozF|llU<=>&w7;%xv zcu-cr?o{gkewq9ku=E~*j!VK_8#j$_JZmaPH;u70+_IBV7Q9Mn2AiD%TYB)Wk!H zbXr1pC4*UiNPdc?ld}8Si4dQ>>%$gzYpmi>rM66a10FIK+l+W`f{z+1|@P>|1xX z)#sd2u#=&^6^A93(fwT$;X;DkHwZdI%5lB>a$xLP{=`1N)R)sI%)GD7Mt!fp!sT!h z4rHrNMVxzaY)>KjawQ?{pGD~8ylcI{XXWj-Xb+gV>rUnBUF#vsf_w6-Zs&w#pgIsT ze)96SYX(SXsXGUj+iji!mi0pX)B!5vjUCz;PNR@6t;v++Fai&Ei79yn0#-7%q*JWt z*tk#-Vds@SaW_bpvaBe!{`8|s8TymfR@92O;1uq&@bV)v8;XnUD;>r)3-aHKo=wQ? z?CcD@G~vJE>Dnw-pTB2aN%P>%&GGAS9ojyKwX=um5qg|mVpO0{Ag-8DK+?dfEE`%1 zaD?ZqgC#S+8bIfU}6UM(BKtea^h}v?Hd4>HBa;QPMf*? zdo>LSbs@wx>Ix@5iE4VZgn^xWv@NmLz@nqoT45L2n*hOmUf^||lkfIFpbnmY#J^$` z5x*V%Hj>jZT(uy9U*1YR*ehi!s2iO*XT~Eo*A&uSaB2k3nB=q|e5VUo!V`*X6(55Y?!8bQ|Z zis_o00mME4y5389vojpLr@pse!Dn0T@aE!Q3Ka=F)4@`-&G~65I$wEh@;N?!qz{G* z@OIy`>L92a6MXmenHm?0ceZyJ8RzSm;G|j+I1y;_&=<6K|F>~|NG*B&3+ z3cCnlNti}!7+IzvLE9i>Gr4zT5al=uh55-Ng*}=Ikt}0aWfD_(^5Kd!V5Mw9N2cC8 zG}X~*$x*CO{j8L>?-_SYzVzK5f%H)8!zP`0n({5!%v-1Yso@F}mUk=+zPxjlu|itRRGL)yZr*_Gwur2*&Ei zZIhV>WNes%QK$>Q+A8rNKtjyQh}04EG95hGL~q5xL1mSe1dnNRrX@v?y4g{9GXnVg zY{3KT1~QEBiA2WGS{#4X?%|yXI9}%X8;#o_&!zpn+>G89jb+EyZ9$f!tANB1-#~WKin!I+- zvxB79-oHv4YyBp~k%bkCnMrKHqp|Vg_4QR{+cI|-ZIk=A`F>)xxbU8cEeASBMon}4 zY`zZ?YLVwPjY*8JvtEBff+`{u^MDl_fygtJ)oo?#zGUhG4 z^%=QH$DG)e{>qq${{XhcjUoQsFA401cefjF%&PwX;@WP1Le^A8I;PDNNLp>}$AE4w z14@^%GB-zCJ`u|+OD)0qEb%+A+ioNwApx&65dsl}SDNUpZ4l)679a0AQ?&B0tcOJ@ zBo2D$KQbzKi309PI=b@Neuq(}mV^j0(bOF_GJpJ>JuU?-&JpGvN z;%d(2SLFwPe`%NBPo)7IBLDcE?|%H)?RUk6Ur45>1<*q8@gvL=XoloC-w?P^LC9ZqLK`uV2_+sdFoS?Xp&33~gqj(5FBt zId}O!|8ErT@|xi+%uhfXfU`?5^PjMNQ+0N=45J04z1Y)l3nC&D`aFV^q{YKHYMZ&q zl)Nv{H|3yd-gG_SURB(rOuTkkRmMJgPo2tkf8e=1!mr@~KY?K@4UJ9n1ND1-nUT8! zZqZ43^OeSeBRnn1=mw9YLGN6?`sIe*c;B9tTaN~+-e5CJW1Ot?(bs?b#CNRA692wy z(rj_F5J6fS?_F>ByHO`QI*XnF4!-F2&G#C#r^UA#fWx&7kcHtNsa-Fwd%Vlt9&%--Gz$e9!LJ+XIxZ>#B-x# zwSz``hDR(W0yhFhWGYWqmQ>krcMWESl5T)AQx&@}Z*DvvnrYelM?zFmE}?&q4}g$? z^ah@ni6=a{H;147vPXYnd=9scPsMN-pErzsCnhrSiI{LPLS9wS01R&+dA@^ufpO7m zO`lwpUmMcpjn7Y@g;{B=EO@H9A0XJ}cY7lxU`|q8bsu`ReS5`X%ecD>jP~KYKB3Vj z9?DBvtBc3k$`=%q8~ho^JFb{e48MIz4&f4Qs|fo_H12eeiY36`)+V8J@kE&}u`Az% zSsK+w@5Fv&UO}#>(9!ACI8sjE=*)J0p!}QM!C(X;MVr?_)jMr5oDW$xQzeFiPh(=< zK^^k3s^*w^`=2!Kn%o?=7zEz#XglxOEFm9gH?Q1Y5fGlJpKS%z!4bqHikxP9YK=)c z4ejHnWJ2QapUKW1+tt2syH&Z$Nm-HX@fZbD&s*$d=$<&{uV+?)oSo@9H#a)qF?E5` ztiwS;{{H2{#COT$zKK%@>+$r~I1AU8W702yF}Kj<8kO55-5|p~=xri~q8t<^r$t%R z_KPiWMn^>n!&BeRZuIAvis|N_-s!dGZJAOyP{`d`RPA4Sq|R^8u)+glamy z@0>RFf#+dhffuypzkc`)dLh_6_>k zeayJmp|%%7$nIyX)YS10;RQ4ns1Xl_gLp4ua-lF)^r|`a<`KUcL^BRE1liskNB;Iq z>7emxR;46{tcN(_r{OFy9$-B5;6LO0;l^1aWrh^?7KaUtaP0;wRSs zFmrr-{;%B)jw}nCX*3GJ8@&_4Y zn=Yladd+vW$Gatt+!vNWbzbhX4+Q}hZvGuZ7C!{t0v2|2vap&_sG;FT=N||7`K*kv zi*_A#b%&Me!}vQmo*>|r@L_B}5?C3D2-i9}$<(BMxkIM=K?sX>-Z_9XjO}!zIIQSQS!t>38P(-|GEK5DYYWDv^F1-#s!&nt_8D$Vg*phm2k^rL z>^%%_L?>rS@MLF1`U%6Zy7a2|=G_KNSjBCGglbt73yvXeQnRsp@ub|O zZ>y{_SsWculzW*S$W2JBmge4Bf>FkEt=Kzl4s}Gubrn(&3MMq6FAWFnO+(5c#^cRs1Is zN~21tE0LhGGp(enVFikQ9-GtTOh=MLsm|4URw8}(bX!}#zN!Ei)SL>0!M(tzMEW{q z>PR0jZuWrDy@5W?8M<6zk8itbaLeL?vse9B;_0m3J1sEl4%Xp5Y{U-3see1WpHnp_qI0C(B(Od ziIBtYF$tvwU@{dyT<9OUwL4v`LH2uW_9p0IQZ8xzVT@Iy8-#-FW?g9Cgl?m~B#ngI zEjSQuKYnmwsQVPU(xR@lro#~d%ucY!$||+;z^zH<(DUi1;2#j3fLG)^aT4?p^Aizs z<&9?cxd)7wThW!C%zT1l?!7Ph!&KB#+F5WTQP`+xC5b&K_9->`DOhrCwouIz6Wrl!WY>Aoy}n)@Yl*YF5q}E8 z05&>*I^rI;;xsh^L}EwDY5Do^>)wa1n3Zpku8(FI&eKdnR5|s5yQtxuP)QI|Otc`WnhuYA1cNCc<-LvN z4`I{x&=A7fz^w0S!r!IPzj?53XcXB1v+Pl;2#r*qU)*aLvs1^>ttukK(&Ai{!Ne=* zI#n#zr9rdB!)|gUF4!WJE_1XlO|eszizKoJ7PYZ4G6)-J)WUW8P6Q*~?VAkvYhwwV zDDk&17OoUH?iW76^r#Oh>rZsr^_1@a*x$K}qRq=Jx_8m~?quF^QgbM%Ywn$2UedI$ zvP*%r69Zuobl^qE33h+~A=?7Y8kml8BVG+WRR2lYJgK8K|9$AXLwH2l=Nz`O)Av)~ z>K5((p0f4J_lgNF^Qe{8DMRM)Mph!kt=1K0c?0(x)Tp|so*4NJ-zUGv*}5En#mtmP zY+NgWcI(PVMz=e;H?ae8CaR-T5W3!c^_s{56Cg%Udpc%gv(RRZV~Q+STIvL1o%rx3 zNziL+riAq)QD6Ry{4b`q>2)3T%I5-TCc)*!{le z!+U=3IluFs_q^|i^E}W0|9>9tIMKOn0$VGv1od~2I7=@WFcG4FAZI#NhVF>FS2(u8 zsCXL!)j^90-sXx0h;jOStWv=U_*z3R+=3Q9ywv!S^U%W&mi@l}I4qI%=6JMU3O%@M z^3rX`@Ts)?!( ziuN7JMfHWBd%`fKezn#wRpX$ zJt#R88Sr)yvsSX1n|CJeP)X_Y_k0xP{Or;x1>foW02IVRU^kd2BO`yo$=>!-pR4;| zaX)>;ZH-aje|7R3p|Tg?XR^q;bomD%TwIWow;sMlZE~g2dePd&pXLK7wii z1<>}WPRLxFC*HJvJHX~lUcmdqm~I?C(XbfiJN-*{#SKof;7>Vy|7c91smwf0$+w1d z;T)C+xA>7)O^|eQalHs-b%wO3qfm?T_*P{DqBr*W^-4cjymLe;{Q9#zl;e(GP`C%E3;Jp|o~u}s8|kbfm@o0)^(9?@*gj(Tt+SfdD^rsrrUMR;VY1Ak9aJ~y_r<1On=ds+WA#m@F za>HV)h2~Bkn)i~lV0v1zg)S$$|AJ;*L8M|~$jFt}RKMxfWlS__N3i>EK6HD~ocg;* zpw^#UM#FlA!c(M~SQE{^t;fXz{|h+z2){gX`S=SVi-o*M#lriVj9)sn3@+3xj<-gS zH&%zxL2>X9q)%GR&Ic4{Hs&j1V=juqtm=x&YI+3D^|th#q8rfOB(jPEm>d z&8~`ShJ&4_j_(m%-$-lskS0_SwYUi(1j(alc5c)=lzF!a^0G=61ws@UGR5w_LWEeX z1!hHCyYx=@92qMzTTzc6DK%SoUTsw{%t^wLaG<~$VIc$&CUzCGnwmbFDl$-Q+faPx zX0XJuY(D4Q8#oC0Duxn*uC07X$Iav?YVhup*s$&3qz?#f^tXY=+GrrqHffGi^>aC{ z=#|zcH|8o+SQFVX^LiWfO+77QUDyNOD+|~oI(6!L^e=;t2R4&b~t#0_!2RcAC z*tVDPx3-$EbHc9s8&G_r^76L?cMI_wkD>YSYOmE7E($E-3d?1domrA@gm^ai~4wvg4BF^e6F4;3J zRxPo4KeP8mi=@&Fa|x1aG^&|lqpP9~DV#n?jM)J)yNj=Q{e zxcH*(D}LMH*68*{?yM_!mThkBc=bk;+;2-<=JpbCOOQVg-djx*^x5nip}Lvb;$)`N zodXvJ_-j>C+NlyIk&^|+{Mp=kZw-I1>?48g*ri&@+_KYusrsbvbPQ_HnU@apy&U{g zUX#FsP(Y&mYo$Q%(Xs(PkUv=|8uPW6etFTQj|5{SVCpg;1PX|)OH6K9@q8m4xG_j} zCTm}9q-CUhk}Y{}PmG`J?)8&W1bV+Q0*This tutorial explains how to use a threaded PCL-based point cloud visualizer. - \subpage tutorial-json
This tutorial explains how to read and save data in the portable JSON format. It focuses on saving the data generated by a visual servoing experiment and exporting it to Python in order to generate plots. - \subpage tutorial-synthetic-blenderproc
This tutorial shows you how to easily generate synthetic data from the 3D model of an object and obtain various modalities. This data can then be used to train a neural network for your own task. +- \subpage tutorial-spc
This tutorial shows you how to monitor if a signal is "in control" using Statistical Process Control methods. */ /*! \page tutorial_munkres Munkres Assignment Algorithm diff --git a/tutorial/mean-drift/tutorial-meandrift.cpp b/tutorial/mean-drift/tutorial-meandrift.cpp index 3e2b6701ba..2e3ea1887a 100644 --- a/tutorial/mean-drift/tutorial-meandrift.cpp +++ b/tutorial/mean-drift/tutorial-meandrift.cpp @@ -43,6 +43,7 @@ namespace TutorialMeanDrift { + //! [Enum_For_Test_Choice] /** * \brief Enumeration that permits to choose which process test to use. * @@ -57,6 +58,7 @@ typedef enum TypeTest COUNT_TYPE_TEST = 5, /*!< Number of different aavailable methods.*/ UNKOWN_TYPE_TEST = COUNT_TYPE_TEST /*!< Unknown method.*/ }TypeTest; +//! [Enum_For_Test_Choice] /** * \brief Permit to cast a \b TypeTest object into a string, for display purpose. @@ -296,6 +298,7 @@ unsigned int meanDriftArrayToNbActivated(const bool array[vpStatisticalTestAbstr return nbActivated; } +//! [Structure_Parameters] /** * \brief Structure that contains the parameters of the different algorithms. */ @@ -335,6 +338,7 @@ typedef struct ParametersForAlgo m_test_nbactivatedalarms = meanDriftArrayToNbActivated(m_test_activatedalarms); } }ParametersForAlgo; +//! [Structure_Parameters] } int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanDrift::ParametersForAlgo parameters, @@ -342,12 +346,15 @@ int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanD { const float dt = 10.f; // Emulate a 10ms period + //! [Plot_Init] vpPlot plotter(1); plotter.initGraph(0, 1); plotter.setTitle(0, "Evolution of the signal"); plotter.setUnitX(0, "Frame ID"); plotter.setUnitY(0, "No units"); + //! [Plot_Init] + //! [Test_Creat] unsigned int idFrame = 0; vpStatisticalTestAbstract *p_test = nullptr; switch (type) { @@ -372,15 +379,15 @@ int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanD } if ((type == TutorialMeanDrift::HINLKEY_TYPE_TEST) && parameters.m_hinkley_computealphadelta) { + // Initialization of Hinkley's test in automatic mode delete p_test; p_test = new vpStatisticalTestHinkley(parameters.m_hinkley_h, parameters.m_hinkley_k, true, parameters.m_test_nbsamples); } + //! [Test_Creat] float signal; - std::cout << "Actual mean of the input signal: " << mean << std::endl; - std::cout << "Actual stdev of the input signal: " << stdev << std::endl; - std::cout << "Mean drift of the input signal: " << mean_drift << std::endl; + //! [Test_Init] // Initial computation of the mean and stdev of the input signal for (unsigned int i = 0; i < parameters.m_test_nbsamples; ++i) { vpGaussRand rndGen(stdev, mean, static_cast(idFrame) * dt); @@ -388,15 +395,17 @@ int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanD p_test->testDownUpwardMeanDrift(signal); ++idFrame; } + //! [Test_Init] std::cout << "Estimated mean of the input signal: " << p_test->getMean() << std::endl; std::cout << "Estimated stdev of the input signal: " << p_test->getStdev() << std::endl; + //! [Loop_Monitor] float mean_eff = mean; bool hasToRun = true; vpStatisticalTestAbstract::vpMeanDriftType drift_type = vpStatisticalTestAbstract::MEAN_DRIFT_NONE; while (hasToRun) { - vpGaussRand rndGen(stdev, mean_eff, vpTime::measureTimeMs() * 1e3 + static_cast(idFrame) * dt); + vpGaussRand rndGen(stdev, mean_eff, static_cast(idFrame) * dt); signal = rndGen(); plotter.plot(0, 0, idFrame - parameters.m_test_nbsamples, signal); drift_type = p_test->testDownUpwardMeanDrift(signal); @@ -408,6 +417,9 @@ int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanD ++idFrame; } } + //! [Loop_Monitor] + + //! [Failure_Debrief] std::cout << "Test failed at frame: " << idFrame - parameters.m_test_nbsamples << std::endl; std::cout << "Type of mean drift: " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift_type) << std::endl; std::cout << "Last signal value: " << signal << std::endl; @@ -444,8 +456,10 @@ int testOnSynthetic(const TutorialMeanDrift::TypeTest &type, const TutorialMeanD p_test->getLimits(limitDown, limitUp); std::cout << "\tLimit down = " << limitDown << std::endl; std::cout << "\tLimit up = " << limitUp << std::endl; + //! [Failure_Debrief] std::cout << "End of test on synthetic data. Press enter to leave." << std::endl; std::cin.get(); + delete p_test; return EXIT_SUCCESS; } @@ -673,6 +687,9 @@ int main(int argc, char *argv[]) std::cout << " Shewhart's test set of WECO rules : " << (parameters.m_shewhart_useWECO && (opt_typeTest == TutorialMeanDrift::SHEWHART_TYPE_TEST) ? TutorialMeanDrift::wecoRulesToString(parameters.m_shewhart_rules) : "N/A") << std::endl; std::cout << " Shewhart's test use WECO rules : " << (opt_typeTest == TutorialMeanDrift::SHEWHART_TYPE_TEST ? TutorialMeanDrift::boolToString(parameters.m_shewhart_useWECO && (opt_typeTest == TutorialMeanDrift::SHEWHART_TYPE_TEST)) : "N/A") << std::endl; std::cout << " Alarm factor Sigma test : " << (opt_typeTest == TutorialMeanDrift::SIGMA_TYPE_TEST ? TutorialMeanDrift::numberToString(parameters.m_sigma_h) : "N/A") << std::endl; + std::cout << " Actual mean of the input signal: " << opt_mean << std::endl; + std::cout << " Actual stdev of the input signal: " << opt_stdev << std::endl; + std::cout << " Mean drift of the input signal: " << opt_meandrift << std::endl; return testOnSynthetic(opt_typeTest, parameters, opt_mean, opt_meandrift, opt_stdev); } From 94cd90125c7a9d75f0a56437d5fbbe39618184dd Mon Sep 17 00:00:00 2001 From: rlagneau Date: Fri, 8 Mar 2024 11:54:52 +0100 Subject: [PATCH 077/164] [DOC] Documented the SPC classes --- doc/tutorial/misc/tutorial-spc.dox | 2 +- .../visp3/core/vpStatisticalTestEWMA.h | 26 ++++++- .../core/vpStatisticalTestMeanAdjustedCUSUM.h | 40 +++++++++- .../visp3/core/vpStatisticalTestShewhart.h | 75 ++++++++++++++----- .../visp3/core/vpStatisticalTestSigma.h | 20 ++++- .../math/misc/vpStatisticalTestShewhart.cpp | 4 +- tutorial/mean-drift/tutorial-meandrift.cpp | 2 + 7 files changed, 139 insertions(+), 30 deletions(-) diff --git a/doc/tutorial/misc/tutorial-spc.dox b/doc/tutorial/misc/tutorial-spc.dox index 8ce166f961..cc32c5d384 100644 --- a/doc/tutorial/misc/tutorial-spc.dox +++ b/doc/tutorial/misc/tutorial-spc.dox @@ -8,7 +8,7 @@ if a signal is "in control". In this tutorial, we will use a Statistical Process Control method to monitor if a -random signal following a Gaussian law is "in control". +random signal following a normal distribution is "in control". \subsection tuto-spc-intro-methods Available methods diff --git a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h index b2df53beaa..134debf418 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h +++ b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h @@ -43,13 +43,35 @@ /** * \ingroup group_core_math_tools - * \brief Class that permits to perform Exponentially Weighted Moving Average mean shift tests. + * \brief Class that permits to perform Exponentially Weighted Moving Average mean drft tests. + * + * The EWMA test is designed to detect drift in the mean \f$ \mu \f$ + * of an observed signal \f$ s(t) \f$. + * + * The test signal \f$ w(t) \f$ is computed as follow: + * + * \f$ w(0) = \mu \f$ + * + * \f$ w(t) = \alpha s(t) + ( 1 - \alpha ) * w(t-1) \f$ + * + * Be \f$ \sigma \f$ the standard deviation of the input signal \f$ s(t) \f$. + * + * A downward alarm is raised if: + * \f$ w(t) <= \mu - 3 * \sigma * \sqrt{ \frac{\alpha}{2 - \alpha}}\f$ + * + * An upward alarm is raised if: + * \f$ w(t) >= \mu + 3 * \sigma * \sqrt{ \frac{\alpha}{2 - \alpha}}\f$ + * + * To detect only downward drifts of the input signal \f$ s(t) \f$ use + * 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: float m_alpha; /*!< Forgetting factor: the higher, the more weight the current signal value has.*/ - float m_wt; /*!< Test signal such as m_wt = m_alpha * y(t) + ( 1 - m_alpha ) * m_wtprev .*/ + float m_wt; /*!< Test signal that permits to raise an alarm.*/ float m_wtprev; /*!< Previous value of the test signal.*/ /** diff --git a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h index 5bdd6f06f5..fdb9f09ebf 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h +++ b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h @@ -44,17 +44,49 @@ /** * \ingroup group_core_math_tools * \brief Class that permits to perform a mean adjusted Cumulative Sum test. + * + * The mean adjusted CUSUM test is designed to detect drift in the mean \f$ \mu \f$ + * of an observed signal \f$ s(t) \f$. + * + * Be \f$ \delta \f$ the amplitude of the mean drift we want to detect. + * Two test signals are computed at each iteration: + * + * \f$ S_-(t) = max\{0, S_-(t-1) - (s(t) - \mu) - \frac{\delta}{2}\} \f$ + * + * \f$ S_+(t) = max\{0, S_+(t-1) + (s(t) - \mu) - \frac{\delta}{2}\} \f$ + * + * A downward alarm is raised if: + * \f$ S_-(t) >= thresh\f$ + * + * An upward alarm is raised if: + * \f$ S_+(t) >= thresh\f$ + * + * To ease the understanding of the detection threshold \f$ \delta \f$ and the + * alarm threshold \f$ thresh \f$, ViSP implemented these two thresholds as + * a multiple of the standard deviation of the signal \f$ \sigma \f$: + * + * \f$ \delta = k \sigma , k \in R^{+*} \f$ + * + * \f$ thresh = h \sigma , h \in R^{+*} \f$ + * + * To have an Average Run Lenght of ~374 samples for a detection threshold \f$ \delta \f$ + * of 1 standard deviation \f$ \sigma \f$, set \f$ h \f$ to 4.76 . + * + * To detect only downward drifts of the input signal \f$ s(t) \f$ use + * 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: float m_delta; /*!< Slack of the CUSUM test, i.e. amplitude of mean shift we want to be able to detect.*/ - float m_h; /*!< Alarm factor that permits to determine the limit telling when a mean shift occurs: limit = m_h * m_stdev . + float m_h; /*!< Alarm factor that permits to determine the limit telling when a mean shift occurs: \f$thresh = h * \sigma \f$ . To have an Average Run Lenght of ~374 samples for a detection of 1 stdev, set it to 4.76f*/ float m_half_delta; /*!< Half of the amplitude we want to detect.*/ - float m_k; /*!< Detection factor that permits to determine the slack: m_delta = m_k * m_stdev .*/ - float m_sminus; /*!< Test signal for downward mean shift: S_-(i) = max{0, S_-(i-1) - (y_i - m_mean) - m_delta/2}.*/ - float m_splus; /*!< Test signal for upward mean shift: S_+(i) = max{0, S_+(i-1) + (y_i - m_mean) - m_delta/2}.*/ + float m_k; /*!< Detection factor that permits to determine the slack: \f$\delta = k * \sigma\f$ .*/ + float m_sminus; /*!< Test signal for downward mean shift: \f$ S_-(t) = max\{0, S_-(t-1) - (s(t) - \mu) - \frac{\delta}{2}\} \f$.*/ + float m_splus; /*!< Test signal for upward mean shift: \f$ S_+(t) = max\{0, S_+(t-1) + (s(t) - \mu) - \frac{\delta}{2}\} \f$.*/ /** * \brief Compute the upper and lower limits of the test signal. diff --git a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h index 22e9d66a3d..5dcfc37723 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h +++ b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h @@ -44,7 +44,30 @@ /** * \ingroup group_core_math_tools - * \brief Class that permits a Shewhart test. + * \brief Class that permits a Shewhart's test. + * + * Be \f$ s(t) \f$ the signal to monitor, \f$ \mu \f$ and \f$ \sigma \f$ the mean and standard deviation + * of this signal when it is "in control". + * + * A downward alarm is raised if: + * \f$ s(t) >= \mu - 3 \sigma \f$ + * + * An upward alarm is raised if: + * \f$ s(t) >= \mu + 3 \sigma \f$ + * + * Additionnally, we can activate the WECO's rules that have been + * proposed by the Western Electric Company to add additionnal verifications: + * - An alarm is raised if two out of three consecutive points fall beyond the \f$2\sigma\f$-limit, on the same side of the mean \f$ \mu \f$ + * - An alarm is raised if four out of five consecutive points fall beyond the \f$1\sigma\f$-limit, on the same side of the mean \f$ \mu \f$ + * - An alarm is raised if eight consecutive points fall on the same side of the mean \f$ \mu \f$. + * + * The user can decide to use or not the WECO's rules. Additionnally, the user can choose which WECO's + * rule(s) to activate. + * + * To detect only downward drifts of the input signal \f$ s(t) \f$ use + * 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 @@ -52,12 +75,12 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma public: typedef enum vpWecoRulesAlarm { - THREE_SIGMA_WECO = 0, - TWO_SIGMA_WECO = 1, - ONE_SIGMA_WECO = 2, - SAME_SIDE_WECO = 3, - NONE_WECO = 4, - COUNT_WECO = 5 + THREE_SIGMA_WECO = 0, /*!< When a \f$ 3\sigma \f$ alarm was raised.*/ + TWO_SIGMA_WECO = 1, /*!< When a \f$ 2\sigma \f$ alarm was raised.*/ + ONE_SIGMA_WECO = 2, /*!< When a \f$ 1\sigma \f$ alarm was raised*/ + SAME_SIDE_WECO = 3, /*!< When a alarm raised when 8 consecutive points lie on the same side of the mean \f$ \mu \f$ was raised.*/ + NONE_WECO = 4, /*!< When no WECO's rule alarm was raised.*/ + COUNT_WECO = 5 /*!< Number of WECO's rules that are implemented.*/ } vpWecoRulesAlarm; static std::string vpWecoRulesAlarmToString(const vpWecoRulesAlarm &alarm); @@ -68,17 +91,17 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma static const int NB_DATA_SIGNAL = 8; unsigned int m_nbDataInBuffer; /*!< Indicate how many data are available in the circular buffer.*/ float m_signal[NB_DATA_SIGNAL]; /*!< The last values of the signal.*/ - bool m_activateWECOrules; /*!< If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + bool m_activateWECOrules; /*!< If true, activate the WECO's rules (NB: it increases the sensitivity of the Shewhart control chart but the false alarm frequency is also increased.)*/ - bool m_activatedWECOrules[COUNT_WECO - 1]; /*!< The WECO rules that are activated. The more are activated, the higher the + bool m_activatedWECOrules[COUNT_WECO - 1]; /*!< The WECO's rules that are activated. The more are activated, the higher the sensitivity of the Shewhart control chart is but the higher the false alarm frequency is.*/ int m_idCurrentData; /*!< The index of the current data in m_signal.*/ - vpWecoRulesAlarm m_alarm; /*!< The type of alarm raised due to WECO rules.*/ - float m_oneSigmaNegLim; /*!< The mean - sigma lower threshold.*/ - float m_oneSigmaPosLim; /*!< The mean + sigma lower threshold.*/ - float m_twoSigmaNegLim; /*!< The mean - 2 sigma lower threshold.*/ - float m_twoSigmaPosLim; /*!< The mean + 2 sigma lower threshold.*/ + vpWecoRulesAlarm m_alarm; /*!< The type of alarm raised due to WECO's rules.*/ + float m_oneSigmaNegLim; /*!< The \f$ \mu - \sigma \* threshold.*/ + float m_oneSigmaPosLim; /*!< The \f$ \mu + \sigma \* threshold.*/ + float m_twoSigmaNegLim; /*!< The \f$ \mu - 2 \sigma \* threshold.*/ + float m_twoSigmaPosLim; /*!< The \f$ \mu + 2 \sigma \* threshold.*/ /** * \brief Compute the upper and lower limits of the test signal. @@ -141,8 +164,10 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma /** * \brief Construct a new vpStatisticalTestShewhart object. * - * \param[in] activateWECOrules If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + * \param[in] activateWECOrules If true, activate the WECO's rules (NB: it increases the sensitivity of the Shewhart * control chart but the false alarm frequency is also increased.) + * \param[in] activatedRules An array where true means that the corresponding WECO's rule is activated and false means + * that it is not. * \param[in] nbSamplesForStats The number of samples to compute the statistics of the signal. */ vpStatisticalTestShewhart(const bool &activateWECOrules = true, const bool activatedRules[COUNT_WECO - 1] = CONST_ALL_WECO_ACTIVATED, const unsigned int &nbSamplesForStats = 30); @@ -150,15 +175,17 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma /** * \brief Construct a new vpStatisticalTestShewhart object. * - * \param[in] activateWECOrules If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + * \param[in] activateWECOrules If true, activate the WECO's rules (NB: it increases the sensitivity of the Shewhart * control chart but the false alarm frequency is also increased.) + * \param[in] activatedRules An array where true means that the corresponding WECO's rule is activated and false means + * that it is not. * \param[in] mean The expected mean of the signal. * \param[in] stdev The expected standard deviation of the signal. */ vpStatisticalTestShewhart(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1], const float &mean, const float &stdev); /** - * \brief Get the alarm raised by the last test due to the WECO rules. + * \brief Get the alarm raised by the last test due to the WECO's rules. * * \return vpWecoRulesAlarm The type of raised alarm. */ @@ -172,7 +199,11 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma * * \return float The signal. */ - inline float getSignal() const +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + inline virtual float getSignal() const override +#else + inline virtual float getSignal() const +#endif { return m_signal[m_idCurrentData]; } @@ -187,8 +218,10 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma /** * \brief (Re)Initialize the test. * - * \param[in] activateWECOrules If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + * \param[in] activateWECOrules If true, activate the WECO's rules (NB: it increases the sensitivity of the Shewhart * control chart but the false alarm frequency is also increased.) + * \param[in] activatedRules An array where true means that the corresponding WECO's rule is activated and false means + * that it is not. * \param[in] nbSamplesForStats The number of samples to compute the statistics of the signal. */ void init(const bool &activateWECOrules, const bool activatedRules[COUNT_WECO - 1] = CONST_ALL_WECO_ACTIVATED, const unsigned int &nbSamplesForStats = 30); @@ -196,8 +229,10 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma /** * \brief (Re)Initialize the test. * - * \param[in] activateWECOrules If true, activate the WECO rules (NB: it increases the sensitivity of the Shewhart + * \param[in] activateWECOrules If true, activate the WECO's rules (NB: it increases the sensitivity of the Shewhart * control chart but the false alarm frequency is also increased.) + * \param[in] activatedRules An array where true means that the corresponding WECO's rule is activated and false means + * that it is not. * \param[in] mean The expected mean of the signal. * \param[in] stdev The expected standard deviation of the signal. */ diff --git a/modules/core/include/visp3/core/vpStatisticalTestSigma.h b/modules/core/include/visp3/core/vpStatisticalTestSigma.h index 94476df584..3c0f10facd 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestSigma.h +++ b/modules/core/include/visp3/core/vpStatisticalTestSigma.h @@ -45,6 +45,24 @@ * \ingroup group_core_math_tools * \brief Class that permits a simple test comparing the current value to the * standard deviation of the signal. + * + * Be \f$ s(t) \f$ the signal to monitor, \f$ \mu \f$ and \f$ \sigma \f$ the mean and standard deviation + * of this signal when it is "in control". + * + * Be \f$ h \f$ a user-defined alarm factor. + * + * A downward alarm is raised if: + * \f$ s(t) >= \mu - h \sigma \f$ + * + * An upward alarm is raised if: + * \f$ s(t) >= \mu - h \sigma \f$ + * + * \f$ h \f$ is often set to 3 if we assume the \f$ s(t) \f$ follows a normal distribution. + * + * To detect only downward drifts of the input signal \f$ s(t) \f$ use + * 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 @@ -129,7 +147,7 @@ class VISP_EXPORT vpStatisticalTestSigma : public vpStatisticalTestAbstract * * \return float The signal. */ - inline float getS() const + inline virtual float getSignal() const { return m_s; } diff --git a/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp index 794e8aea27..cc1be99cec 100644 --- a/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp @@ -88,7 +88,7 @@ vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestShewhart::detectDown return vpStatisticalTestAbstract::MEAN_DRIFT_NONE; } if ((m_signal[m_idCurrentData] <= m_limitDown) && m_activatedWECOrules[THREE_SIGMA_WECO]) { - m_alarm = vpWecoRulesAlarm::THREE_SIGMA_WECO; + m_alarm = THREE_SIGMA_WECO; return vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD; } if (!m_activateWECOrules) { @@ -160,7 +160,7 @@ vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestShewhart::detectUpwa return vpStatisticalTestAbstract::MEAN_DRIFT_NONE; } if ((m_signal[m_idCurrentData] >= m_limitUp) && m_activatedWECOrules[THREE_SIGMA_WECO]) { - m_alarm = vpWecoRulesAlarm::THREE_SIGMA_WECO; + m_alarm = THREE_SIGMA_WECO; return vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD; } if (!m_activateWECOrules) { diff --git a/tutorial/mean-drift/tutorial-meandrift.cpp b/tutorial/mean-drift/tutorial-meandrift.cpp index 2e3ea1887a..181e94906d 100644 --- a/tutorial/mean-drift/tutorial-meandrift.cpp +++ b/tutorial/mean-drift/tutorial-meandrift.cpp @@ -32,6 +32,8 @@ //! \example tutorial-meandrift.cpp +#include //std::memcpy + #include #include #include From 54a2513d0419809f81ed6c3739a01a56811a1e08 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Fri, 8 Mar 2024 16:37:27 +0100 Subject: [PATCH 078/164] [TEST] Added unit tests for SPC classes --- .../visp3/core/vpStatisticalTestShewhart.h | 2 +- .../math/misc/vpStatisticalTestShewhart.cpp | 2 +- modules/core/test/math/testSPC.cpp | 809 ++++++++++++++++++ tutorial/mean-drift/tutorial-meandrift.cpp | 8 + 4 files changed, 819 insertions(+), 2 deletions(-) create mode 100644 modules/core/test/math/testSPC.cpp diff --git a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h index 5dcfc37723..584658b0ec 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h +++ b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h @@ -86,9 +86,9 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma static std::string vpWecoRulesAlarmToString(const vpWecoRulesAlarm &alarm); static const bool CONST_ALL_WECO_ACTIVATED[COUNT_WECO - 1]; + static const int NB_DATA_SIGNAL = 8; protected: - static const int NB_DATA_SIGNAL = 8; unsigned int m_nbDataInBuffer; /*!< Indicate how many data are available in the circular buffer.*/ float m_signal[NB_DATA_SIGNAL]; /*!< The last values of the signal.*/ bool m_activateWECOrules; /*!< If true, activate the WECO's rules (NB: it increases the sensitivity of the Shewhart diff --git a/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp index cc1be99cec..b30bcf0a1f 100644 --- a/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp @@ -104,7 +104,7 @@ vpStatisticalTestAbstract::vpMeanDriftType vpStatisticalTestShewhart::detectDown // Reinit for next iteration nbAbove2SigmaLimit = 0; nbAbove1SigmaLimit = 0; - if (m_signal[id] <= m_mean && m_activatedWECOrules[SAME_SIDE_WECO]) { + if (m_signal[id] < m_mean && m_activatedWECOrules[SAME_SIDE_WECO]) { // Single-side test ++nbAboveMean; } diff --git a/modules/core/test/math/testSPC.cpp b/modules/core/test/math/testSPC.cpp new file mode 100644 index 0000000000..407330060b --- /dev/null +++ b/modules/core/test/math/testSPC.cpp @@ -0,0 +1,809 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * + * Description: + * Test various Statistical Process Control methods. + */ + +/*! + \example testSPC.cpp + \brief Test various Statistical Process Control methods. +*/ + +#include +#include + +#include +#include +#include +#include +#include + +bool initializeShewhartTest(const float &mean, const float &stdev, const bool &verbose, const std::string &testName, vpStatisticalTestShewhart &tester) +{ + const bool activateWECOrules = true; + tester.init(activateWECOrules, vpStatisticalTestShewhart::CONST_ALL_WECO_ACTIVATED, mean, stdev); + bool isInitOK = true; + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT_INIT = vpStatisticalTestAbstract::MEAN_DRIFT_NONE; + vpStatisticalTestAbstract::vpMeanDriftType drift; + unsigned int i = 0; + while ((i < vpStatisticalTestShewhart::NB_DATA_SIGNAL - 1) && isInitOK) { + drift = tester.testDownUpwardMeanDrift(mean); + isInitOK = (drift == EXPECTED_DRIFT_INIT); + if (isInitOK) { + ++i; + } + } + if (!isInitOK) { + if (verbose) { + std::cerr << "\t" << testName << " test initialization failed: " << std::endl; + std::cerr << "\t\ts(t) = " << tester.getSignal() << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\t\tlim_- = " << limitDown << std::endl; + std::cerr << "\t\tlim_+ = " << limitUp << std::endl; + std::cerr << "\t\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\t\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT_INIT) << std::endl; + } + } + return isInitOK; +} + +void usage(const char *name) +{ + std::cout << "SYNOPSIS " << std::endl; + std::cout << name << "[--mean ] [--stdev ] [-v, --verbose] [-h, --help]" << std::endl; + std::cout << "\nOPTIONS" << std::endl; + std::cout << " --mean" << std::endl; + std::cout << " Permits to set the mean of the input signal." << std::endl; + std::cout << std::endl; + std::cout << " --stdev" << std::endl; + std::cout << " Permits to set the standard deviation of the input signal." << std::endl; + std::cout << std::endl; + std::cout << " -v, --verbose" << std::endl; + std::cout << " Activate verbose mode." << std::endl; + std::cout << std::endl; + std::cout << " -h, --help" << std::endl; + std::cout << " Display the help." << std::endl; + std::cout << std::endl; +} + +bool getOptions(int argc, const char **argv, float &opt_mean, float &opt_stdev, bool &opt_verbose) +{ + int i = 1; + while (i < argc) { + std::string argname(argv[i]); + if ((argname == "--mean") && ((i + 1) < argc)) { + opt_mean = std::atof(argv[i + 1]); + ++i; + } + else if ((argname == "--stdev") && ((i + 1) < argc)) { + opt_stdev = std::atof(argv[i + 1]); + ++i; + } + else if ((argname == "-v") || (argname == "--verbose")) { + opt_verbose = true; + } + else if ((argname == "-h") || (argname == "--help")) { + usage(argv[0]); + return false; + } + else if ((argname == "-c") || (argname == "-d")) { + // Arguments given by CTest by default, do nothing + } + else { + usage(argv[0]); + std::cerr << "Error: unrecognised argument \"" << argv[i] << "\"" << std::endl; + return false; + } + ++i; + } + return true; +} + +int main(int argc, const char **argv) +{ + float opt_mean = 0.f; + float opt_stdev = 1.f; + bool opt_verbose = false; + + bool isParsingOk = getOptions(argc, argv, opt_mean, opt_stdev, opt_verbose); + if (!isParsingOk) { + return EXIT_FAILURE; + } + + bool success = true; + + // vpStatisticalTestEWMA tests + { + if (opt_verbose) { + std::cout << "------ vpStatisticalTestEWMA tests ------" << std::endl; + } + const float alpha = 0.1f; + vpStatisticalTestEWMA tester(alpha); + + // ---- Upward drift test ---- + { + tester.init(alpha, opt_mean, opt_stdev); + + // w(t = 1) >= mu + 3 sigma sqrt(alpha / (2 - alpha)) + // <=> alpha s(t=1) + (1 - alpha) mu >= mu + 3 sigma sqrt(alpha / (2 - alpha)) + // <=> s(t=1) >= (1 / alpha) (alpha mu + 3 sigma sqrt(alpha / (2 - alpha)) + float signal = (1.f / alpha) * (alpha * opt_mean + 3.f * opt_stdev * std::sqrt(alpha / (2.f - alpha))); + signal += 0.5f; // To be sure we are greater than the threshold + vpStatisticalTestAbstract::vpMeanDriftType drift = tester.testDownUpwardMeanDrift(signal); + if (drift != vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD) { + success = false; + if (opt_verbose) { + std::cerr << "Upward drift test failed: " << std::endl; + std::cerr << "\tw(t) = " << tester.getWt() << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\tlimit_up = " << limitUp << std::endl; + } + } + else if (opt_verbose) { + std::cout << "Upward drift test succeeded." << std::endl; + } + } + + // ---- Downward drift test ---- + { + tester.init(alpha, opt_mean, opt_stdev); + // w(t = 1) <= mu - 3 sigma sqrt(alpha / (2 - alpha)) + // <=> alpha s(t=1) + (1 - alpha) mu <= mu - 3 sigma sqrt(alpha / (2 - alpha)) + // <=> s(t=1) <= (1 / alpha) (alpha mu - 3 sigma sqrt(alpha / (2 - alpha)) + float signal = (1.f / alpha) * (alpha * opt_mean - 3.f * opt_stdev * std::sqrt(alpha / (2.f - alpha))); + signal -= 0.5f; // To be sure we are greater than the threshold + vpStatisticalTestAbstract::vpMeanDriftType drift = tester.testDownUpwardMeanDrift(signal); + if (drift != vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD) { + success = false; + if (opt_verbose) { + std::cerr << "Downward drift test failed: " << std::endl; + std::cerr << "\tw(t) = " << tester.getWt() << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\tlimit_down = " << limitDown << std::endl; + } + } + else if (opt_verbose) { + std::cout << "Downward drift test succeeded." << std::endl; + } + } + } + + // vpStatisticalTestHinkley tests + { + if (opt_verbose) { + std::cout << "------ vpStatisticalTestHinkley tests ------" << std::endl; + } + + const float h = 4.76f, k = 1.f; + vpStatisticalTestHinkley tester(h, k, opt_mean, opt_stdev); + const unsigned int HINKLEY_NB_DATA = 4; + const float HINKLEY_SAMPLE = 2.f * opt_stdev; + + // Hinkley's test upward drift + { + const float HINKLEY_DATA[HINKLEY_NB_DATA] = { HINKLEY_SAMPLE, HINKLEY_SAMPLE, HINKLEY_SAMPLE, HINKLEY_SAMPLE }; + const vpStatisticalTestAbstract::vpMeanDriftType HINKLEY_EXPECTED_RES[HINKLEY_NB_DATA] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD }; + bool isTestOk = true; + unsigned int id = 0; + vpStatisticalTestAbstract::vpMeanDriftType drift; + while ((id < HINKLEY_NB_DATA) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(HINKLEY_DATA[id]); + isTestOk = (drift == HINKLEY_EXPECTED_RES[id]); + if (isTestOk) { + ++id; + } + } + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "Upward drift test failed: " << std::endl; + float Tk = tester.getTk(), Nk = tester.getNk(); + std::cerr << "T(k) = " << Tk << " | N(k) = " << Nk << " => S+(k) = " << Tk - Nk << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "lim_+ = " << limitUp << std::endl; + std::cerr << "drift type : " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "expected drift type : " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(HINKLEY_EXPECTED_RES[id]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "Upward drift test succeeded." << std::endl; + } + } + + // Hinkley's test downward drift + { + const float HINKLEY_DATA[HINKLEY_NB_DATA] = { -1.f * HINKLEY_SAMPLE, -1.f * HINKLEY_SAMPLE, -1.f * HINKLEY_SAMPLE, -1.f * HINKLEY_SAMPLE }; + const vpStatisticalTestAbstract::vpMeanDriftType HINKLEY_EXPECTED_RES[HINKLEY_NB_DATA] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD }; + bool isTestOk = true; + unsigned int id = 0; + vpStatisticalTestAbstract::vpMeanDriftType drift; + while ((id < HINKLEY_NB_DATA) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(HINKLEY_DATA[id]); + isTestOk = (drift == HINKLEY_EXPECTED_RES[id]); + if (isTestOk) { + ++id; + } + } + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "Downward drift test failed: " << std::endl; + float Sk = tester.getSk(), Mk = tester.getMk(); + std::cerr << "S(k) = " << Sk << " | M(k) = " << Mk << " => S+(k) = " << Mk - Sk << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "lim_- = " << limitDown << std::endl; + std::cerr << "drift type : " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "expected drift type : " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(HINKLEY_EXPECTED_RES[id]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "Downward drift test succeeded." << std::endl; + } + } + } + + // vpStatisticalTestMeanAdjustedCUSUM tests + { + if (opt_verbose) { + std::cout << "------ vpStatisticalTestMeanAdjustedCUSUM tests ------" << std::endl; + } + + const float h = 4.76f, k = 1.f; + vpStatisticalTestMeanAdjustedCUSUM tester(h, k); + tester.init(h, k, opt_mean, opt_stdev); + const unsigned int CUSUM_NB_DATA = 4; + const float CUSUM_SAMPLE = 2.f * opt_stdev; + + // Mean adjusted CUSUM test upward drift + { + const float CUSUM_DATA[CUSUM_NB_DATA] = { CUSUM_SAMPLE, CUSUM_SAMPLE, CUSUM_SAMPLE, CUSUM_SAMPLE }; + const vpStatisticalTestAbstract::vpMeanDriftType CUSUM_EXPECTED_RES[CUSUM_NB_DATA] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD }; + bool isTestOk = true; + unsigned int id = 0; + vpStatisticalTestAbstract::vpMeanDriftType drift; + while ((id < CUSUM_NB_DATA) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(CUSUM_DATA[id]); + isTestOk = (drift == CUSUM_EXPECTED_RES[id]); + if (isTestOk) { + ++id; + } + } + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "Upward drift test failed: " << std::endl; + std::cerr << "\tS+(k) = " << tester.getTestSignalPlus() << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\tlim_+ = " << limitUp << std::endl; + std::cerr << "\tdrift type : " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\texpected drift type : " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(CUSUM_EXPECTED_RES[id]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "Upward drift test succeeded." << std::endl; + } + } + + // Mean adjusted CUSUM test upward drift + { + const float CUSUM_DATA[CUSUM_NB_DATA] = { -1.f * CUSUM_SAMPLE, -1.f * CUSUM_SAMPLE, -1.f * CUSUM_SAMPLE, -1.f * CUSUM_SAMPLE }; + const vpStatisticalTestAbstract::vpMeanDriftType CUSUM_EXPECTED_RES[CUSUM_NB_DATA] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD }; + bool isTestOk = true; + unsigned int id = 0; + vpStatisticalTestAbstract::vpMeanDriftType drift; + while ((id < CUSUM_NB_DATA) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(CUSUM_DATA[id]); + isTestOk = (drift == CUSUM_EXPECTED_RES[id]); + if (isTestOk) { + ++id; + } + } + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "Downward drift test failed: " << std::endl; + std::cerr << "\tS-(k) = " << tester.getTestSignalMinus() << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\tlim_- = " << limitDown << std::endl; + std::cerr << "\tdrift type : " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\texpected drift type : " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(CUSUM_EXPECTED_RES[id]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "Downward drift test succeeded." << std::endl; + } + } + } + + // vpStatisticalTestShewhart tests + { + if (opt_verbose) { + std::cout << "------ vpStatisticalTestShewhart tests ------" << std::endl; + } + const bool activateWECOrules = true; + vpStatisticalTestShewhart tester(activateWECOrules, vpStatisticalTestShewhart::CONST_ALL_WECO_ACTIVATED, opt_mean, opt_stdev); + + // Upward drift test + { + if (opt_verbose) { + std::cout << "Upward drift tests" << std::endl; + } + + // 3-sigma test + { + bool isInitOK = initializeShewhartTest(opt_mean, opt_stdev, opt_verbose, "3-sigma", tester); + if (!isInitOK) { + success = false; + } + else { + const float signal = 3.5f * opt_stdev; + vpStatisticalTestAbstract::vpMeanDriftType drift = tester.testDownUpwardMeanDrift(signal); + vpStatisticalTestShewhart::vpWecoRulesAlarm alarm = tester.getAlarm(); + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT = vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD; + const vpStatisticalTestShewhart::vpWecoRulesAlarm EXPECTED_ALARM = vpStatisticalTestShewhart::THREE_SIGMA_WECO; + if ((drift != EXPECTED_DRIFT) || (alarm != EXPECTED_ALARM)) { + success = false; + if (opt_verbose) { + std::cerr << "\t3-sigma test failed: " << std::endl; + std::vector s = tester.getSignals(); + std::cerr << "\t\ts(t) = [ "; + for (size_t i = 0; i < s.size(); ++i) { + std::cerr << s[i] << " "; + } + std::cerr << "]" << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\t\tlim_+ = " << limitUp << std::endl; + std::cerr << "\t\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\t\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT) << std::endl; + std::cerr << "\t\tdetected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(alarm) << std::endl; + std::cerr << "\t\texpected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(EXPECTED_ALARM) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "\t3-sigma test succeeded " << std::endl; + } + } + } + + // 2-sigma test + { + bool isInitOK = initializeShewhartTest(opt_mean, opt_stdev, opt_verbose, "2-sigma", tester); + if (!isInitOK) { + success = false; + } + else { + const unsigned int NB_SAMPLES = 3; + const float DATA[NB_SAMPLES] = { 2.75f * opt_stdev, 1.5f * opt_stdev, 2.5f * opt_stdev }; + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT[NB_SAMPLES] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD }; + const vpStatisticalTestShewhart::vpWecoRulesAlarm EXPECTED_ALARM[NB_SAMPLES] = { vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::TWO_SIGMA_WECO }; + vpStatisticalTestAbstract::vpMeanDriftType drift; + vpStatisticalTestShewhart::vpWecoRulesAlarm alarm = tester.getAlarm(); + unsigned int i = 0; + bool isTestOk = true; + while ((i < NB_SAMPLES) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(DATA[i]); + alarm = tester.getAlarm(); + isTestOk = ((drift == EXPECTED_DRIFT[i]) && (alarm == EXPECTED_ALARM[i])); + if (isTestOk) { + ++i; + } + } + + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "\t2-sigma test failed: " << std::endl; + std::vector s = tester.getSignals(); + std::cerr << "\t\ts(t) = [ "; + for (size_t i = 0; i < s.size(); ++i) { + std::cerr << s[i] << " "; + } + std::cerr << "]" << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\t\tlim_+ = " << limitUp << std::endl; + std::cerr << "\t\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\t\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT[i]) << std::endl; + std::cerr << "\t\tdetected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(alarm) << std::endl; + std::cerr << "\t\texpected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(EXPECTED_ALARM[i]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "\t2-sigma test succeeded " << std::endl; + } + } + } + + // 1-sigma test + { + bool isInitOK = initializeShewhartTest(opt_mean, opt_stdev, opt_verbose, "1-sigma", tester); + if (!isInitOK) { + success = false; + } + else { + const unsigned int NB_SAMPLES = 5; + const float DATA[NB_SAMPLES] = { 2.75f * opt_stdev, 1.5f * opt_stdev, 0.5f * opt_stdev, 1.5f * opt_stdev, 2.5f * opt_stdev }; + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT[NB_SAMPLES] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD }; + const vpStatisticalTestShewhart::vpWecoRulesAlarm EXPECTED_ALARM[NB_SAMPLES] = { vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::ONE_SIGMA_WECO }; + vpStatisticalTestAbstract::vpMeanDriftType drift; + vpStatisticalTestShewhart::vpWecoRulesAlarm alarm = tester.getAlarm(); + unsigned int i = 0; + bool isTestOk = true; + while ((i < NB_SAMPLES) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(DATA[i]); + alarm = tester.getAlarm(); + isTestOk = ((drift == EXPECTED_DRIFT[i]) && (alarm == EXPECTED_ALARM[i])); + if (isTestOk) { + ++i; + } + } + + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "\t1-sigma test failed: " << std::endl; + std::vector s = tester.getSignals(); + std::cerr << "\t\ts(t) = [ "; + for (size_t i = 0; i < s.size(); ++i) { + std::cerr << s[i] << " "; + } + std::cerr << "]" << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\t\tlim_+ = " << limitUp << std::endl; + std::cerr << "\t\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\t\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT[i]) << std::endl; + std::cerr << "\t\tdetected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(alarm) << std::endl; + std::cerr << "\t\texpected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(EXPECTED_ALARM[i]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "\t1-sigma test succeeded " << std::endl; + } + } + } + + // Same-side test + { + bool isInitOK = initializeShewhartTest(opt_mean, opt_stdev, opt_verbose, "Same-side", tester); + if (!isInitOK) { + success = false; + } + else { + const unsigned int NB_SAMPLES = 8; + const float DATA[NB_SAMPLES] = { 2.75f * opt_stdev, 0.5f * opt_stdev, 1.5f * opt_stdev, 0.5f * opt_stdev, 2.75f * opt_stdev, 0.5f * opt_stdev, 1.5f * opt_stdev, 0.5f * opt_stdev }; + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT[NB_SAMPLES] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD }; + const vpStatisticalTestShewhart::vpWecoRulesAlarm EXPECTED_ALARM[NB_SAMPLES] = { vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::SAME_SIDE_WECO }; + vpStatisticalTestAbstract::vpMeanDriftType drift; + vpStatisticalTestShewhart::vpWecoRulesAlarm alarm = tester.getAlarm(); + unsigned int i = 0; + bool isTestOk = true; + while ((i < NB_SAMPLES) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(DATA[i]); + alarm = tester.getAlarm(); + isTestOk = ((drift == EXPECTED_DRIFT[i]) && (alarm == EXPECTED_ALARM[i])); + if (isTestOk) { + ++i; + } + } + + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "\tSame-side test failed: " << std::endl; + std::vector s = tester.getSignals(); + std::cerr << "\t\ts(t) = [ "; + for (size_t i = 0; i < s.size(); ++i) { + std::cerr << s[i] << " "; + } + std::cerr << "]" << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\t\tlim_+ = " << limitUp << std::endl; + std::cerr << "\t\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\t\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT[i]) << std::endl; + std::cerr << "\t\tdetected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(alarm) << std::endl; + std::cerr << "\t\texpected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(EXPECTED_ALARM[i]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "\tSame-side test succeeded " << std::endl; + } + } + } + } + + // Downward drift test + { + if (opt_verbose) { + std::cout << "Downward drift tests" << std::endl; + } + + // 3-sigma test + { + bool isInitOK = initializeShewhartTest(opt_mean, opt_stdev, opt_verbose, "3-sigma", tester); + if (!isInitOK) { + success = false; + } + else { + const float signal = -3.5f * opt_stdev; + vpStatisticalTestAbstract::vpMeanDriftType drift = tester.testDownUpwardMeanDrift(signal); + vpStatisticalTestShewhart::vpWecoRulesAlarm alarm = tester.getAlarm(); + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT = vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD; + const vpStatisticalTestShewhart::vpWecoRulesAlarm EXPECTED_ALARM = vpStatisticalTestShewhart::THREE_SIGMA_WECO; + if ((drift != EXPECTED_DRIFT) || (alarm != EXPECTED_ALARM)) { + success = false; + if (opt_verbose) { + std::cerr << "\t3-sigma test failed: " << std::endl; + std::vector s = tester.getSignals(); + std::cerr << "\t\ts(t) = [ "; + for (size_t i = 0; i < s.size(); ++i) { + std::cerr << s[i] << " "; + } + std::cerr << "]" << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\t\tlim_- = " << limitDown << std::endl; + std::cerr << "\t\tlim_+ = " << limitUp << std::endl; + std::cerr << "\t\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\t\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT) << std::endl; + std::cerr << "\t\tdetected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(alarm) << std::endl; + std::cerr << "\t\texpected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(EXPECTED_ALARM) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "\t3-sigma test succeeded " << std::endl; + } + } + } + + // 2-sigma test + { + bool isInitOK = initializeShewhartTest(opt_mean, opt_stdev, opt_verbose, "2-sigma", tester); + if (!isInitOK) { + success = false; + } + else { + const unsigned int NB_SAMPLES = 3; + const float DATA[NB_SAMPLES] = { -2.75f * opt_stdev, -1.5f * opt_stdev, -2.5f * opt_stdev }; + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT[NB_SAMPLES] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD }; + const vpStatisticalTestShewhart::vpWecoRulesAlarm EXPECTED_ALARM[NB_SAMPLES] = { vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::TWO_SIGMA_WECO }; + vpStatisticalTestAbstract::vpMeanDriftType drift; + vpStatisticalTestShewhart::vpWecoRulesAlarm alarm = tester.getAlarm(); + unsigned int i = 0; + bool isTestOk = true; + while ((i < NB_SAMPLES) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(DATA[i]); + alarm = tester.getAlarm(); + isTestOk = ((drift == EXPECTED_DRIFT[i]) && (alarm == EXPECTED_ALARM[i])); + if (isTestOk) { + ++i; + } + } + + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "\t2-sigma test failed: " << std::endl; + std::vector s = tester.getSignals(); + std::cerr << "\t\ts(t) = [ "; + for (size_t i = 0; i < s.size(); ++i) { + std::cerr << s[i] << " "; + } + std::cerr << "]" << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\t\tlim_- = " << limitDown << std::endl; + std::cerr << "\t\tlim_+ = " << limitUp << std::endl; + std::cerr << "\t\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\t\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT[i]) << std::endl; + std::cerr << "\t\tdetected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(alarm) << std::endl; + std::cerr << "\t\texpected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(EXPECTED_ALARM[i]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "\t2-sigma test succeeded " << std::endl; + } + } + } + + // 1-sigma test + { + bool isInitOK = initializeShewhartTest(opt_mean, opt_stdev, opt_verbose, "1-sigma", tester); + if (!isInitOK) { + success = false; + } + else { + const unsigned int NB_SAMPLES = 5; + const float DATA[NB_SAMPLES] = { -2.75f * opt_stdev, -1.5f * opt_stdev, 1.5f * opt_stdev, -1.5f * opt_stdev, -2.5f * opt_stdev }; + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT[NB_SAMPLES] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD }; + const vpStatisticalTestShewhart::vpWecoRulesAlarm EXPECTED_ALARM[NB_SAMPLES] = { vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::ONE_SIGMA_WECO }; + vpStatisticalTestAbstract::vpMeanDriftType drift; + vpStatisticalTestShewhart::vpWecoRulesAlarm alarm = tester.getAlarm(); + unsigned int i = 0; + bool isTestOk = true; + while ((i < NB_SAMPLES) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(DATA[i]); + alarm = tester.getAlarm(); + isTestOk = ((drift == EXPECTED_DRIFT[i]) && (alarm == EXPECTED_ALARM[i])); + if (isTestOk) { + ++i; + } + } + + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "\t1-sigma test failed: " << std::endl; + std::vector s = tester.getSignals(); + std::cerr << "\t\ts(t) = [ "; + for (size_t i = 0; i < s.size(); ++i) { + std::cerr << s[i] << " "; + } + std::cerr << "]" << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\t\tlim_- = " << limitDown << std::endl; + std::cerr << "\t\tlim_+ = " << limitUp << std::endl; + std::cerr << "\t\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\t\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT[i]) << std::endl; + std::cerr << "\t\tdetected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(alarm) << std::endl; + std::cerr << "\t\texpected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(EXPECTED_ALARM[i]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "\t1-sigma test succeeded " << std::endl; + } + } + } + + // Same-side test + { + bool isInitOK = initializeShewhartTest(opt_mean, opt_stdev, opt_verbose, "Same-side", tester); + if (!isInitOK) { + success = false; + } + else { + const unsigned int NB_SAMPLES = 8; + const float DATA[NB_SAMPLES] = { -2.75f * opt_stdev, -0.5f * opt_stdev, -1.5f * opt_stdev, -0.5f * opt_stdev, -2.75f * opt_stdev, -0.5f * opt_stdev, -1.5f * opt_stdev, -0.5f * opt_stdev }; + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT[NB_SAMPLES] = { vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_NONE, vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD }; + const vpStatisticalTestShewhart::vpWecoRulesAlarm EXPECTED_ALARM[NB_SAMPLES] = { vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::NONE_WECO, vpStatisticalTestShewhart::SAME_SIDE_WECO }; + vpStatisticalTestAbstract::vpMeanDriftType drift; + vpStatisticalTestShewhart::vpWecoRulesAlarm alarm = tester.getAlarm(); + unsigned int i = 0; + bool isTestOk = true; + while ((i < NB_SAMPLES) && isTestOk) { + drift = tester.testDownUpwardMeanDrift(DATA[i]); + alarm = tester.getAlarm(); + isTestOk = ((drift == EXPECTED_DRIFT[i]) && (alarm == EXPECTED_ALARM[i])); + if (isTestOk) { + ++i; + } + } + + if (!isTestOk) { + success = false; + if (opt_verbose) { + std::cerr << "\tSame-side test failed: " << std::endl; + std::vector s = tester.getSignals(); + std::cerr << "\t\ts(t) = [ "; + for (size_t i = 0; i < s.size(); ++i) { + std::cerr << s[i] << " "; + } + std::cerr << "]" << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\t\tlim_+ = " << limitUp << std::endl; + std::cerr << "\t\tlim_- = " << limitDown << std::endl; + std::cerr << "\t\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\t\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT[i]) << std::endl; + std::cerr << "\t\tdetected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(alarm) << std::endl; + std::cerr << "\t\texpected alarm = " << vpStatisticalTestShewhart::vpWecoRulesAlarmToString(EXPECTED_ALARM[i]) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "\tSame-side test succeeded " << std::endl; + } + } + } + } + } + + // vpStatisticalTestSigma tests + { + if (opt_verbose) { + std::cout << "------ vpStatisticalTestSigma tests ------" << std::endl; + } + const float h = 3.f; + vpStatisticalTestSigma tester(h, opt_mean, opt_stdev); + + // Upward drift test + { + const float signal = 3.5f * opt_stdev; + vpStatisticalTestAbstract::vpMeanDriftType drift = tester.testDownUpwardMeanDrift(signal); + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT = vpStatisticalTestAbstract::MEAN_DRIFT_UPWARD; + if (drift != EXPECTED_DRIFT) { + success = false; + if (opt_verbose) { + std::cerr << "Upward drift test failed: " << std::endl; + std::cerr << "\ts(t) = " << tester.getSignal() << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\tlim_+ = " << limitUp << std::endl; + std::cerr << "\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "Upward drift test succeeded " << std::endl; + } + } + + // Downward drift test + { + const float signal = -3.5f * opt_stdev; + vpStatisticalTestAbstract::vpMeanDriftType drift = tester.testDownUpwardMeanDrift(signal); + const vpStatisticalTestAbstract::vpMeanDriftType EXPECTED_DRIFT = vpStatisticalTestAbstract::MEAN_DRIFT_DOWNWARD; + if (drift != EXPECTED_DRIFT) { + success = false; + if (opt_verbose) { + std::cerr << "Downward drift test failed: " << std::endl; + std::cerr << "\ts(t) = " << tester.getSignal() << std::endl; + float limitDown = 0.f, limitUp = 0.f; + tester.getLimits(limitDown, limitUp); + std::cerr << "\tlim_- = " << limitDown << std::endl; + std::cerr << "\tdetected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(drift) << std::endl; + std::cerr << "\texpected drift = " << vpStatisticalTestAbstract::vpMeanDriftTypeToString(EXPECTED_DRIFT) << std::endl; + } + } + else if (opt_verbose) { + std::cout << "Downward drift test succeeded " << std::endl; + } + } + } + + if (success) { + std::cout << "Test succeed" << std::endl; + } + else { + std::cout << "Test failed" << std::endl; + return EXIT_FAILURE; + } + return EXIT_SUCCESS; +} diff --git a/tutorial/mean-drift/tutorial-meandrift.cpp b/tutorial/mean-drift/tutorial-meandrift.cpp index 181e94906d..945f312678 100644 --- a/tutorial/mean-drift/tutorial-meandrift.cpp +++ b/tutorial/mean-drift/tutorial-meandrift.cpp @@ -43,6 +43,7 @@ #include #include +#if defined(VISP_HAVE_DISPLAY) namespace TutorialMeanDrift { //! [Enum_For_Test_Choice] @@ -695,3 +696,10 @@ int main(int argc, char *argv[]) return testOnSynthetic(opt_typeTest, parameters, opt_mean, opt_meandrift, opt_stdev); } +#else +int main() +{ + std::cerr << "Recompile ViSP with display capabilities in order to use this tutorial." << std::endl; + return EXIT_FAILURE; +} +#endif From 0050cc133bc0d2757f797db7fb1ff1b1eb92e9e6 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Fri, 8 Mar 2024 17:31:08 +0100 Subject: [PATCH 079/164] [CORPS] Added several methods for automatic Gamma correction + some methods for mean, stdev and sum in vpImage --- .../imgproc/tutorial-imgproc-brightness.dox | 7 + modules/core/include/visp3/core/vpImage.h | 181 ++++++- .../imgproc/include/visp3/imgproc/vpImgproc.h | 145 ++++- modules/imgproc/src/vpImgproc.cpp | 507 +++++++++++++++++- .../tutorial-brightness-adjustment.cpp | 91 +++- 5 files changed, 867 insertions(+), 64 deletions(-) diff --git a/doc/tutorial/imgproc/tutorial-imgproc-brightness.dox b/doc/tutorial/imgproc/tutorial-imgproc-brightness.dox index 1797cf6fb1..eafd02e649 100644 --- a/doc/tutorial/imgproc/tutorial-imgproc-brightness.dox +++ b/doc/tutorial/imgproc/tutorial-imgproc-brightness.dox @@ -49,6 +49,13 @@ The result image is the following: \image html img-tutorial-brighness-gamma-correction-3.5.png "Left: underexposed image - Right: image corrected with gamma=3.5" +ViSP proposes the implementation of several automatic computation of the gamma factor. +Most of these methods are designed for gray-shade images, so ViSP proposes different way +of handling the colors. + +You can test the different methods using the `--gamma-method` option of the tutorial program +and the different way of handling the colors using the `--gamma-color-handling` option. + \section imgproc_brightness_histogram_equalization Histogram equalization Histogram equalization is an image processing method that will adjust the contrast of an image by stretching or shrinking the intensity distribution in order to have a linear cumulative histogram distribution. diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 1184627d29..b3f82d0794 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -186,7 +186,13 @@ template class vpImage // Return the maximum value within the bitmap Type getMaxValue(bool onlyFiniteVal = true) const; // Return the mean value of the bitmap - Type getMeanValue() const; + double getMeanValue() const; + double getMeanValue(const vpImage *p_mask) const; + double getMeanValue(const vpImage *p_mask, unsigned int &nbValidPoints) const; + double getStdev() const; + double getStdev(const vpImage *p_mask) const; + double getStdev(const double &mean) const; + double getStdev(const double &mean, const unsigned int &nbValidPoints, const vpImage *p_mask) const; // Return the minumum value within the bitmap Type getMinValue(bool onlyFiniteVal = true) const; // Look for the minumum and the maximum value within the bitmap @@ -231,6 +237,7 @@ template class vpImage // Get image pixels sum double getSum() const; + double getSum(const vpImage *p_mask, unsigned int &nbValidPoints) const; /*! Get the image width. @@ -939,14 +946,103 @@ template <> inline float vpImage::getMaxValue(bool onlyFiniteVal) const /*! \brief Return the mean value of the bitmap */ -template Type vpImage::getMeanValue() const +template double vpImage::getMeanValue() const { - if ((height == 0) || (width == 0)) + if ((height == 0) || (width == 0)) { return 0.0; + } return getSum() / (height * width); } +/*! + \brief Return the mean value of the bitmap + + \param[in] p_mask A boolean mask that indicates which points must be considered, if set. +*/ +template double vpImage::getMeanValue(const vpImage *p_mask) const +{ + unsigned int nbValidPoints = 0; + return getMeanValue(p_mask, nbValidPoints); +} + +/*! + \brief Return the mean value of the bitmap + + \param[in] p_mask A boolean mask that indicates which points must be considered, if set. + \param[out] nbValidPoints Number of points that are valid according to the boolean mask. +*/ +template double vpImage::getMeanValue(const vpImage *p_mask, unsigned int &nbValidPoints) const +{ + nbValidPoints = 0; + if ((height == 0) || (width == 0)) { + return 0.0; + } + + double sum = getSum(p_mask, nbValidPoints); + return sum / nbValidPoints; +} + +/*! +* \brief Return the standard deviation of the bitmap +*/ +template double vpImage::getStdev() const +{ + double mean = getMeanValue(); + return getStdev(mean); +} + +/*! +* \brief Return the standard deviation of the bitmap +* +* \param[in] p_mask A boolean mask that indicates which points must be considered, if set. +*/ +template double vpImage::getStdev(const vpImage *p_mask) const +{ + unsigned int nbValidPoints = 0; + double mean = getMeanValue(p_mask, nbValidPoints); + return getStdev(mean, nbValidPoints, p_mask); +} + +/*! +* \brief Return the standard deviation of the bitmap +* +* \param[in] mean The mean of the image. +*/ +template double vpImage::getStdev(const double &mean) const +{ + const unsigned int size = width * height; + double sum = 0.; + for (unsigned int i = 0; i < size; ++i) { + sum += (bitmap[i] - mean) * (bitmap[i] - mean); + } + sum /= static_cast(size); + return std::sqrt(sum); +} + +/*! +* \brief Return the standard deviation of the bitmap +* +* \param[in] mean The mean of the image. +* \param[in] nbValidPoints Number of points that are valid according to the boolean mask. +* \param[in] p_mask A boolean mask that indicates which points must be considered, if set. +*/ +template double vpImage::getStdev(const double &mean, const unsigned int &nbValidPoints, const vpImage *p_mask) const +{ + if (p_mask == nullptr) { + return getStdev(mean); + } + const unsigned int size = width * height; + double sum = 0.; + for (unsigned int i = 0; i < size; ++i) { + if (p_mask->bitmap[i]) { + sum += (bitmap[i] - mean) * (bitmap[i] - mean); + } + } + sum /= static_cast(nbValidPoints); + return std::sqrt(sum); +} + /*! * \brief Return the minimum value within the bitmap * \param onlyFiniteVal : This parameter is ignored for non double or non float bitmap. @@ -1869,6 +1965,34 @@ template inline double vpImage::getSum() const return res; } +/** + * Compute the sum of image intensities. + * For vpRGBa image type, compute the sum (R+G+B) of image intensities. + * + * \param[in] p_mask Boolean mask that indicates the valid points by a true flag. + * \param[out] nbValidPoints The number of valid points according to the \b p_mask. + */ +template inline double vpImage::getSum(const vpImage *p_mask, unsigned int &nbValidPoints) const +{ + if ((height == 0) || (width == 0)) + return 0.0; + if (p_mask == nullptr) { + nbValidPoints = height * width; + return getSum(); + } + + double res = 0.0; + nbValidPoints = 0; + unsigned int size = height * width; + for (unsigned int i = 0; i < size; ++i) { + if (p_mask->bitmap[i]) { + res += static_cast(bitmap[i]); + ++nbValidPoints; + } + } + return res; +} + /** * \relates vpImage */ @@ -1884,6 +2008,32 @@ template <> inline double vpImage::getSum() const return res; } +/** + * \relates vpImage + */ +template <> inline double vpImage::getSum(const vpImage *p_mask, unsigned int &nbValidPoints) const +{ + if ((height == 0) || (width == 0)) { + return 0.0; + } + + if (p_mask == nullptr) { + nbValidPoints = height * width; + return getSum(); + } + + double res = 0.0; + nbValidPoints = 0; + unsigned int size = height * width; + for (unsigned int i = 0; i < size; ++i) { + if (p_mask->bitmap[i]) { + res += static_cast(bitmap[i].R) + static_cast(bitmap[i].G) + static_cast(bitmap[i].B); + ++nbValidPoints; + } + } + return res; +} + /** * \relates vpImage */ @@ -1899,6 +2049,31 @@ template <> inline double vpImage::getSum() const return res; } +/** + * \relates vpImage + */ +template <> inline double vpImage::getSum(const vpImage *p_mask, unsigned int &nbValidPoints) const +{ + if ((height == 0) || (width == 0)) { + return 0.0; + } + if (p_mask == nullptr) { + nbValidPoints = height * width; + return getSum(); + } + + double res = 0.0; + nbValidPoints = 0; + unsigned int size = height * width; + for (unsigned int i = 0; i < size; ++i) { + if (p_mask->bitmap[i]) { + res += static_cast(bitmap[i].R) + static_cast(bitmap[i].G) + static_cast(bitmap[i].B); + ++nbValidPoints; + } + } + return res; +} + /*! Operation C = *this - B. diff --git a/modules/imgproc/include/visp3/imgproc/vpImgproc.h b/modules/imgproc/include/visp3/imgproc/vpImgproc.h index bd7f7cfdd9..70db6ca84c 100644 --- a/modules/imgproc/include/visp3/imgproc/vpImgproc.h +++ b/modules/imgproc/include/visp3/imgproc/vpImgproc.h @@ -40,6 +40,7 @@ #ifndef _vpImgproc_h_ #define _vpImgproc_h_ +#include #include #include #include @@ -91,6 +92,93 @@ typedef enum */ } vpAutoThresholdMethod; +/** + * \brief Gamma Correction automatic methods. + */ +typedef enum vpGammaMethod +{ + GAMMA_MANUAL = 0, /*!< User-defined constant positive gamma factor.*/ + GAMMA_LOG_BASED = 1, /*!< Scott, J & Pusateri M (2009)"Towards Real-time Hardware + Gamma Correction for Dynamic Contrast Enhancement" + IEEE Applied Imagery Pattern Recognition Workshop (AIPR 2009)*/ + GAMMA_NONLINEAR_BASED = 2, /*!< Shi, Y et al. (2007), "Reducing Illumination Based On Nonlinear Gamma Correction", + International Conference on Image Processing */ + GAMMA_CDF_BASED = 3, /*!< Huang, SC et al. (2013),"Efficient Contrast Enhancement Using Adaptive + Gamma Correction With Weighting Distribution", + IEEE Trans. on Image Processing, VOL. 22, NO. 3, MARCH 2013. */ + GAMMA_CLASSIFICATION_BASED = 4, /*!< Rahman, S et al. (2016), "An adaptive gamma correction for image + enhancement", EURASIP Journal on Image and Video Processing*/ + GAMMA_SPATIAL_VARIANT_BASED = 5, /*!< Lee, S et al. (2010), "A Space-Variant Luminance Map based + Color Image Enhancement", + IEEE Trans. on Consumer Electronics, Vol. 56, No. 4, November 2010.*/ + GAMMA_METHOD_COUNT = 6 +} vpGammaMethod; + +/** + * \brief Get the list of available vpGammaMethod. + * + * \param[in] pref The prefix of the list. + * \param[in] sep The separator between two elements of the list. + * \param[in] suf The suffix of the list. + * \return std::string The list of available items. + */ +VISP_EXPORT std::string vpGammaMethodList(const std::string &pref = "<", const std::string &sep = " , ", + const std::string &suf = ">"); + +/** + * \brief Cast a \b vp::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. + */ +VISP_EXPORT std::string vpGammaMethodToString(const vpGammaMethod &type); + +/** + * \brief Cast a string into a \b vp::vpGammaMethod. + * + * \param[in] name The name of the backend. + * \return vp::vpGammaMethod The corresponding enumeration value. + */ +VISP_EXPORT vpGammaMethod vpGammaMethodFromString(const std::string &name); + +/** + * \brief How to handle color images when applying Gamma Correction. + */ +typedef enum vpGammaColorHandling +{ + GAMMA_RGB = 0, /*!< Gamma correction is apply to Red, Blue and Green channels individually.*/ + GAMMA_HSV = 1, /*!< The input image is converted into HSV space, Gamma Correction is applied to Value channel and + then the image is converted back into RGBa space.*/ + GAMMA_COLOR_HANDLING_COUNT = 2 +} vpGammaColorHandling; + +/** + * \brief Get the list of available vpGammaColorHandling. + * + * \param[in] pref The prefix of the list. + * \param[in] sep The separator between two elements of the list. + * \param[in] suf The suffix of the list. + * \return std::string The list of available items. + */ +VISP_EXPORT std::string vpGammaColorHandlingList(const std::string &pref = "<", const std::string &sep = " , ", + const std::string &suf = ">"); + +/** + * \brief Cast a \b vp::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. + */ +VISP_EXPORT std::string vpGammaColorHandlingToString(const vpGammaColorHandling &type); + +/** + * \brief Cast a string into a \b vp::vpGammaColorHandling. + * + * \param[in] name The name of the backend. + * \return vp::vpGammaColorHandling The corresponding enumeration value. + */ +VISP_EXPORT vpGammaColorHandling vpGammaColorHandlingFromString(const std::string &name); + /*! * \ingroup group_imgproc_brightness * @@ -262,42 +350,71 @@ VISP_EXPORT void equalizeHistogram(const vpImage &I1, vpImage &I * * Perform a gamma correction on a grayscale image. * - * \param I : The grayscale image to apply gamma correction. - * \param gamma : Gamma value. + * \param[out] I : The grayscale image to apply gamma correction. + * \param[in] gamma : Gamma value. If equals to -1, use automatic Gamma correction based on a non-linear + * technique. If equals to -2, use automatic Gamma correction based on a logarithmic technique. + * If equals to -3, uses automatic Gamma correction based on classification. If equals to -4, uses automatic Gamma + * correction based on probalistics. + * \param[in] method: The method to use: either \b GAMMA_MANUAL if the user wants to use a positive constant \b gamma + * factor, or one of the automatic method if \b gamma is negative. + * \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, double gamma); +VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const vpGammaMethod &method = GAMMA_MANUAL, + const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma * * Perform a gamma correction on a grayscale image. * - * \param I1 : The first grayscale image. - * \param I2 : The second grayscale image after gamma correction. - * \param gamma : Gamma value. + * \param[in] I1 : The first grayscale image. + * \param[out] I2 : The second grayscale image after gamma correction. + * \param[in] gamma : Gamma value. If equals to -1, use automatic Gamma correction based on a non-linear + * technique. If equals to -2, use automatic Gamma correction based on a logarithmic technique. + * If equals to -3, uses automatic Gamma correction based on classification. If equals to -4, uses automatic Gamma + * correction based on probalistics. + * \param[in] method: The method to use: either \b GAMMA_MANUAL if the user wants to use a positive constant \b gamma + * factor, or one of the automatic method if \b gamma is negative. + * \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, double gamma); +VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, + const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma * * Perform a gamma correction on a color image. * - * \param I : The color image to apply gamma correction. - * \param gamma : Gamma value. + * \param[out] I : The color image to apply gamma correction. + * \param[in] gamma : Gamma value. + * \param[in] colorHandling : How to handle the colors of the image. + * \param[in] method : The method to use: either \b GAMMA_MANUAL if the user wants to use a positive constant \b gamma factor, + * or one of the automatic method if \b gamma is negative. + * \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, double gamma); +VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const vpGammaColorHandling &colorHandling = GAMMA_RGB, + const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma * * Perform a gamma correction on a color image. * - * \param I1 : The first color image. - * \param I2 : The second color image after gamma correction. - * \param gamma : Gamma value. + * \param[in] I1 : The first color image. + * \param[out] I2 : The second color image after gamma correction. + * \param[in] gamma : Gamma value. + * \param[in] colorHandling : How to handle the colors of the image. + * \param[in] method: The method to use: either \b GAMMA_MANUAL if the user wants to use a positive constant \b gamma factor, + * or one of the automatic method if \b gamma is negative. + * \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, double gamma); +VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, + const vpGammaColorHandling &colorHandling = GAMMA_RGB, + const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_retinex diff --git a/modules/imgproc/src/vpImgproc.cpp b/modules/imgproc/src/vpImgproc.cpp index f3adc5ddc3..8496c6ebd2 100644 --- a/modules/imgproc/src/vpImgproc.cpp +++ b/modules/imgproc/src/vpImgproc.cpp @@ -60,11 +60,120 @@ #include #include #include +#include #include #include namespace vp { +std::string vpGammaMethodList(const std::string &pref, const std::string &sep, const std::string &suf) +{ + std::string list(pref); + for (unsigned int i = 0; i < (GAMMA_METHOD_COUNT - 1); ++i) { + vpGammaMethod type = static_cast(i); + list += vpGammaMethodToString(type); + list += sep; + } + vpGammaMethod type = static_cast(GAMMA_METHOD_COUNT - 1); + list += vpGammaMethodToString(type); + list += suf; + return list; +} + +std::string vpGammaMethodToString(const vpGammaMethod &type) +{ + std::string name; + switch (type) { + case GAMMA_MANUAL: + name = "gamma_manual"; + break; + case GAMMA_LOG_BASED: + name = "gamma_log"; + break; + case GAMMA_NONLINEAR_BASED: + name = "gamma_nonlinear"; + break; + case GAMMA_CDF_BASED: + name = "gamma_cdf"; + break; + case GAMMA_CLASSIFICATION_BASED: + name = "gamma_classification"; + break; + case GAMMA_SPATIAL_VARIANT_BASED: + name = "gamma_spatial_variant"; + break; + case GAMMA_METHOD_COUNT: + default: + name = "gamma_method_unknown"; + } + return name; +} + +vpGammaMethod vpGammaMethodFromString(const std::string &name) +{ + vpGammaMethod type(GAMMA_METHOD_COUNT); + unsigned int count = static_cast(GAMMA_METHOD_COUNT); + bool notFound = true; + unsigned int i = 0; + while ((i < count) && notFound) { + vpGammaMethod temp = static_cast(i); + if (name == vpGammaMethodToString(temp)) { + type = temp; + notFound = false; + } + ++i; + } + return type; +} + +std::string vpGammaColorHandlingList(const std::string &pref, const std::string &sep, const std::string &suf) +{ + std::string list(pref); + for (unsigned int i = 0; i < (GAMMA_COLOR_HANDLING_COUNT - 1); ++i) { + vpGammaColorHandling type = static_cast(i); + list += vpGammaColorHandlingToString(type); + list += sep; + } + vpGammaColorHandling type = static_cast(GAMMA_COLOR_HANDLING_COUNT - 1); + list += vpGammaColorHandlingToString(type); + list += suf; + return list; +} + +std::string vpGammaColorHandlingToString(const vpGammaColorHandling &type) +{ + std::string name; + switch (type) { + case GAMMA_RGB: + name = "gamma_color_rgb"; + break; + case GAMMA_HSV: + name = "gamma_color_hsv"; + break; + case GAMMA_COLOR_HANDLING_COUNT: + default: + name = "gamma_color_unknown"; + } + return name; +} + +vpGammaColorHandling vpGammaColorHandlingFromString(const std::string &name) +{ + vpGammaColorHandling type(GAMMA_COLOR_HANDLING_COUNT); + unsigned int count = static_cast(GAMMA_COLOR_HANDLING_COUNT); + bool notFound = true; + unsigned int i = 0; + while ((i < count) && notFound) { + vpGammaColorHandling temp = static_cast(i); + if (name == vpGammaColorHandlingToString(temp)) { + type = temp; + notFound = false; + } + ++i; + } + return type; +} + void adjust(vpImage &I, double alpha, double beta) { // Construct the look-up table @@ -193,57 +302,403 @@ void equalizeHistogram(const vpImage &I1, vpImage &I2, bool useH vp::equalizeHistogram(I2, useHSV); } -void gammaCorrection(vpImage &I, double gamma) +namespace { - double inverse_gamma = 1.0; - if (gamma > 0) { - inverse_gamma = 1.0 / gamma; - } - else { - throw vpException(vpException::badValue, "The gamma value must be positive !"); - } +/** + * \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 + * Workshop (AIPR 2009), 2009 + * + * The gamma factor depends on the mean of the original image and its intensity range. + * + * \param[out] I The image on which gamma correction must be applied. + * \param[in] p_mask Boolean that indicates which points must be taken into account (true value) + * or must be ignored (false value). + */ +void gammaCorrectionLogMethod(vpImage &I, const vpImage *p_mask) +{ + float mean = static_cast(I.getMeanValue(p_mask)); + unsigned char inputMin = 0, inputMax = 0; + I.getMinMaxValue(inputMin, inputMax); + unsigned char inputRange = inputMax - inputMin; + + float gamma_computed = (std::log(128.f) - std::log(256.f)) / (std::log(mean) - std::log(inputRange)); + float inverse_gamma = 1.f / gamma_computed; // Construct the look-up table unsigned char lut[256]; + float inputRangeAsFloat = static_cast(inputRange); + for (unsigned int i = inputMin; i <= inputMax; i++) { + lut[i] = vpMath::saturate(std::pow(static_cast(i - inputMin) / inputRangeAsFloat, inverse_gamma) * 255.f); + } + + I.performLut(lut); +} + +/** + * \brief This method is an implementation of the article "REDUCING ILLUMINATION BASED ON NONLINEAR GAMMA CORRECTION" + * by Yihua Shi, Jinfeng Yang, Renbiao Wu, International Conference on Image Processing · September 2007 + * + * The gamma factor is the result of the sum of non-linear functions whose values depend on + * the pixel intensity. + * + * \param[out] I The image on which gamma correction must be applied. + * \param[in] p_mask Boolean that indicates which points must be taken into account (true value) + * or must be ignored (false value). + */ +void gammaCorrectionNonLinearMethod(vpImage &I, const vpImage *p_mask) +{ + (void)p_mask; + const float a = 0.2f; + const float b = 0.3f; + const float c = 0.3f; + const float x_m = 127.5f; + const float alpha = std::atan2(-b, x_m); + const float rho = 0.1f; + unsigned char lut[256]; for (unsigned int i = 0; i < 256; i++) { - lut[i] = vpMath::saturate(pow((double)i / 255.0, inverse_gamma) * 255.0); + float x = static_cast(i); + float phi = M_PIf * x / (2.f * x_m); + float f1 = a * std::cos(phi); + float k = rho * std::sin(4 * M_PIf * x / 255.f); + float f2 = (k + b)*std::cos(alpha) + x * std::sin(alpha); + float r = c * std::abs(x / x_m - 1.f); + float f3 = r * std::cos(3.f * M_PIf * x / 255.f); + float g = f1 + f2 + f3; + float gamma = 1 + g; + float inverse_gamma = 1.f / gamma; + lut[i] = vpMath::saturate(std::pow(static_cast(i) / 255.f, inverse_gamma) * 255.f); } + I.performLut(lut); +} +/** + * \brief This method is an implementation of the article "An adaptive gamma correction for image + * enhancement", Shanto Rahman, Md Mostafijur Rahman, M. Abdullah-Al-Wadud, Golam Dastegir Al-Quaderi and + * Mohammad Shoyaib, EURASIP Journal on Image and Video Processing (2016) + * + * The gamma factor depends of the contrast of the image. The constant depends on the brightness of + * the image. + * + * \param[out] I The image on which gamma correction must be applied. + * \param[in] p_mask Boolean that indicates which points must be taken into account (true value) + * or must be ignored (false value). + */ +void gammaCorrectionClassificationBasedMethod(vpImage &I, const vpImage *p_mask) +{ + unsigned int nbValidPoints = 0; + double mean = I.getMeanValue(p_mask, nbValidPoints); + double stdev = I.getStdev(mean, nbValidPoints, p_mask); + double meanNormalized = mean / 255.; + double stdevNormalized = stdev / 255.; + const float tau = 3.f; + bool isAlreadyHighContrast = (4. * stdevNormalized) > (1./tau); + unsigned char lut[256]; + float gamma = 0.f; + if (isAlreadyHighContrast) { + // Case medium to high contrast image + gamma = std::exp((1.f - (meanNormalized + stdevNormalized))/2.f); + } + else { + // Case low contrast image +#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) + gamma = -std::log2(stdevNormalized); +#else + gamma = -std::log(stdevNormalized) / std::log(2); +#endif + } + if (meanNormalized < 0.5) { + // Case dark image + float meanPowerGamma = std::pow(meanNormalized, gamma); + for (unsigned int i = 0; i <= 255; i++) { + float iNormalized = static_cast(i)/255.f; + float iPowerGamma = std::pow(iNormalized, gamma); + lut[i] = vpMath::saturate(255.f * (iPowerGamma / (iPowerGamma + (1.f - iPowerGamma) * meanPowerGamma))); + } + } + else { + // Case bright image + for (unsigned int i = 0; i <= 255; i++) { + float iNormalized = static_cast(i)/255.f; + lut[i] = vpMath::saturate(std::pow(iNormalized, gamma) * 255.f); + } + } I.performLut(lut); } -void gammaCorrection(const vpImage &I1, vpImage &I2, double gamma) +/** + * \brief This technique comes from the article "Efficient Contrast Enhancement Using Adaptive + * Gamma Correction With Weighting Distribution" by Shih-Chia Huang, Fan-Chieh Cheng, and Yi-Sheng Chiu, + * IEEE TRANSACTIONS ON IMAGE PROCESSING, VOL. 22, NO. 3, MARCH 2013. + * + * It works well on globally dark images that must be brightened, but overcompensate + * images that are already "bright enough". + * + * \param[out] I The image on which gamma correction must be applied. + * \param[in] p_mask Boolean that indicates which points must be taken into account (true value) + * or must be ignored (false value). + */ +void gammaCorrectionProbabilisticBased(vpImage &I, const vpImage *p_mask) { - I2 = I1; - vp::gammaCorrection(I2, gamma); + const unsigned int nbBins = 256; + vpHistogram histo; + histo.setMask(p_mask); + histo.calculate(I, nbBins); + unsigned int totalNbPoints = histo.getTotal(); + unsigned int minHisto = histo[0]; + unsigned int maxHisto = histo[0]; + for (unsigned int i = 1; i < nbBins; ++i) { + minHisto = std::min(minHisto, histo[i]); + maxHisto = std::max(maxHisto, histo[i]); + } + float pdfMin = static_cast(minHisto) / static_cast(totalNbPoints); + float pdfMax = static_cast(maxHisto) / static_cast(totalNbPoints); + float pdf_w[nbBins]; + float sum_pdf_w = 0.f; + for (unsigned int i = 0; i < nbBins; ++i) { + float pdf = static_cast(histo[i])/static_cast(totalNbPoints); + pdf_w[i] = pdfMax * std::sqrt((pdf - pdfMin)/(pdfMax - pdfMin)); // alpha = 0.5 + sum_pdf_w += pdf_w[i]; + } + unsigned char lut[256]; + float cdf_w = 0; + for (unsigned int i = 0; i <= 255; i++) { + cdf_w += pdf_w[i] / sum_pdf_w; + float gamma = 1.f - cdf_w; + float iNormalized = static_cast(i)/255.f; + lut[i] = vpMath::saturate(std::pow(iNormalized, gamma) * 255.f); + } + I.performLut(lut); +} + +/** + * \brief This technique comes from the article "A Space-Variant Luminance Map based Color Image Enhancement" by Sungmok + * Lee, Homin Kwon, Hagyong Han, Gidong Lee, and Bongsoon Kang, + * IEEE Transactions on Consumer Electronics, Vol. 56, No. 4, November 2010. + * + * \param[out] I The image on which gamma correction must be applied. + * \param[in] p_mask Boolean that indicates which points must be taken into account (true value) + * or must be ignored (false value). + */ +void gammaCorrectionSpatialBased(vpImage &I, const vpImage *p_mask) +{ + unsigned int width = I.getWidth(), height = I.getHeight(); + vpImage I_2, I_4, I_8; + I.subsample(2, 2, I_2); + I.subsample(4, 4, I_4); + I.subsample(8, 8, I_8); + vpImage I_blur, I_2_blur, I_4_blur, I_8_blur; + const bool normalize = true; + vpImageFilter::gaussianBlur(I, I_blur, 3, 0.f, normalize, p_mask); + vpImageFilter::gaussianBlur(I_2, I_2_blur, 3, 0.f, normalize, p_mask); + vpImageFilter::gaussianBlur(I_4, I_4_blur, 3, 0.f, normalize, p_mask); + vpImageFilter::gaussianBlur(I_8, I_8_blur, 3, 0.f, normalize, p_mask); + vpImage L, L_2, L_4, L_8; + vpImageTools::resize(I_blur, L, width, height, vpImageTools::INTERPOLATION_CUBIC); + vpImageTools::resize(I_2_blur, L_2, width, height, vpImageTools::INTERPOLATION_CUBIC); + vpImageTools::resize(I_4_blur, L_4, width, height, vpImageTools::INTERPOLATION_CUBIC); + vpImageTools::resize(I_8_blur, L_8, width, height, vpImageTools::INTERPOLATION_CUBIC); + const float alpha = 0.5f; + unsigned int size = height * width; + float stdev = I.getStdev(p_mask); + float p; + if (stdev <= 40) { + p = 2.f; + } + else if (stdev <= 80) { + p = -0.025f * stdev + 3.f; + } + else { + p = 1.f; + } + + for (unsigned int i = 0; i < size; ++i) { + bool hasToCompute = true; + if (p_mask != nullptr) { + hasToCompute = p_mask->bitmap[i]; + } + if (hasToCompute) { + float svlm = (L.bitmap[i] + L_2.bitmap[i] + L_4.bitmap[i] + L_8.bitmap[i]) / 4.f; // Computation of the space-variant luminance map + float gamma = std::pow(alpha, (128.f - svlm)/128.f); + float iNormalized = static_cast(I.bitmap[i])/255.f; + float o = std::pow(iNormalized, gamma) * 255.f; // Computation of the luminance + float r = svlm / o; + float e = std::pow(r, p); + float s = 255.f * std::pow(o / 255.f, e); + I.bitmap[i] = vpMath::saturate((s * static_cast(I.bitmap[i])) / o); + } + } +} + +/** + * \brief This technique comes from the article "A Space-Variant Luminance Map based Color Image Enhancement" by Sungmok + * Lee, Homin Kwon, Hagyong Han, Gidong Lee, and Bongsoon Kang, + * IEEE Transactions on Consumer Electronics, Vol. 56, No. 4, November 2010. + * + * \param[out] I The image on which gamma correction must be applied. + * \param[in] p_mask Boolean that indicates which points must be taken into account (true value) + * or must be ignored (false value). + */ +void gammaCorrectionSpatialBased(vpImage &I, const vpImage *p_mask) +{ + unsigned int width = I.getWidth(), height = I.getHeight(); + unsigned int size = height * width; + vpImage I_gray(height, width); + for (unsigned int i = 0; i < size; ++i) { + vpRGBa rgb = I.bitmap[i]; + I_gray.bitmap[i] = 0.299 * rgb.R + 0.587 * rgb.G + 0.114 *rgb.B; + } + vpImage I_2, I_4, I_8; + I_gray.subsample(2, 2, I_2); + I_gray.subsample(4, 4, I_4); + I_gray.subsample(8, 8, I_8); + vpImage I_blur, I_2_blur, I_4_blur, I_8_blur; + const bool normalize = true; + vpImageFilter::gaussianBlur(I_gray, I_blur, 3, 0.f, normalize, p_mask); + vpImageFilter::gaussianBlur(I_2, I_2_blur, 3, 0.f, normalize, p_mask); + vpImageFilter::gaussianBlur(I_4, I_4_blur, 3, 0.f, normalize, p_mask); + vpImageFilter::gaussianBlur(I_8, I_8_blur, 3, 0.f, normalize, p_mask); + vpImage L, L_2, L_4, L_8; + vpImageTools::resize(I_blur, L, width, height, vpImageTools::INTERPOLATION_CUBIC); + vpImageTools::resize(I_2_blur, L_2, width, height, vpImageTools::INTERPOLATION_CUBIC); + vpImageTools::resize(I_4_blur, L_4, width, height, vpImageTools::INTERPOLATION_CUBIC); + vpImageTools::resize(I_8_blur, L_8, width, height, vpImageTools::INTERPOLATION_CUBIC); + const float alpha = 0.5f; + + float stdev = I.getStdev(p_mask); + float p; + if (stdev <= 40) { + p = 2.f; + } + else if (stdev <= 80) { + p = -0.025f * stdev + 3.f; + } + else { + p = 1.f; + } + for (unsigned int i = 0; i < size; ++i) { + bool hasToCompute = true; + if (p_mask != nullptr) { + hasToCompute = p_mask->bitmap[i]; + } + if (hasToCompute) { + float svlm = (L.bitmap[i] + L_2.bitmap[i] + L_4.bitmap[i] + L_8.bitmap[i]) / 4.f; // Computation of the space-variant luminance map + float gamma = std::pow(alpha, (128.f - svlm)/128.f); + float iNormalized = static_cast(I_gray.bitmap[i])/255.f; + float o = std::pow(iNormalized, gamma) * 255.f; // Computation of the luminance + float r = svlm / o; + float e = std::pow(r, p); + float s = 255.f * std::pow(o / 255.f, e); + I.bitmap[i].R = vpMath::saturate((s * static_cast(I.bitmap[i].R)) / o); + I.bitmap[i].G = vpMath::saturate((s * static_cast(I.bitmap[i].G)) / o); + I.bitmap[i].B = vpMath::saturate((s * static_cast(I.bitmap[i].B)) / o); + } + } +} } -void gammaCorrection(vpImage &I, double gamma) +void gammaCorrection(vpImage &I, const float &gamma, const vpGammaMethod &method, const vpImage *p_mask) { - double inverse_gamma = 1.0; - if (gamma > 0) { + float inverse_gamma = 1.0; + if ((gamma > 0) && (method == GAMMA_MANUAL)) { inverse_gamma = 1.0 / gamma; + // Construct the look-up table + unsigned char lut[256]; + for (unsigned int i = 0; i < 256; i++) { + lut[i] = vpMath::saturate(std::pow(static_cast(i) / 255.0, inverse_gamma) * 255.0); + } + + I.performLut(lut); + } + 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; + throw(vpException(vpException::badValue, errMsg.str())); + } + else if (gamma > 0) { + std::stringstream errMsg; + errMsg << "ERROR: asking for automatic gamma correction but setting a user-defined factor (" << gamma << ")." << std::endl; + throw(vpException(vpException::badValue, errMsg.str())); } else { - throw vpException(vpException::badValue, "The gamma value must be positive !"); + if (method == GAMMA_NONLINEAR_BASED) { + gammaCorrectionNonLinearMethod(I, p_mask); + } + else if (method == GAMMA_LOG_BASED) { + gammaCorrectionLogMethod(I, p_mask); + } + else if (method == GAMMA_CLASSIFICATION_BASED) { + gammaCorrectionClassificationBasedMethod(I, p_mask); + } + else if (method == GAMMA_CDF_BASED) { + gammaCorrectionProbabilisticBased(I, p_mask); + } + else if (method == GAMMA_SPATIAL_VARIANT_BASED) { + gammaCorrectionSpatialBased(I, p_mask); + } + else { + std::stringstream errMsg; + errMsg << "Gamma automatic method \"" << vpGammaMethodToString(method) << "\" is not handled." << std::endl; + throw(vpException(vpException::badValue, errMsg.str())); + } } +} - // Construct the look-up table - vpRGBa lut[256]; - for (unsigned int i = 0; i < 256; i++) { - lut[i].R = vpMath::saturate(pow((double)i / 255.0, inverse_gamma) * 255.0); - lut[i].G = vpMath::saturate(pow((double)i / 255.0, inverse_gamma) * 255.0); - lut[i].B = vpMath::saturate(pow((double)i / 255.0, inverse_gamma) * 255.0); - lut[i].A = vpMath::saturate(pow((double)i / 255.0, inverse_gamma) * 255.0); +void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, + const vpGammaMethod &method, const vpImage *p_mask) +{ + I2 = I1; + vp::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)) { + gammaCorrectionSpatialBased(I, p_mask); } + else { + if (colorHandling == GAMMA_HSV) { + const unsigned int height = I.getHeight(), width = I.getWidth(); + unsigned int size = height * width; + std::vector hue(size); + std::vector saturation(size); + std::vector value(size); - I.performLut(lut); + vpImageConvert::RGBaToHSV((unsigned char *)I.bitmap, &hue.front(), &saturation.front(), &value.front(), size); + vpImage I_hue(&hue.front(), height, width); + vpImage I_saturation(&saturation.front(), height, width); + vpImage I_value(&value.front(), height, width); + + gammaCorrection(I_value, gamma, method, p_mask); + + vpImageConvert::HSVToRGBa(I_hue.bitmap, I_saturation.bitmap, I_value.bitmap, (unsigned char *)I.bitmap, size); + } + else if (colorHandling == GAMMA_RGB) { + vpImage pR, pG, pB, pa; + vpImageConvert::split(I, &pR, &pG, &pB, &pa); + gammaCorrection(pR, gamma, method, p_mask); + gammaCorrection(pG, gamma, method, p_mask); + gammaCorrection(pB, gamma, method, p_mask); + gammaCorrection(pa, gamma, method, p_mask); + vpImageConvert::merge(&pR, &pG, &pB, &pa, I); + } + else { + std::stringstream errMsg; + errMsg << "Gamma color handling mode \"" << vpGammaColorHandlingToString(colorHandling); + errMsg << "\" is not handled." << std::endl; + throw(vpException(vpException::badValue, errMsg.str())); + } + } } -void gammaCorrection(const vpImage &I1, vpImage &I2, double gamma) +void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, + const vpGammaColorHandling &colorHandling, const vpGammaMethod &method, + const vpImage *p_mask) { I2 = I1; - vp::gammaCorrection(I2, gamma); + vp::gammaCorrection(I2, gamma, colorHandling, method, p_mask); } void stretchContrast(vpImage &I) diff --git a/tutorial/imgproc/brightness/tutorial-brightness-adjustment.cpp b/tutorial/imgproc/brightness/tutorial-brightness-adjustment.cpp index d62440741d..90ff929689 100644 --- a/tutorial/imgproc/brightness/tutorial-brightness-adjustment.cpp +++ b/tutorial/imgproc/brightness/tutorial-brightness-adjustment.cpp @@ -25,54 +25,82 @@ int main(int argc, const char **argv) std::string input_filename = "Sample_low_brightness.png"; double alpha = 10.0, beta = 50.0; double gamma = 3.5; + vp::vpGammaMethod method = vp::GAMMA_MANUAL; + vp::vpGammaColorHandling colorHandling = vp::GAMMA_HSV; int scale = 240, scaleDiv = 3, level = 0, kernelSize = -1; double dynamic = 3.0; for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--input" && i + 1 < argc) { input_filename = std::string(argv[i + 1]); - } else if (std::string(argv[i]) == "--alpha" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--alpha" && i + 1 < argc) { alpha = atof(argv[i + 1]); - } else if (std::string(argv[i]) == "--beta" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--beta" && i + 1 < argc) { beta = atof(argv[i + 1]); - } else if (std::string(argv[i]) == "--gamma" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--gamma" && i + 1 < argc) { gamma = atof(argv[i + 1]); - } else if (std::string(argv[i]) == "--scale" && i + 1 < argc) { + } + else if ((std::string(argv[i]) == "--gamma-color-handling") && ((i + 1) < argc)) { + ++i; + colorHandling = vp::vpGammaColorHandlingFromString(argv[i]); + } + else if ((std::string(argv[i]) == "--gamma-method") && ((i + 1) < argc)) { + ++i; + method = vp::vpGammaMethodFromString(argv[i]); + } + else if (std::string(argv[i]) == "--scale" && i + 1 < argc) { scale = atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--scaleDiv" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--scaleDiv" && i + 1 < argc) { scaleDiv = atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--level" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--level" && i + 1 < argc) { level = atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--kernelSize" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--kernelSize" && i + 1 < argc) { kernelSize = atoi(argv[i + 1]); - } else if (std::string(argv[i]) == "--dynamic" && i + 1 < argc) { + } + else if (std::string(argv[i]) == "--dynamic" && i + 1 < argc) { dynamic = 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 << "Usage: " << argv[0] - << " [--input ]" - " [--alpha ] [--beta ]" - " [--gamma ]" - " [--scale [--scaleDiv for " - "vp::retinex()]" - " [--level [--kernelSize " - "]" - " [--dynamic ] [--help]" - << std::endl; + << " [--input ]" + " [--alpha ] [--beta ]" + " [--gamma ]" + " [--gamma-color-handling " << vp::vpGammaColorHandlingList() << "]" + " [--gamma-method " << vp::vpGammaMethodList() << "]" + " [--scale [--scaleDiv for " + "vp::retinex()]" + " [--level [--kernelSize " + "]" + " [--dynamic ] [--help]" + << std::endl; return EXIT_SUCCESS; } } vpImage I_color; vpImageIo::read(I_color, input_filename); + vpImage I_gray; + vpImageConvert::convert(I_color, I_gray); vpImage I_color_res(I_color.getHeight(), 2 * I_color.getWidth()); I_color_res.insert(I_color, vpImagePoint()); + vpImage I_gray_res(I_gray.getHeight(), 2 * I_gray.getWidth()); + I_gray_res.insert(I_gray, vpImagePoint()); #ifdef VISP_HAVE_X11 + vpDisplayX d_gray(I_gray_res); vpDisplayX d(I_color_res); #elif defined(VISP_HAVE_GDI) + vpDisplayGDI d_gray(I_gray_res); vpDisplayGDI d(I_color_res); #elif defined(HAVE_OPENCV_HIGHGUI) + vpDisplayOpenCV d_gray(I_gray_res); vpDisplayOpenCV d(I_color_res); #endif @@ -91,9 +119,30 @@ int main(int argc, const char **argv) vpDisplay::getClick(I_color_res); //! [Gamma correction] + if (method != vp::GAMMA_MANUAL) { + // If the user wants to use an automatic method, the gamma factor must be negative. + gamma = -1.; + } + + if (gamma > 0.) { + // If the user wants to set a constant user-defined gamma factor, the method must be set to manual. + method = vp::GAMMA_MANUAL; + } + vpImage I_gray_gamma_correction; + vp::gammaCorrection(I_gray, I_gray_gamma_correction, gamma, method); vpImage I_color_gamma_correction; - vp::gammaCorrection(I_color, I_color_gamma_correction, gamma); + vp::gammaCorrection(I_color, I_color_gamma_correction, gamma, colorHandling, method); //! [Gamma correction] + I_gray_res.insert(I_gray_gamma_correction, vpImagePoint(0, I_gray.getWidth())); + ss.str(""); + ss << "Sample_low_brightness_gray.png"; + vpImageIo::write(I_gray_res, ss.str()); + + vpDisplay::display(I_gray_res); + vpDisplay::displayText(I_gray_res, 20, 20, "Gamma correction on gray image. Click to continue.", vpColor::red); + vpDisplay::flush(I_gray_res); + vpDisplay::getClick(I_gray_res); + I_color_res.insert(I_color_gamma_correction, vpImagePoint(0, I_color.getWidth())); ss.str(""); ss << "Sample_low_brightness_gamma=" << gamma << ".png"; @@ -126,7 +175,7 @@ int main(int argc, const char **argv) ss.str(""); ss << "Sample_low_brightness_scale=" << scale << "_scaleDiv=" << scaleDiv << "_level=" << level - << "_dynamic=" << dynamic << "_kernelSize=" << kernelSize << ".png"; + << "_dynamic=" << dynamic << "_kernelSize=" << kernelSize << ".png"; vpImageIo::write(I_color_res, ss.str()); vpDisplay::display(I_color_res); From 66f235a179dd122d9c3ab16e9d71c5a957ccb94c Mon Sep 17 00:00:00 2001 From: rlagneau Date: Fri, 8 Mar 2024 17:38:32 +0100 Subject: [PATCH 080/164] [FIX] Fixed wrong delete in vpStasticalTestAbstract --- modules/core/src/math/misc/vpStatisticalTestAbstract.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp index 4986a117b9..399b4b3ddd 100644 --- a/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp @@ -147,7 +147,7 @@ vpStatisticalTestAbstract::vpStatisticalTestAbstract(const vpStatisticalTestAbst vpStatisticalTestAbstract::~vpStatisticalTestAbstract() { if (m_s != nullptr) { - delete m_s; + delete[] m_s; m_s = nullptr; } } @@ -161,7 +161,7 @@ void vpStatisticalTestAbstract::init() m_mean = 0.f; m_nbSamplesForStatistics = 0; if (m_s != nullptr) { - delete m_s; + delete[] m_s; m_s = nullptr; } m_stdev = 0.f; @@ -180,7 +180,7 @@ vpStatisticalTestAbstract &vpStatisticalTestAbstract::operator=(const vpStatisti } else if (m_s != nullptr) { m_nbSamplesForStatistics = 0; - delete m_s; + delete[] m_s; m_s = nullptr; } m_stdev = 0.f; @@ -192,7 +192,7 @@ void vpStatisticalTestAbstract::setNbSamplesForStat(const unsigned int &nbSample { m_nbSamplesForStatistics = nbSamples; if (m_s != nullptr) { - delete m_s; + delete[] m_s; } m_s = new float[nbSamples]; } From 16bcacd5eb5a80bda28d40754ae8df6a5a0171f1 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Mon, 11 Mar 2024 12:03:24 +0100 Subject: [PATCH 081/164] [FIX] Fixed Java binding for ewly introduced gammaCorrection-related methods --- .../imgproc/include/visp3/imgproc/vpImgproc.h | 12 +- modules/java/misc/imgproc/gen_dict.json | 182 ++++++++++++++++++ 2 files changed, 188 insertions(+), 6 deletions(-) diff --git a/modules/imgproc/include/visp3/imgproc/vpImgproc.h b/modules/imgproc/include/visp3/imgproc/vpImgproc.h index 70db6ca84c..e6b5ad16da 100644 --- a/modules/imgproc/include/visp3/imgproc/vpImgproc.h +++ b/modules/imgproc/include/visp3/imgproc/vpImgproc.h @@ -360,7 +360,7 @@ 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 = GAMMA_MANUAL, +VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! @@ -380,7 +380,7 @@ VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, * them to true. */ VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, - const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); + const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma @@ -395,8 +395,8 @@ VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I, const float &gamma, const vpGammaColorHandling &colorHandling = GAMMA_RGB, - const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); +VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const vpGammaColorHandling &colorHandling = vp::GAMMA_RGB, + const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma @@ -413,8 +413,8 @@ VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const v * them to true. */ VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, - const vpGammaColorHandling &colorHandling = GAMMA_RGB, - const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); + const vpGammaColorHandling &colorHandling = vp::GAMMA_RGB, + const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_retinex diff --git a/modules/java/misc/imgproc/gen_dict.json b/modules/java/misc/imgproc/gen_dict.json index c7a00a2fc2..1411ff1de1 100644 --- a/modules/java/misc/imgproc/gen_dict.json +++ b/modules/java/misc/imgproc/gen_dict.json @@ -124,6 +124,188 @@ " return;", "}\n" ] + }, + "gammaCorrection" : { + "j_code" : [ + "//", + "// C++: static void fillHoles(vpImage_char I1, vpImage_char I2, float gamma vp_vpGammaMethod method = vp::GAMMA_MANUAL, vpImage_bool * I_mask = 0)", + "//", + "\n", + "//javadoc: Vp::gammaCorrection(I1, I2, gamma)", + "\n", + "public static void gammaCorrection(VpImageUChar I1, VpImageUChar I2, float gamma)", + "{", + " gammaCorrection(I1.nativeObj, I2.nativeObj, gamma);", + " return;", + "}\n", + "//", + "// C++: static void fillHoles(vpImage_char I, float gamma vp_vpGammaMethod method = vp::GAMMA_MANUAL, vpImage_bool * I_mask = 0)", + "//", + "\n", + "//javadoc: Vp::gammaCorrection(I1, gamma)", + "\n", + "public static void gammaCorrection(VpImageUChar I, float gamma)", + "{", + " gammaCorrection(I.nativeObj, gamma);", + " return;", + "}", + "\n" + ], + "jn_code" : [ + "// C++: static void gammaCorrection(vpImage_char I1, vpImage_char I2, float gamma, vpGammaMethod method = vp::GAMMA_MANUAL, vpImage_bool* p_mask = 0)", + "private static native void gammaCorrection(long I1_nativeobj, long I2_nativeobj, float gamma);\n", + "// C++: static void gammaCorrection(vpImage_char I, float gamma, vpGammaMethod method = vp::GAMMA_MANUAL, vpImage_bool* p_mask = 0)", + "private static native void gammaCorrection(long I_nativeobj, float gamma);\n" + ], + "cpp_code" : [ + "//", + "// manual port", + "// C++: static void gammaCorrection(vpImage_char I1, vpImage_char I2, float gamma, vpGammaMethod method = vp::GAMMA_MANUAL, vpImage_bool* p_mask = 0)", + "//", + "//javadoc: Vp::gammaCorrection(I1, I2, gamma)", + "JNIEXPORT void JNICALL Java_org_visp_imgproc_VpImgproc_gammaCorrection_10 (JNIEnv*, jclass, jlong, jlong, jfloat);", + "JNIEXPORT void JNICALL Java_org_visp_imgproc_VpImgproc_gammaCorrection_10 (JNIEnv* env, jclass , jlong I1_nativeObj, jlong I2_nativeObj, jfloat gamma)", + "{", + " static const char method_name[] = \"imgproc::gammaCorrection_10()\";", + " try {", + " LOGD(\"%s\", method_name);", + " vpImage& I1 = *((vpImage*)I1_nativeObj);", + " vpImage& I2 = *((vpImage*)I2_nativeObj);", + " vp::gammaCorrection( I1, I2, (float)gamma, vp::GAMMA_MANUAL, 0 );", + " return;", + " } catch(const std::exception &e) {", + " throwJavaException(env, &e, method_name);", + " } catch (...) {", + " throwJavaException(env, 0, method_name);", + " }", + " return;", + "}\n", + "//", + "// manual port", + "// C++: static void gammaCorrection(vpImage_char I, float gamma, vpGammaMethod method = vp::GAMMA_MANUAL, vpImage_bool* p_mask = 0)", + "//", + "//javadoc: Vp::gammaCorrection(I, gamma)\n", + "JNIEXPORT void JNICALL Java_org_visp_imgproc_VpImgproc_gammaCorrection_13 (JNIEnv*, jclass, jlong, jfloat);\n", + "JNIEXPORT void JNICALL Java_org_visp_imgproc_VpImgproc_gammaCorrection_13 (JNIEnv* env, jclass , jlong I_nativeObj, jfloat gamma)", + "{", + " static const char method_name[] = \"imgproc::gammaCorrection_13()\";", + " try {", + " LOGD(\"%s\", method_name);", + " vpImage& I = *((vpImage*)I_nativeObj);", + " vp::gammaCorrection( I, (float)gamma, vp::GAMMA_MANUAL, 0 );", + " return;", + " } catch(const std::exception &e) {", + " throwJavaException(env, &e, method_name);", + " } catch (...) {", + " throwJavaException(env, 0, method_name);", + " }", + " return;", + "}\n\n" + ] + }, + "vpGammaColorHandlingList" : { + "j_code" : [ + "\n//", + "// manual port", + "// C++: std::string vpGammaColorHandlingList(const std::string &pref = \"<\", const std::string &sep = \" , \", const std::string &suf = \">\")\n", + "//javadoc: Vp::vpGammaColorHandlingList(pref, sep, suf)\n", + "public static String vpGammaColorHandlingList(String pref, String sep, String suf)", + "{", + " return vpGammaColorHandlingList(pref, sep, suf);", + "}" + ], + "jn_code" : [ + "\n// C++: std::string vpGammaColorHandlingList(const std::string &pref = \"<\", const std::string &sep = \" , \", const std::string &suf = \">\")\n" + ], + "cpp_code" : [ + "//", + "// manual port", + "// C++: std::string vpGammaColorHandlingList(const std::string &pref = \"<\", const std::string &sep = \" , \", const std::string &suf = \">\")\n", + "//", + "JNIEXPORT jstring JNICALL Java_org_visp_imgproc_VpImgproc_vpGammaColorHandlingList_10 (JNIEnv*, jclass, jstring);", + "JNIEXPORT jstring JNICALL Java_org_visp_imgproc_VpImgproc_vpGammaColorHandlingList_10 (JNIEnv* env, jclass , jstring pref)", + "{", + " static const char method_name[] = \"imgproc::vpGammaColorHandlingList_10()\";", + " try {", + " LOGD(\"%s\", method_name);", + " const char* utf_pref = env->GetStringUTFChars(pref, 0); string n_pref( utf_pref ? utf_pref : \"\" ); env->ReleaseStringUTFChars(pref, utf_pref);", + " string _retval_ = vp::vpGammaColorHandlingList( n_pref );", + " return JNIEnv*->NewStringUTF(_retval_.c_str());", + " } catch(const std::exception &e) {", + " throwJavaException(env, &e, method_name);", + " } catch (...) {", + " throwJavaException(env, 0, method_name);", + " }", + " return 0;", + "}\n", + "JNIEXPORT jstring JNICALL Java_org_visp_imgproc_VpImgproc_vpGammaColorHandlingList_11 (JNIEnv*, jclass);", + "JNIEXPORT jstring JNICALL Java_org_visp_imgproc_VpImgproc_vpGammaColorHandlingList_11 (JNIEnv* env, jclass )", + "{", + " static const char method_name[] = \"imgproc::vpGammaColorHandlingList_11()\";", + " try {", + " LOGD(\"%s\", method_name);", + " string _retval_ = vp::vpGammaColorHandlingList( );", + " return JNIEnv*->NewStringUTF(_retval_.c_str());", + " } catch(const std::exception &e) {", + " throwJavaException(env, &e, method_name);", + " } catch (...) {", + " throwJavaException(env, 0, method_name);", + " }", + " return 0;", + "}\n" + ] + }, + "vpGammaMethodList" : { + "j_code" : [ + "\n//", + "// manual port", + "// C++: std::string vpGammaMethodList(const std::string &pref = \"<\", const std::string &sep = \" , \", const std::string &suf = \">\")\n", + "//javadoc: Vp::vpGammaMethodList(pref, sep, suf)\n", + "public static String vpGammaMethodList(String pref, String sep, String suf)", + "{", + " return vpGammaMethodList(pref, sep, suf);", + "}" + ], + "jn_code" : [ + "\n// C++: std::string vpGammaMethodList(const std::string &pref = \"<\", const std::string &sep = \" , \", const std::string &suf = \">\")\n" + ], + "cpp_code" : [ + "//", + "// manual port", + "// C++: std::string vpGammaMethodList(const std::string &pref = \"<\", const std::string &sep = \" , \", const std::string &suf = \">\")\n", + "//", + "JNIEXPORT jstring JNICALL Java_org_visp_imgproc_VpImgproc_vpGammaMethodList_10 (JNIEnv*, jclass, jstring);", + "JNIEXPORT jstring JNICALL Java_org_visp_imgproc_VpImgproc_vpGammaMethodList_10 (JNIEnv* env, jclass , jstring pref)", + "{", + " static const char method_name[] = \"imgproc::vpGammaMethodList_10()\";", + " try {", + " LOGD(\"%s\", method_name);", + " const char* utf_pref = env->GetStringUTFChars(pref, 0); string n_pref( utf_pref ? utf_pref : \"\" ); env->ReleaseStringUTFChars(pref, utf_pref);", + " string _retval_ = vp::vpGammaMethodList( n_pref );", + " return JNIEnv*->NewStringUTF(_retval_.c_str());", + " } catch(const std::exception &e) {", + " throwJavaException(env, &e, method_name);", + " } catch (...) {", + " throwJavaException(env, 0, method_name);", + " }", + " return 0;", + "}\n", + "JNIEXPORT jstring JNICALL Java_org_visp_imgproc_VpImgproc_vpGammaMethodList_11 (JNIEnv*, jclass);", + "JNIEXPORT jstring JNICALL Java_org_visp_imgproc_VpImgproc_vpGammaMethodList_11 (JNIEnv* env, jclass )", + "{", + " static const char method_name[] = \"imgproc::vpGammaMethodList_11()\";", + " try {", + " LOGD(\"%s\", method_name);", + " string _retval_ = vp::vpGammaMethodList( );", + " return JNIEnv*->NewStringUTF(_retval_.c_str());", + " } catch(const std::exception &e) {", + " throwJavaException(env, &e, method_name);", + " } catch (...) {", + " throwJavaException(env, 0, method_name);", + " }", + " return 0;", + "}\n" + ] } } }, From d66ad95effd704be26fd148f174e6234326fad33 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Mon, 11 Mar 2024 12:32:41 +0100 Subject: [PATCH 082/164] Fix java bindings for gamma correction functionalities --- modules/java/misc/imgproc/gen_dict.json | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/modules/java/misc/imgproc/gen_dict.json b/modules/java/misc/imgproc/gen_dict.json index 1411ff1de1..e2f14d5906 100644 --- a/modules/java/misc/imgproc/gen_dict.json +++ b/modules/java/misc/imgproc/gen_dict.json @@ -230,7 +230,7 @@ " LOGD(\"%s\", method_name);", " const char* utf_pref = env->GetStringUTFChars(pref, 0); string n_pref( utf_pref ? utf_pref : \"\" ); env->ReleaseStringUTFChars(pref, utf_pref);", " string _retval_ = vp::vpGammaColorHandlingList( n_pref );", - " return JNIEnv*->NewStringUTF(_retval_.c_str());", + " return env->NewStringUTF(_retval_.c_str());", " } catch(const std::exception &e) {", " throwJavaException(env, &e, method_name);", " } catch (...) {", @@ -245,7 +245,7 @@ " try {", " LOGD(\"%s\", method_name);", " string _retval_ = vp::vpGammaColorHandlingList( );", - " return JNIEnv*->NewStringUTF(_retval_.c_str());", + " return env->NewStringUTF(_retval_.c_str());", " } catch(const std::exception &e) {", " throwJavaException(env, &e, method_name);", " } catch (...) {", @@ -282,7 +282,7 @@ " LOGD(\"%s\", method_name);", " const char* utf_pref = env->GetStringUTFChars(pref, 0); string n_pref( utf_pref ? utf_pref : \"\" ); env->ReleaseStringUTFChars(pref, utf_pref);", " string _retval_ = vp::vpGammaMethodList( n_pref );", - " return JNIEnv*->NewStringUTF(_retval_.c_str());", + " return env->NewStringUTF(_retval_.c_str());", " } catch(const std::exception &e) {", " throwJavaException(env, &e, method_name);", " } catch (...) {", @@ -297,7 +297,7 @@ " try {", " LOGD(\"%s\", method_name);", " string _retval_ = vp::vpGammaMethodList( );", - " return JNIEnv*->NewStringUTF(_retval_.c_str());", + " return env->NewStringUTF(_retval_.c_str());", " } catch(const std::exception &e) {", " throwJavaException(env, &e, method_name);", " } catch (...) {", From 39d0110da14e2e25cb72d0ee41c09311ef52f701 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 11 Mar 2024 13:33:44 +0100 Subject: [PATCH 083/164] rename file with invalid naming convention --- .../visp/{windows-dll-manager.py => windows_dll_manager.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename modules/python/bindings/visp/{windows-dll-manager.py => windows_dll_manager.py} (100%) diff --git a/modules/python/bindings/visp/windows-dll-manager.py b/modules/python/bindings/visp/windows_dll_manager.py similarity index 100% rename from modules/python/bindings/visp/windows-dll-manager.py rename to modules/python/bindings/visp/windows_dll_manager.py From 3e93687f2abe2525f6c49254f6da306409d6d445 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Mon, 11 Mar 2024 13:52:45 +0100 Subject: [PATCH 084/164] [FIX] Trying to fix error C2039: 'max': is not a member of 'std' --- modules/core/include/visp3/core/vpStatisticalTestAbstract.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h index ac5d7867ae..dbf9604a2d 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h +++ b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h @@ -37,7 +37,7 @@ #ifndef _vpStatisticalTestAbstract_h_ #define _vpStatisticalTestAbstract_h_ - +#include #include #include #include From f12208432e050aefd63c556833ea759d5fc6b1eb Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 11 Mar 2024 14:02:06 +0100 Subject: [PATCH 085/164] Fix bindings build on python 3.8 --- modules/python/generator/visp_python_bindgen/header.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/python/generator/visp_python_bindgen/header.py b/modules/python/generator/visp_python_bindgen/header.py index d87dcc2c7d..159bce1b07 100644 --- a/modules/python/generator/visp_python_bindgen/header.py +++ b/modules/python/generator/visp_python_bindgen/header.py @@ -243,7 +243,7 @@ def generate_class(self, bindings_container: BindingsContainer, cls: ClassScope, If it is templated, the mapping (template argument types => Python class name) must be provided in the JSON config file ''' - def generate_class_with_potiental_specialization(name_python: str, owner_specs: OrderedDict[str, str], cls_config: Dict) -> str: + def generate_class_with_potiental_specialization(name_python: str, owner_specs: 'OrderedDict[str, str]', cls_config: Dict) -> str: ''' Generate the bindings of a single class, handling a potential template specialization. The handled information is: From 0dc94b4526bf8d4c89294d774642baa4239142e1 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Mon, 11 Mar 2024 14:17:57 +0100 Subject: [PATCH 086/164] [FIX] Changed vpCHT::rmin and vpCHT::rmax from uint to float --- .../visp3/imgproc/vpCircleHoughTransform.h | 24 +++++++++---------- .../imgproc/src/vpCircleHoughTransform.cpp | 13 ++++------ 2 files changed, 17 insertions(+), 20 deletions(-) diff --git a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h index 5580948782..8eefb325cf 100644 --- a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h +++ b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h @@ -96,8 +96,8 @@ class VISP_EXPORT vpCircleHoughTransform // // Center candidates computation attributes std::pair m_centerXlimits; /*!< Minimum and maximum position on the horizontal axis of the center of the circle we want to detect.*/ std::pair m_centerYlimits; /*!< Minimum and maximum position on the vertical axis of the center of the circle we want to detect.*/ - unsigned int m_minRadius; /*!< Minimum radius of the circles we want to detect.*/ - unsigned int m_maxRadius; /*!< Maximum radius of the circles we want to detect.*/ + float m_minRadius; /*!< Minimum radius of the circles we want to detect.*/ + float m_maxRadius; /*!< Maximum radius of the circles we want to detect.*/ int m_dilatationKernelSize; /*!< Kernel size of the dilatation that is performed to detect the maximum number of votes for the center candidates.*/ int m_averagingWindowSize; /*!< Size of the averaging window around the maximum number of votes to compute the center candidate such as it is the barycenter of the window. Must be odd.*/ @@ -135,8 +135,8 @@ class VISP_EXPORT vpCircleHoughTransform , m_upperCannyThreshRatio(0.8f) , m_centerXlimits(std::pair(std::numeric_limits::min(), std::numeric_limits::max())) , m_centerYlimits(std::pair(std::numeric_limits::min(), std::numeric_limits::max())) - , m_minRadius(0) - , m_maxRadius(1000) + , m_minRadius(0.f) + , m_maxRadius(1000.f) , m_dilatationKernelSize(3) , m_averagingWindowSize(5) , m_centerMinThresh(50.f) @@ -198,8 +198,8 @@ class VISP_EXPORT vpCircleHoughTransform , const int &edgeMapFilterNbIter , const std::pair ¢erXlimits , const std::pair ¢erYlimits - , const unsigned int &minRadius - , const unsigned int &maxRadius + , const float &minRadius + , const float &maxRadius , const int &dilatationKernelSize , const int &averagingWindowSize , const float ¢erThresh @@ -227,8 +227,8 @@ class VISP_EXPORT vpCircleHoughTransform , m_upperCannyThreshRatio(upperCannyThreshRatio) , m_centerXlimits(centerXlimits) , m_centerYlimits(centerYlimits) - , m_minRadius(std::min(minRadius, maxRadius)) - , m_maxRadius(std::max(minRadius, maxRadius)) + , m_minRadius(std::min(minRadius, maxRadius)) + , m_maxRadius(std::max(minRadius, maxRadius)) , m_dilatationKernelSize(dilatationKernelSize) , m_averagingWindowSize(averagingWindowSize) , m_centerMinThresh(centerThresh) @@ -573,9 +573,9 @@ class VISP_EXPORT vpCircleHoughTransform params.m_centerXlimits = j.value("centerXlimits", params.m_centerXlimits); params.m_centerYlimits = j.value("centerYlimits", params.m_centerYlimits); - std::pair radiusLimits = j.value("radiusLimits", std::pair(params.m_minRadius, params.m_maxRadius)); - params.m_minRadius = std::min(radiusLimits.first, radiusLimits.second); - params.m_maxRadius = std::max(radiusLimits.first, radiusLimits.second); + std::pair radiusLimits = j.value("radiusLimits", std::pair(params.m_minRadius, params.m_maxRadius)); + params.m_minRadius = std::min(radiusLimits.first, radiusLimits.second); + params.m_maxRadius = std::max(radiusLimits.first, radiusLimits.second); params.m_dilatationKernelSize = j.value("dilatationKernelSize", params.m_dilatationKernelSize); params.m_averagingWindowSize = j.value("averagingWindowSize", params.m_averagingWindowSize); @@ -621,7 +621,7 @@ class VISP_EXPORT vpCircleHoughTransform */ inline friend void to_json(json &j, const vpCircleHoughTransformParameters ¶ms) { - std::pair radiusLimits = { params.m_minRadius, params.m_maxRadius }; + std::pair radiusLimits = { params.m_minRadius, params.m_maxRadius }; j = json { {"filteringAndGradientType", vpImageFilter::vpCannyFilteringAndGradientTypeToString(params.m_filteringAndGradientType)}, diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index a30d1829f9..3d1c4660d3 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -600,30 +600,27 @@ vpCircleHoughTransform::computeCenterCandidates() // Saving the edge point for further use m_edgePointsList.push_back(std::pair(r, c)); - float float_minRad = static_cast(m_algoParams.m_minRadius); - float float_maxRad = static_cast(m_algoParams.m_maxRadius); - for (int k1 = 0; k1 < nbDirections; ++k1) { bool hasToStopLoop = false; int x_low_prev = std::numeric_limits::max(), y_low_prev, y_high_prev; int x_high_prev = (y_low_prev = (y_high_prev = x_low_prev)); - float rstart = float_minRad, rstop = float_maxRad; + float rstart = m_algoParams.m_minRadius, rstop = m_algoParams.m_maxRadius; float min_minus_c = minimumXpositionFloat - static_cast(c); float min_minus_r = minimumYpositionFloat - static_cast(r); float max_minus_c = maximumXpositionFloat - static_cast(c); float max_minus_r = maximumYpositionFloat - static_cast(r); if (sx > 0) { float rmin = min_minus_c / sx; - rstart = std::max(rmin, float_minRad); + rstart = std::max(rmin, m_algoParams.m_minRadius); float rmax = max_minus_c / sx; - rstop = std::min(rmax, float_maxRad); + rstop = std::min(rmax, m_algoParams.m_maxRadius); } else if (sx < 0) { float rmin = max_minus_c / sx; - rstart = std::max(rmin, float_minRad); + rstart = std::max(rmin, m_algoParams.m_minRadius); float rmax = min_minus_c / sx; - rstop = std::min(rmax, float_maxRad); + rstop = std::min(rmax, m_algoParams.m_maxRadius); } if (sy > 0) { From e6fe88b4dab1da0ce1d3327b7d6ab6ff28930be9 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 11 Mar 2024 14:50:02 +0100 Subject: [PATCH 087/164] Logging for CI bug with headers coming from multiple folders --- .../python/generator/visp_python_bindgen/generator_config.py | 4 +++- modules/python/generator/visp_python_bindgen/submodule.py | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/modules/python/generator/visp_python_bindgen/generator_config.py b/modules/python/generator/visp_python_bindgen/generator_config.py index 39e92f454c..db8eafefb8 100644 --- a/modules/python/generator/visp_python_bindgen/generator_config.py +++ b/modules/python/generator/visp_python_bindgen/generator_config.py @@ -156,9 +156,10 @@ def is_forbidden_function_name(name: str) -> bool: @staticmethod def update_from_main_config_file(path: Path) -> None: - assert path.exists() + assert path.exists(), f'Main config file {path} was not found' with open(path, 'r') as main_config_file: main_config = json.load(main_config_file) + print(json.dumps(main_config, indent=2)) logging.info('Updating the generator config from dict: ', main_config) GeneratorConfig.pcpp_config.include_directories = main_config['include_dirs'] @@ -176,6 +177,7 @@ def update_from_main_config_file(path: Path) -> None: for module_name in modules_dict: headers = map(lambda s: Path(s), modules_dict[module_name].get('headers')) deps = modules_dict[module_name].get('dependencies') + # Include only headers that are in the VISP source directory headers = list(filter(lambda h: source_dir in h.parents, headers)) headers_log_str = '\n\t'.join([str(header) for header in headers]) diff --git a/modules/python/generator/visp_python_bindgen/submodule.py b/modules/python/generator/visp_python_bindgen/submodule.py index 82f0a11e11..7b9cefc0ce 100644 --- a/modules/python/generator/visp_python_bindgen/submodule.py +++ b/modules/python/generator/visp_python_bindgen/submodule.py @@ -284,8 +284,8 @@ def get_submodules(config_path: Path, generate_path: Path) -> List[Submodule]: headers = module_data.headers if len(headers) == 0: print(f'Module {module_data.name} has no input headers, skipping!') - continue + # The headers are already filtered: they should all come from the ViSP source folder (no vpConfig, etc.) include_dir = headers[0].parent hh = "\n".join(map(lambda s: str(s), headers)) assert all(map(lambda header_path: header_path.parent == include_dir, headers)), f'Found headers in different directory, this case is not yet handled. Headers = {hh}' From 3d954fa6185f45630c2c1ab65b403861b99c6860 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 11 Mar 2024 16:16:20 +0100 Subject: [PATCH 088/164] Fix attempt for CI failing with assert, Add cmake target for Python bindings tests --- modules/python/CMakeLists.txt | 3 ++ .../visp_python_bindgen/generator_config.py | 6 ++- modules/python/test/CMakeLists.txt | 48 +++++++++++++++++++ modules/python/test/requirements.txt | 3 ++ 4 files changed, 59 insertions(+), 1 deletion(-) create mode 100644 modules/python/test/CMakeLists.txt create mode 100644 modules/python/test/requirements.txt diff --git a/modules/python/CMakeLists.txt b/modules/python/CMakeLists.txt index dd2035c473..ef6ea0766c 100644 --- a/modules/python/CMakeLists.txt +++ b/modules/python/CMakeLists.txt @@ -119,6 +119,9 @@ if(BUILD_PYTHON_BINDINGS_DOC) add_subdirectory(doc) endif() +# Step 6: Test bindings +add_subdirectory(test) + # Export Variables to parent cmake set(VISP_PYTHON_BOUND_MODULES "") diff --git a/modules/python/generator/visp_python_bindgen/generator_config.py b/modules/python/generator/visp_python_bindgen/generator_config.py index db8eafefb8..4735813a71 100644 --- a/modules/python/generator/visp_python_bindgen/generator_config.py +++ b/modules/python/generator/visp_python_bindgen/generator_config.py @@ -179,7 +179,11 @@ def update_from_main_config_file(path: Path) -> None: deps = modules_dict[module_name].get('dependencies') # Include only headers that are in the VISP source directory - headers = list(filter(lambda h: source_dir in h.parents, headers)) + # Fix: Check specifically in the modules directory, + # since the build directory (containing vpConfig.h, that we want to ignore) + # Can be in the src folder + headers = list(filter(lambda h: (source_dir / 'modules') in h.parents, headers)) + headers_log_str = '\n\t'.join([str(header) for header in headers]) logging.info(f'Module {module_name} headers: \n\t{headers_log_str}') GeneratorConfig.module_data.append(ModuleInputData(module_name, headers, deps)) diff --git a/modules/python/test/CMakeLists.txt b/modules/python/test/CMakeLists.txt new file mode 100644 index 0000000000..80e91829e4 --- /dev/null +++ b/modules/python/test/CMakeLists.txt @@ -0,0 +1,48 @@ +############################################################################# +# +# ViSP, open source Visual Servoing Platform software. +# Copyright (C) 2005 - 2023 by Inria. All rights reserved. +# +# This software is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2 of the License, or +# (at your option) any later version. +# See the file LICENSE.txt at the root directory of this source +# distribution for additional information about the GNU GPL. +# +# For using ViSP with software that can not be combined with the GNU +# GPL, please contact Inria about acquiring a ViSP Professional +# Edition License. +# +# See https://visp.inria.fr for more information. +# +# This software was developed at: +# Inria Rennes - Bretagne Atlantique +# Campus Universitaire de Beaulieu +# 35042 Rennes Cedex +# France +# +# If you have questions regarding the use of this file, please contact +# Inria at visp@inria.fr +# +# This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE +# WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. +# +# Description: +# ViSP Python bindings stubs +# +############################################################################# + + +add_custom_target(visp_python_bindings_test_dependencies + COMMAND ${PYTHON3_EXECUTABLE} -m pip install ${_pip_args} -r "${CMAKE_CURRENT_SOURCE_DIR}/requirements.txt" + COMMENT "Installing dependencies to test Python bindings..." + DEPENDS visp_python_bindings +) + +add_custom_target(visp_python_bindings_test + COMMAND ${PYTHON3_EXECUTABLE} -m pytest "${CMAKE_CURRENT_SOURCE_DIR}" + COMMAND ${PYTHON3_EXECUTABLE} -m pytest "--doctest-glob=*.rst" "${CMAKE_CURRENT_SOURCE_DIR}/../doc" + COMMENT "Testing Python bindings..." + DEPENDS visp_python_bindings_test_dependencies +) diff --git a/modules/python/test/requirements.txt b/modules/python/test/requirements.txt new file mode 100644 index 0000000000..fba349822b --- /dev/null +++ b/modules/python/test/requirements.txt @@ -0,0 +1,3 @@ +numpy +pytest +pytest-sphinx From 9989cb9efc7952edb57f9dab4c7133845eff3bae Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Mon, 11 Mar 2024 17:15:26 +0100 Subject: [PATCH 089/164] Reduce SPC tutorial image resolution and change format to jpeg --- .../tutorial/misc/img-tutorial-spc-run.jpg | Bin 0 -> 97635 bytes .../tutorial/misc/img-tutorial-spc-run.png | Bin 147847 -> 0 bytes doc/tutorial/misc/tutorial-spc.dox | 4 ++-- 3 files changed, 2 insertions(+), 2 deletions(-) create mode 100644 doc/image/tutorial/misc/img-tutorial-spc-run.jpg delete mode 100644 doc/image/tutorial/misc/img-tutorial-spc-run.png diff --git a/doc/image/tutorial/misc/img-tutorial-spc-run.jpg b/doc/image/tutorial/misc/img-tutorial-spc-run.jpg new file mode 100644 index 0000000000000000000000000000000000000000..ccbcce61ea312b0d8ab6c25a524cff5c9f2fc92f GIT binary patch literal 97635 zcmeFY1yEc~(=d9l-~|F8P~x>dLCY@I#5J<~niJ$-u4^vqsQT`vNJAbBNu00jjFP(*%! z>#snQoR8g808mi@*Z=^)0x(gC0W>6pg8Tp|_W_JwFaTJfQ2YnBM`8J+4Jxt?FM#|8 z@R64r3g0i71PKSfvIEfnpiM;HZwj)<8?L|a3Q8*Kw0vB=JY2j&0Kmt?$1lS3P=rT_ zmPc5GPf&!14**cJQUBzDCYg=)Cye5G!|ZwqwMR)-)>K_nOkEUKo}4-w{&-rR#$&=!{N{S4g6O*nfN6mFv@wuOU#Gr z@y^@heLgB-Eew~$kAJoMFCly@Yj;belC;QLDN7eO4BuwIl6bcD{ zx`Aze!&5h~#cz1~R~v0jS)@Kl5TLcRHMc^-v`Co4($)=vgm2_$w1QaO;9Y*hPB-w4 zr5P>$Mr-po7~<%OldygMN= z?tmt;Ugp1{=l?}73pfKVfG^;Nq_F{Pk<_$+G!o;2>3b@|Vs3!Z~LHfY31jpvC@$vq%Ae`d0vOZ~8ABV-^714g~=CCl_-!^Iz=Hkl(0J zkzRdRfOJd)0J!r70B{W5pFTu76|$h<$p8Sx{Pp#BCIG-p0D#Nb>+6f0>+8#0WPh^& z@WJV~osn&Ccma8n0HFO00Go+<=&mh!4aCV(np0>jQCgau@Ltr~lPV1PR}u zx#?+tHSur|r`Jb5RxOs(zg}Hh7xcT@vku5mgeVshaeK?)m8GbYQlh0$Mi@Vvmc-T2R(cbViw{Z6K z5T~cV>F7V@x11h!Pyg!aAG+Pt{8H|}BC|$@r2h!`53-w@|CS7CqyL)fPecAk52To4 zHxh^#Xj;2FJ9^&eBJqfin^%nc|Azict=}YnQRq0?c}Vd6LGmy3zp3>9s{eaOe@FkD zM9t048aV>LWcyRFzvKSa{>CgKvd)gqZdxwpmevx;=Kn_htu@k4A}Y>Sc29jDn|oMG z+=O0Eo`;+~LfU_ZUNP=}wfPsdtedsDhqIfuv$Lbb-{bgiy1&={K`6$3<0*ghoZoKw z3ybti2^=KlpFS>ub3Fsd0%)i=<>ng=SOYYC%8>WNJNN(M|_8v@D36tykUZJLy3ltg(M`z#l}Tq|2NC^2Y?6*#S={u4TT6m zB|0@JK!+9$I(s*vi@)$(#z=>rK~x>-~oNEeyIlp>3GqlHO%93Fz8*MSG5oC-@3#1^#GHE;UT|_rdu_sphZY-O$TE-+m>$!Iq&sKs?*|?V!;5iNl=5; zaZvszK>WV;(Ica>9kmQ`$J5bPEJ&rIS`K3t7`6X|4<3Zmcc~dv9vs-EJM`7Sv{>!< z%k8PY>7VTE$4XaCC>P|0l3~_?MUsn-O(Z`u_E#qxjOu`yl< zD$rC*7T$u6aMVx=x1mQ|a2k`TyT1HNG;5%T0k~C4llSzHu9z(aAGbvv4Lx@7m&z*U zJY;0O|J;R1$yvL`L8TlB8SMbSGv#wToRt@Axp&$_Esou75=MH4HMLbLxcsI|ur!+# z&(AEO6Xo1{eLPph-+Qz_tEhb2kdzkM?4mC-M)@NuM6eUp1-jx)P4=3rG0}=<(9aJ6 zRs*TYkCYi_q!TwQF;*Fj8YT-}?eKoM99@jU>6Te%7nhW-)SWmf_uecXM|?E~kr+SO zp|BVC*6Kd*wyM>yD>*1V7$)VapZ8-UBTLq6wFC-Y#9}gpNUL9rueXto97S9QCZS)8uMr6le2M*4rew|_rr_`Xj4HbUp9`idJ-aXhiNqmB0eQ~rP0LMT%KxPi&- zqL@;iwn|5PGY8jzfRyLI+~e`-7yk_vCP*{$`f3rip#o>oM~H^>*&X(9RMUU>3Pw`a zdfL(OXy-!VIcJ$UW}_>oB!pGtlulD|Xo!5#Uym$hxQRMT0cKECm*j4|QJ^wSqm}39 z3~i!5Jqc(j-FuqEayp_^JcAj#=$bnU~(5 zAC{-Fvx{P}v$GU-n#H#>HJqJHOf;#KmhG&p3X8z!4E+sH9}g&_$YD1;vJIU_YS#oJh+5DQ0E%J?f5N zGk+YE=i4l|?jWy!q5hYCj(p`d>afszI%}=yW|jM-{u!&Ii1x75E>Ug$R{;G-I3F-; zORzIAiC472THQ?7ec$ZXME=N>!EID1wDIc-k8XOp6CIQO0AO#@8iVmNRH(%iOWE$}rhULQlx|9}zh|MBS%;-ard%S|`x|#&wqe#zhwkR4;a-Lp`ey#FitL%DGx`R?#K9fk0?Kp-U=TF#Wc<6pwfq@Zp364Q)yt?|=0tX20%# z{HR22^J(&X!yR_}e2f37*T>)QqMxg;e4hV=Rjh@hty``~1)Qg?=X{v}ea(49^~fn4 z))NHRI=i2YgSj`j0%*mxGp|bdfzN|4M9iDxLrG`rGK_Lb#CL&Cjn z>`YL#Z+-L~*Y!u6@Tpfwhit8U`tUN8AGYh0qulZOo{US#BX%?<){8zxS_iQ1T@A>c zPyU~iRD&tyDGlGa4us`2u*752eMV1=mS4(AS0~?-9Ah%Y0l%RlYuKeM!O~m_IrQ40 zs7{2%mnQUreeSJ1e-oWsN3I5^@jU(%vS2MEtnAEWzgI~0QFKIIsTW|}Azysn(8ykk zt?eC6sceaj$(U~CzAEL#UFh^PW3*0M3}rAtK|&j7%V|FJRvky*$CTt9N&^0>9{P-I z?y_Azq775<2`yv!O1s907yYa;TlimXa5pL5Gkff)s{!ucDbLhV&tLBK&WUQ@`9S%z zTS6O?pl>^;`!3Z|at|gpCc~_IPqr{03C^pJVqS&J!D0r-lxH}AsruZRXn}o*4_emS zwZ7oHV~+w=HxSvGz}h$A!)%demg<>kwuhhieG##smk;BH_%SW%^fid)XjxE#g)zsF zg5qwfZp;4`B1_{BJ>LCN^OqiX>6CCK@iwMPU2a4`>h(^}c9&lC6LGqWFy`b?U+~I} z9c=!xgBDV$2Y=(IwW+8;X{(Y8Cw{sw>p&ucS8~#mRW3Q&)HpF9*B0s7ae~nh@r(L^sEj3w#9$%6aNy4D%D4%o{$)toK(Bw;&WqO zsb}y_$su>iUu(gue7pa1vjNQ?vq4)JC;UBfI>7moM6!Wvrz-E_&w7|G4t*R>+M-~~ zZY%GFw}VL=80_1LqEjgO(b4i6IFUWaEW|BFu1c}2O6)b3!EQ^Kp*CV?fiI*~kT3Ko zcrb`niQn*&8Y{V^kNQ2hUCe-mY)s;6qZ_&Ea10Kmrq+)|ob?gMJZqN1tw>XncSN2X z?CEh*vaE)dLgh=tp;^SY6faSOQ<1R?RT$IJTc=g2gT$NBDq8HrX|^as;){5n@BEnd zC{muLv&@XH-&hE$2G@7k{gM(Hch%d)eB<_{lzs^!=M;&kFY{GA;4sS?VZkm$1~Izu zvH_chx*th>FK^HDqmLoi*M!}=D-}CrEkadEc$Qh*!@sq_#p%nukSigu#JM-~VbMQk z>yO5@r7iorocijEk?21ZQd&_C7m6e$o?HVWL5pmo=kH(@6Bi&v(cAyQl{-@EhaB%S zX@giD&X$7DdCuNmQj69mPHZGD8 zhGQxj;tHOgYE}fR<7}0YGjYgds>SE#C>-qkzE-A5eN5W{| zZa5BHoOd5@k{L{^=4)Kn3wcFCp(?LUtawSee5AcWX5WSIa_tpt;K|TYzW*r>=?B&& z4veQ{F~q)#y%!z96{A6m)z`oX-!+i0<7KyC6qGDE65dUZXz0g5B?rxrcY2dVGX99? zQ&=bYH3CFEqLxi%oAQKtjSR@~M6M<%p_B>T@3KYJanQ)$m4f&TtwD3-9sQX!Ob}4R z=~tQBjKtD0qq^d9PG7Y@K4aHEau*QRHP5FU|E*9>H3G8Q0n)+6ijCx*%B?`fAOj#w*hlC@#5C^<2) z>_doV5)G|dEHfreZWfoG^C(_POV>}WW+Pc5CMD(Y81hM37On>MknB(boM^FEpGO4U z8LK2+OR2?xY~25T8M%E_@rf9c#BA*ze_jvq zPsWOu4<*PKUg6^3^`d%iW#hERv7D|w8y|IUp5&d>N-^p1W*#5D?C$@y>AgDdCt4(BALsAec*5lG_0ZIN0! zb_FlC(l<(Sx~i`?4P98EIZ`h|cn1RtbLX*f@)*J8;TgvkkdesGJ3n0dnj5=Z>&XX& z4@*jL4b)Z(n`c9t{5bBj52?4hUonXTR8J(ub016skgX->U@i^T>UXgWRap8G>0YGlkgL< zHyQ-V`tF+)GZK9w02%d4nALoEpQTUUeNl}jdjjmeBbfF1r+&;xMEEMlP3W(KSY}&z*mgnV!p=9`%(Eh;GFkcAsnLuNdl)n@h=Z{)+W+$XGA`JJxp^9nr7MRl>`5 zdFneFK45EV#f&b~Y?tXoc&Sb_JV+r~h$HQKsbi%?`2sFlJP$R;5k&?NYBP1JxIXD# zG2c`)=o>sa=VrPwcvP?IDkWZF=<^@(n9I7MOt!n7I_DOA^bz93uqWZkV@a~EoQ3J; za*CiIKS{$|VF@*%PZ!2Y1}f<96d70~cI-a-QRuy6kWNw?>=v6(fe4xnnl=VoF_xA- zogk1PPEw5MOyT`C~1#^=&y+>`@zj*69%(hd*y21@e19HxkIdV{r1~8*dw5(*<0Ce z+bR9mfX%+0ZGqG9+WYi`ZfcWflL7I=#(|!j`XeY zJr}X|JdH}kkF#SH%DGinc=@C-*Vlt#i7AHYV_H>hk|kyga8lB}(g?P#Y(CO#)CDDV z2a4e+e-rwsm=st%YT;|%{CNvfv$3}AWxM;(o|x1ndhErVa)t8j)i^pU`)u%?Z}E|4 zA^3LIdFv;!mD5LWO!9ZUI~m!fa&G^2L20BdG-v1W5}HBZ52hL zXon#oiSDR5S7Kc{F>&?tCGzjovI5_aF7C1G9FCNU^a(*XH#(n2m*I>!5nOnT&HGvo z(RWcb%atfUa*J>1X^ikg@Fp&*Autl189sBfDGmL|PIoolfBEW=G!M2_BmlP5PMh5V zw<_OB)lCJ#U38kklb-CVefEf_eYN^}rJTgH^-dOe@^cwXZ#&tvI3F%yjKl0fr)FmR zF23X?puR2dn2?ALTUV>f;U2Klp)Dn0P@aTKVdw+yl`Fsq)5YhE z+MGgstn7j(dui3E^LYkm9l>1D6_-Zs7umAC z2s&;$$DBH$nmJdhPkS1weA2U-Vq(Jv)2j312o~m|#S#6baUH{tq~RY?DR<~Baia|< znug6Xc=CT9e3}p~9BmT0J6(CWJ4p%xYsVY9iMiLYsxKxc6)DiLEk#a5YgYpEfsNf}c((+z-& zB4+qGUszaqoPcdkM1*!eZ_A#g5n{+*;u({JwIxM;rHc6ATP;t}cfOCzs-Nq524ZC+ z{Nv^{XvJQKtA8x>sfJmyqN9C4BaKK3-L{C28h_-krBoNb1D+V@8WgOmYn^CWDyl9L zBWGMs<>FZ8BrJ6jCc`^TH7~;Gq6Fatl9Xb&)iIVZ2upP2kBBfn_?AaDX0?$zU_6-? z%_swYoSQpaxJqi2sd{=#J=aQH8p;)?-dVgr&;Ln9R?)!0-I{%&mQ^8;0C|dmfIY5n zNNJeTQn8`${i=g5LQIs!V=n1sEOc{Jd+!k87@q*$){EkG3FAWJ65x46_oJMN#W$*m zZk&l-1DSd0tMn13);VH2E02QdBcx%e9+grCit-F@gJ9_a4nle z5&5|-6mwNH_04I@Rf`}zgu+4FL$7mqw$sMLPQZT>U@8s&+n zc>QsBx?X5`I1zXEuFS<(sdSbCdsQBuAQd+|K|l84?Ro41oVpB3`^~zhb1L13^}5vq z6DPMh?&rMAj)T&hK$V}fiFWb7?X#ZAjqixDv=(pV?q;exmd;|% zM2pJXBhYRKu`#!{%E5v!r8(aPHxT2MUp)YOTzCx? zOAxKa2~{rFlMU16v#&KbLRpQgjiw$p_*BXZ*1|UUtMYMml|NDily(ush5PE=t#}mE zw$ye3*|^Gj<=a?gTdUHjU@y*(KMi0&Npr1u|MYdgF>}rBo&3N0YUrt`2)G8l}6$iNJzm*EoWE6^B~*UT##1* z<6(?);l#MG)nu5<{*txttb^r2zQhRyPL6(QQ|^7PJwzVD;tD&K= z?Z$&JPa-AY8KiR*5Yh43My3$?5PL&X~{1>aKbAEva@y9cD;#@)_ zbZ@8i5{h*9mC%@o9qWcayGNw;f^k!;JRbU&2 zW$nkGAZ+Oe;dz{>Po&+w^>JWI$`^6qa#+v;J8q_CmE}s;b8RoX!WyZSIlDDywQ{6E)~f6%cFJMoJtdt+ zuBqJ|JRk3Zy&*gF#bsioCgM}B)6Pv0)Ufo<8Ly0^KF z4&(?*TzAETrx1UIsERilim`QRE9r^8BxV^=2Z=r_IuX!pncK;_aC1LgS6+Yf44KHz`_iS>5o+YI+QgRlGkTaN zuE^4?ecmmYw+n?i-E1~zW7iWuYtLfZ$IeBM&Hahkg`?u_Tu}#Hre}oOk?`6u*LWfH zC@5}#%sMd#*A62^ybz6`F?9nnV`W0EH!)$kznf7#hs^YziKa(CE2&Wk%7Jg2juTh# zgHy)iC8*}f?yLw86|VI)^phZbSD6(*qP$X_dV?hRip&k`d8J+hTQ)!Etu2po%rZx| z3CXRUNV}ghINch-?n{$KJ0g@clkPE9AS`uL9+>W8te|h7rVzwArphx!9J7-GrM!{ z5V!vQY^2Jd_^|95t{%?2;(to>AzoOMZ+@~2B3#3`#N+@_ncegi=zDrGAd2b0H5kDG2}@2ygwHX;@gj- zY2g@R<*QJr+^lj#+`?q2o@B^kvon=TIlKn?WJG$M?oJ(yS>)Vi?UbM|sYTJU=Vbj* zYLkUE^q#)@WsI=&z+!xb6RY{W@>8DxX=XgJGAJ|cZ8GFefzER#lR{rp?TT%xedX6# zbW1;T+K|}k?7-$G(~-V@I!9l{<^`9J#h>6>A1J?xK8t=<1P#pXuDS-aLk5z-u1irm zr6lAYOIB7tG#_3OWZn=LTy^H2D4)O656~3U?$PV8fnU6pq6n8_?+ZN5c=q~R6uv@! z{j}2h?z^_xHZF&a(Mo9B=6GxO_ZDvSZ&LXN+T{2FOxBhdS(~ms?@89{v(DVi|!f#q3ZlI)eqe4Nc?S^<=;C26nrGaYtwDt zCKJ;WpKom(QX8D96SMx+*G=*tHS3@IEdQ#;nu*OWxEeSWY`GJaZTWn4SHc55{GToh z6#R2{;a|@e+DkIst;M1toDUrd!D0+O=P{S-w^Q&H&USyF-O#K3om*DUxNV+PQOB=r z+}R)cdN{AFJJh`OsMEYU_vLeRCn0Rb_EpOlx{0d}1_;6R79JA?F|*t;y2mpIgRtGa zjVJgV#~U-dFsGUOjB92yU$(ue{WL!+`qG91L?=#lNz{*64xa0qxaJ0Fl~dTRAMErX zHl0c~KBiU_rBO)R_CvO$L+yL5x0cL5Ck}N8g$Yu+N|6X9#NvEO#Iu%)Z;1uU6X&9; zy_`9+yr_>Ic#4yfp4OC8I?R0Yu3R5bU_17ee>=`zpX`a2ys^mXz)>mMPi$nm7mKD! z;G#sCMJgXvU^r#4pw*NLIf0p2%*a>6le%$668AigictNuxHfF+97G3>cgH6@p61`R zDB{j(#ASu7gjCd`Gf(-3Ji-wfL`Xgqwn2;sj<3qt=Gd^mQ{eivVJboC{R2?C7;tJRI8l^_>6Lia%jL<)^ zXE)vOgm>pS-%T4Be)A|)HcXJiXVqT$i8u#86;}*e+6ZZ|*mI@A2+b&6A3aYkkDVUD z(SXY%kD^kK3%UBT@)*O}mMZk>j!Y2AwC4sop&>8y%h zAJf*k$d@72Kw-b!pa~jd#gOreMWdAxa|ro3e~!htDp18dM5DTy@ZE&*NMyL!ci z+|^&ZH8edwSF28e;pw94wyq|GrLMmB{H~s}(C+ug^#qws++@adF5@^!ftso27w&|a z{)_hv1BQ{C_9rl@LT11!V+wup@yd>klE|EP`D#gJ7Y=XKI>*6s=}@D`?o7V9{RQWA zGOVv2u{5`H`oM~_YQ}XUK9RLFG5r;3db~6m`UEjVy2%2X;(kFP&HXm-r-t+MHH6a) z@m?Y4NzsTNwOFGH&vK#sF&&$}s!V{IKv|;pO77E(b0RSp4`hx#BS*{$9DJ@SFVu zO118L@d*SXEA%YNusUxlr4F60#rRuCi95{vU6rPt3f%)%69vYhqnqW$7u$jBpScR{ zj3x6twM#HUejIla>E_RJb#rpU&^olACA$tvp{;61rl;*ZOEWo1PSn=i-Ip&r7`ehT zyrLU=Ns#iwutl_|YukT0d>S#(ZZL^aQaiZfY??1jxH685_XP(f6-DYHC}a=+*ZM zQJSB1gT*t^;4(a+O;AX+RG(!-PB*5#QtyDSQm0-`hPZ~c`~hO}_J_kdCx{&SVZ5A_ zNW5AG%HWdF05I#GDLF0WD&0-xu+);hR-(pw)90UGhJ0WTCAiL zW7dc*zFN^??&JFDyL_@wa{NMO`*2IJaa^4tGV;&HV1&ST#$e&{-RPQ({5Zu28{{p5 z?81T<#GSkBg7MwnZ{qx2l_r~9F*+!I*!8ip?XTGbLWe_)fdZqsof6UY9$l5+*}2Oo zG!B0{tlTGQa=%)azIvSXZ89+J!tokN`&=5BsB2pX3E4xilK(*YN%XJPnGg9%@jimyHv+?0fvQzXT+#JAC+) zeRXQ8Z{D>g8uF#tLx+!#onDP+Q+ZoqUA~HsF`0O$X|qH7PD7D{VG&5`cvkyPOom_P zt4P?vtq4!ugzA94E$7C2;J{+zl_q)zc8h-eX=%+B`Iffiv6hBfdRZmS#+6{*V6`)u z0+=Hd<{(sF>;-B{a7|EdWo~~h*4+QLUevQ+W_q@M;HeBvghMgIwxaXd(HedW8Xr( zZ)3?FHKCU}C~~ami&pWjtMO_@hWbYV>9*;m^O8Rubl&KT2)AA-j?avFlhuvy zaElbA$rsdj*r6}-Cv|yZC;`6DUwr>C5Fl!d(|cr{5Pf?Eq10NNXxbV^l5vWNv5@W~ zc2kvFnG6?E(Qz}q)UTxdIKTG`npf;s7>}h(_W7Xm@c1Xt(^I-T4!J{6= zPBzRV^IJ`|Ti91NW|;)M2|=f$pG!>*(q7nj@R#_dBtQSP1f(Aj)%8_{4VzUqLsYv7_} zZLsTG#Dl7qrLzHFGS%wShP+9&IyTbb6H4VW5l&p0=Y84DyjC?wm##bb+Ft zEo{g^c-0yf-n!C@kQFFlp7v8HtxdFi*7BvGGD!XO3fgTO-%x_(LKI0Hn{)1?UdCk2 zBG2cm%*B65UngLY;``9@Nf<4Y@w+Hi_CwLfhf}H&(p5u)ZLP^sxU5|xB1_l63^M&1 zRsX7Gps$TC2T#Yz2Dw4>sa%^U5P354T>Z{XsF5W%jIWv1++XU_=8Z;f)BVQEbkwu% z)oNCLg$ zM650^5Ee$q3L5Fn^OSDOOl!OCUc!U&cH)itdYnFl#JP$?0LP0gt#pgAWw{D!>U4aj zai7f(o6X%?TyVpuS@cT{@kUSiIUZwa^;tjWM;K$_nsnsVi4M*`D>12qP6&N#u=!|^ zp-sP)tQKwLNtST@NPp)%-`{=IRb@^C{={1MWO5b)E8Nox$PL@k&>+|mi}!ZdE^a#U zUo?p>dDWUvX&9r)H7C;0eJAtkWT!oN(X}?T@a_j$NX1ia;-wHc##iA%akf)KrPg_m z9ain)X45dA#MB2{C7j-ORpac|tU1g2Wz|O+cVt3B;6=DyFnGfMd= zewYFHw@$n|HsrlG@g8>301bnlhC0GNzn`=Wh}#J4OiDplnM8?%JeN9n;5Pv^*7v9sNFj)ZGJy zJ}}zCePLZSYEOJ!RYMt%@aT?IDDv6<^+tiw+Obo}q|fQqyW3V`^@x!TM|++yi38eP zr++{!sg2)UHAimOa z6!6G3>LfP)aDSE-yN{fobOc8x^}d=2@6pCpH09a1u$W?m7`vRp`lg9h^S7h?$c$`W$)c!s9)Rx0JbUg7r9zL+coqMm+ zIsTA7+5Aa-;b(8u_yQ~lm$M?RH9CvA)MEPBBl+ZoKr5K`LTlg)WjoyYiqr;OTUf`a zgXbg(356XiM7eJa1-nNYO~NKTc|AQdht#*Q%tkPSqOgJ(QniGDhR&Hj@fi~87#SH0 z@ZRYHdKqniJ1cCOU7>n7$zbPvaEjJ!xeMn`%}lK`@hYbk&ot-+rG;@NVTHG+chOyg zx-RSU81S1$45J!~_o`qvfS<4IkkXU zixowy`>RbJdr@db3uTAWu`+=)gaDLY;iG)Bfrx^N1S9;%wJN^$GPBrD4;%7*yU#B5gjwFb(tZTaJ2jPaRd zQbJ1Y{Gj5~*5^&4Z6}GtIm&5FJULySrxRs`5GZMp!W2p`e|9lUxuh#}EZM(wMi#!7 zq7JmD22wW+)7<9v;kB_w8`+NxFr*@ty2(qf9-m~;%*i4 zB;7g=XKZdIu}&n$4{X*!*B4q$p2M*jI;tl-_$B2v3vj8??-?m%!inF-!@_d1`Ls2q zgxZ%Qvz`pID<3k3gbwCL<^q@f9!k~k&t zD$Eso>n2;UfX!nzv-Wpx@vmLzTbWKDR^=PAgDd%55<}F0F_rpX zucpGP+Y(-X-*%BQDRdE!=3#jFSCb`hUQVK)bFofgS*pQX@vV&Emy7~b=t+Vp@(M0Q zi6oIpHoMEIwU&OW?0U<4&kaP2#GxswDVslT8(mRPH6HA+Lx`cWpgBk#r)aPQVd*0A zGcnh6RBYHvl8MQ*e_0d9Wp2{}j0x;0m?3xY#j3OElsM*9kRQSo1w*AFBhMn(Rm|$_ zY&?@7#`@W7P?Z}vL#*!t`3HqxM^bYzhhKe3J7x5UxKx8*12U;-Gc30$&egAhIpe$6 zz$Lrba zgE>h$H=N8n!X(OS20NUfIdfxw1d>>|GY)Q+_49{+fIW~^W<@CAbf{NLpJCp)LL3|p zuTcm%6rI@YCgRw^i{B=3B>Ad* z)Vqf5XD~*QC#3e#Iv!^A8Y~~(f3F6Cu{R&0=o8dn%JKk?Pow zd3G9I=w6EV&Pds5pckoWES&&UEx#od;Gk@#1D7Di1mtQ>? zz%A7mEOn<7ur3%BTlm374d;#_nU* zxS&4%E3&iPYXIig|72do0LGO(z4jHqddSwXX=DZr<#qk>h>$p^A^04}+m}$LCItW4 z-fNME%EL{jN>z0+;LFmv`}W(VZ5E#T0R*)}0-)l%)#=8m4sL6*ej^e1n|8Y;qMC0& zk}nDc*3PB%{(bYXcjE17s2I5-NN( z4f@J?`@1pM9Qf&xG3S0&9VneG60+*Ymeol^qBb5~XzVERu|RM}mh;3jY5=c?m{<>C z_u73mszDvadg31WS_hf9H0cljY)6k)OtrdtpDF3OCv2;B);7`PEPeXsQPg89WhIfh z$?xU+A$9@qk`gdzqEU9)N}sEpb6bzi$ur3bZy62Sm3e3~a&eMIZaujqr?$kZsd%KH zdPbayi<8fW={tSBg0?}a&!rq3Ey@vr9vGQFF4>UgEjlc{my2Uphn=mM) zE?{WLI(_6p^4_asTzv4*4}VXhMykKzoRjPAM2izY%}2+lrGn6RYm6Yo;vVos+P=KNA($;&uQj}-M$7W ztg*o^L05BF`d2QJQEpQPS0SrNmpEBC7HoO<^x&gi=|)K;){wYBFXVybgbRWI!-}++ zAu2RP+&eaF)KpKksy1CGHKMGy$w^D?BXvido#h^beYNoe+0hZ|d1HaKwGDQh6lePOA889)ajh=Bu4>Oi#CUF!oHfy`C zGCBxbdcZ~=^?DB|xF_)1$!HYD_p{vVAaop_te0#%5UNQSlB6?LhI%O4HgTq#Ujx-8 z^H_k_Dj-UG~ub+a3wUM^78og zvm*#BDsj%)pu?fsPmHm}_VI)Kw1veX;|em5->0fIe}c%>+b_Cf{#=Jr{cRok?7h?< z=M=-7v_3Y#%s-pUQut8bcD?lYeF*>8xq4PZ?ORwM)Iwdvk-Hzsm;c!P@HZ_xN%p&= zIpa~fF)0imiuTpr;LU~S%Al1)8Ql7`lK{d3i4C0Id&Q5&?Hu;YnJhySOOnMZAEmw5 zIXcOKtHsbRY!9ip-kBFnF_d-gbyb#V8O2PFm$n-z$SKdlg)&>!|%jy~V* zsRe8A?sPPIyR$JKi-=^epB*f;;^wCkO}X(VqAL*gN2r4pMMvtGq%l7Rr$@$hI<6VY zJ!)#B{OlAM^|5}z)eg7hzE`jBm=nk$ zfq11-SKo?>K67KS#ARxfNV#`r%Y|0)+PtT!ZYj?ZRgD?~;!ebMXX1>JQ`R;hj8nCN zYF_UoOcr}8;{^kwMZG)7HCrNcKy7>lChHN=^Wn$5Xq=zRjsA;8DL5f1fx^em4-8hzewlEui`># zgcs)>pE$Q>so3RWJM0*`NRDdRBF%1yvW!k6gA=HQ868beGq=Eo^Ra+l_x45PM(XL4 zc}{Q$M%Sd!16`=wHGq#VGzA*@wo>%Uw@?1#X6+EcFBeA4Pw{`&4=cd6?4r7_@v6H zaz3h0rVdlkI-W}b%hkOtY<%w$nS@OYBM~Iac#Tb!KLK^>Q({+?mq$?}FHzFJ)H<6~`NC<}`qthOFUs4vqqb<*I$bz?e^U6F~WCr@q7O^_b^=Mr> zF-OgWWVD)*R7rD;vYnL)R zQAI1yd7OEzq8K+Y@tX)p3R%cPfF6lbbaloQ6PA>c?!zpOXnWd>mDQ{Jr=aqTqFS(9 z>HTP*(Kddg`%G~YQ6!gLqQm^3Biwn%U0g9j;a+XuJ}JaPF|tJ}`*3tgvPoc0=!@DN zRd)691^gTBT<6s_-o-@~y=V1vVJhy1$6)cZhzK%y8=1!!M`>wgcV)o7ugL9C>WRaA zstq-0SImv>3@~Uf9?PHHuS#0&M}^!^w}M0K7Yo6gt>#ZR6Xi>Xx%Ldx-JV7C_rF&K zS$45Q;8$cKu_Ruo*ov%bX#Eq>_r}FaGM&nyMaQ<|eEl4x!coHI9CIS|+^WhAtpcv3 zT*|8Y-l*b6FfkGV5MjX!QI*-rMN@! z0tqg~-HR6}?hb_ncZzlMd!Bdi_j&g@Yn}7oBr9t&YbKfb-q(FypIh8RYo0GV;IdBj zy{Uuy;%yyiOT+2#g7p@pDzTsKz>Kt8Fxv9dBpv=&?X})UTP{1#BkdVClwjy^<7Qt! z)Q|(xPD(_;Nkt`kDpX+#fYhM6mCE*ZuWi-J(V3!tED_Kt?L5jA5T7tOn<2d*>6 zGunM%Qt)`Cj%FuB@-1C*CaC^;lk?$&V(Nl>r)2ZXWtK=Gbv?+?KUku+r!aGs!*D~y)IdVQkdNDcbvWjZZdcl(qS4Fxd=4vJhN1Ue@ zx`;p};J621(J=iKo*-DtPihX-S-?7tLpg9d+}Lq-N^wHEXJ;ef7^Sg=EC){QU)|sR z498Uhr(xo8lg?I~)M_=h6$=va?>%C>_V#75IOd~YUwr8s(rwJAYb}h+PN?;NK?;v5 z?QWH6maAy+h-gY2lZ?YG6KI!+;3#o8W-9?e>buVA-oH!5e1A^WUj9-L70)l^C4ZHD zMllhX!+V_GT(pdw%^Qro~3IJCH<~9c zE(k>){D8drbChsExh@0ogUWyg-5Nm0RC(9WDf<)f(xQ-gFi9Xyp>QG8*CzJmnt5N{ zNZp0CWag;fAGB8r@8y?)=NSVXnk?(gsUeg$=kJrn96UZ1NRZ8_Vu4rp#?)Vr7kGx-+JDKcK&YH zWLM?|PkO&&xahw%nx1%)EXjX${^Z#FOP|SSf0h4~0;ri)CF6rD%3Z6r-)z>o zn!!c}IjH{V6<@yALvB)*^(q^WC{=63zZ#Q{I$Mio-BHramml|jbihkWFXGcu%VAk_ zJ~p;B;+0s=LMrRaIp=%6&Ma2`OZvq&TtbaY?R!w+@v05xsHn0kB5pF1vuQ^uwjW_L z@&3GKC<}GpQ(1;F{8_pS;PKakUE}z)75&;b)obY~hfVO!Yb`ldmnI>K5HRH$ zOrzvvjWKa$WcE9oMg+C-?%+L1y!?!JpC}6`YERGB=Dlr4#+nY?1!3&^F#9y0b{<$i zR+8bHZ?s;iw`_U-G}YDH^Ge80i2b-~MJ}wU;AVRzgTHyS*V?YUxU4$-SU4)ub}Pq^ z&RfYPr~n-71(&Rs}0i%E2lU=eVgBTHDv^D>l)-5^ex zH(^%W<}xITs05?7$ZaZn_$x|j7J(j^ALz&;7hkbVkEuu%#~PDU=}cSjT&OSRJo-I2 z&~g&+L@Gi99m=!_qt0OkZOHWh0#TC-6h_#SS<^Ez&}-!4Gywo>S~-xM42G% zEhW7yv8MUnZdXKiEV6MapCyz?e6NF*p`}^o2JdpnmN&HgUV4WDirI8skuUId;CbJ@ z`vJ$5-%cKnsw=zL^j;o?E5-L5FmIkpKi<|KRNh|XA2YVm=aR1l!Z3s_I%n#WI5j*kmu>avxD>SM?NEGNPA=-GVq)@@D7c zDVsuss|pQVC_MbWs%Q)!e^|@EBRKK|9aU|+Q&b*-lU?k+X~ZJDvxF;5;*a~*Xk}BQ zIQ@`RYUh+UW4kwZ+ns;dH30TL!`06?jH|X}qcX!{+99-__k@1Bkatac0ML}~^;Dqg z;L#W+>3Jr$G|7qRdHI)W7>t@Hu{)h5ZO;kRh)zLafSHs9HDPbe8_>=Vh$oB{M-OTv z@7U6e2L$G$6iH<>=X?COrJMZ&vt7;a#)AP@LzEy57l?M$f^Dv`!LQAPtBknlus3hf zDFd(1B3o5EQLnvfUJAhV7HtgoEP|rt51`R#t&8%Z>K)$Na5(;!HB7JV_xx6Cs0VW; zAI5Mxfb%r*Pm_qU-K)XwI^M${itTmr1(C?`wWxClt#{M<1HBC_sT~-Q?fRTmup9g z0`lQ8Oe@GSv6-3f!ng?DcGuzey zYKk4j`WQc%MCUgWd9%scEOIF3!p+%BQV~#fu#YYcDAJ)YF|l+<>1lLd=@p-;eR8;Z z+4GHqr*0H?2|-8}GY`E*h||_OG+Np;*v;1~M}K>2j&IOlyH?`3B1n%V)|f&q-*nBN zZKv@@|BB_cZbQihSsQ5s*wO!J{Vw6(8FwYf#{IkhrVPaQ-p95sulKS}Fx6?LZW^qQd($;`>4$CopOc7Gn0 zWzFs-w^-WM80QQnl3awi6TF3hJ;^L2u3=*M1hPNBd z;1esU)-LKvk7l%rJo5t+%rRq5&J%9pMeZrO_q1b7e7X+jk#bNAr zpt}N%6zyL*GM*W|_)2__j1wBa)}4hl4%Dlm1=_lVpy3TAAxgf zDslFL{o}1gt$)^DrndM9nP4mrJ{6utgXUdpv!jM`2+e-Pl8Mf9#jP!4@c;)49PJTG z^adP^_P~w;wI$g8#Q~W~7zX~K%`17%YR4jEOp(Vnkox)b4yM%Oah5B2j&x6AGcs@$ zWTf9C)5m$jS`N^|$GAB(pbpIR^m|Umkeu`lGZGfG+v|Pb{>W5FA}=}^9n8Cn#Cx(tq5bfU{*9>`&BC` z|AGPH<8j7b^xGDrV*0Jrq9TQP4d(gL>{CeAR3l5@_|Rju?rueIsX5!g{f2pUvUTg- z^L)H#FXU$}2Y5KXSSNR0}0A`#gW1jj;8nmWQO^yV^N{hk=iM;zV96*Lz<9@2c5udwj zKHweIu`J-joaLebKknVe6al2GT6jT0Sx;@Z_u`@&wOjZc?5oJV^ji>m-IsTGJ|1dj zsuSJ=-l>~3WU_u?_`DI7P%ZA*^(Q~1|MfoiH#R*~0 zx%DJp(-5oUN?E~O9_(Bp3pE0|4JFsSO)-Iq$Pp1H8K#MdRS=DisD$=Mel8m~#H!Kr z{0x`bH1Fd+Wa177AiQ_5m)EkSHA~LLaEAk2y>rnY0JVbdsTt8kSp4wo6=30D@FM7x z!S7whiGVnPBU6idN~H#=rEgktf%gY$DL-}bnXaeBV^rAP8xpBNJ+KQLYQ;&;QvrLB zOCoW4LC*8vu!A3f*W44Iy(LTD*ZQ68r|W-dQN_iuR5smzdA?Opgtkwr!LZrKv9!A% zi7!(T%T)<+D;Q03v?t!?XVL%{Yb4X79G}9kOUJFiG%mQ%Fsw(7n53F)6HSo0P~@^`h?OVjJG7>M_%m3YtC<#bH@ z5AP0&E=r(V_T>v3p&k5dO>lvE;~Ei4QVXC(&tV8YAvRz$B8ogHYfP`KP+Krdu*GG@ zW}WQ*X@2M*9;)YpR*#G(JQMzT62CU9-yBLRkBs^GISuBd`JIShApLE7=K%3`vEoiu zshcM#eUiaXD-AK6kauuA-BTRTnv#3Ecz1-%`jq=#rbeYI2OcdVHF*R75}Eu$mSj!4 zLoVi3%`+Fx?NZAs!P=F|^|e86GqT#zmZ)-RDoh6fR0KHJt0}md27ElxWd7ZvOS>xE z`GwgOD7`lcJeMG19luI=Tr{^zm>=)CpPM^#E!4X9D>q4etgA(*oZ4!nL@%3ne?F1^ z*IwZ^APJStgf8KfO$(#b#C_~y>!rEwNg%CTGOiu3zmjU`*zMue1xu%fIECM_rp;uw z-m1j$GM{$k_op)r2XoZzAFp;8IXNF0EO~R4iw2aKO)@EKET3xP#n>{@jJkSnMq6kf zAv_R7`X$0H2#%CpCA-Fej-25g2siDXpcUAC;R+MIG-`Atv)s#=Z{MaUV$wUQp6$Q z6fUXwJGOkT=x7dBsXbD=BI^Zy?2{hE42Y5 z*I%qqfez-_t*yKDO_TLwkDOAG{M_6+1uh9U-QrV<5aDF5THU2)tv@0q)aVrIuxXnV zM}MAjWz}Dyu}3NdW_4=&D?8Eo=~&Rc2f2ag{+(^km+&0RrxasLBJ;+7l{sedS5 zYkm0LqR{4b!jnG*+$g)Ox_EpQyxn4@kdgm+mYr~y4q1qsuIWoi#c8%)vh?Bocn>Afd=?pjz9hJx-M9)K}yrk%pKmJ-NUASvaUe z__2W!PMMw;#>AsZeypeZ&_<;#7IYf8x~fP+JEvpxw+mFQ^Tbdx1&LPA9;iBd4Z)A& zebQ5*PgQS3txh(++c%;0j4UC3U~IyRpugi``zO&{_(e)LWHFvq~yWDg%}x}c$w z;<=bQQP%2@0g8m`riu^!^u(v=oxO&re2m}o{5=gR4*YtBcvel2zO&>Y*cm!kdOenG zsL82JZ@y)k>kpECR+B8hedQl7n6odKJb|*dyDKWvs;>!jV0A*z$wHzYe-QMK+F`B# zlz;lWvUwq)T7qOgv3raPoJKeADN7u}=HL;4$LO*-t$U!Ee-F$3VPHI4kgdoj1U<*n7j-l3Dq8>dUR|7m4O}L5m()d-E7eX^_%J(KQRXJ z)7q@Z(3>~E&M_`(veTQAwg+4s{mpUt27r=o!(u}PHQVM9=+4vg#r)Q2@2MS+dMW#` z;qOTUNK{TG*=`6_=H5#Jo=SKg^&oWR$#nRohkWgLD`1qHo7r2vlPEEdB*NlkCf;vC zoCld}&U&6T^dVQczyru-gkjCTF$>Jz?^of3{K(h|3hbjb_mVcs8c)3|yxfs7X8w~I zwm3hhkR-NIYMMwKk~6%Cw)a;;tC36?D#mUT1=(Ny_{=z8-IBC>Q_a{A#HOiYZEL8^ zsWtfVXfHx<(~slV)GgqMHTBdzeG`GesqEgKaxOJ_%t`mFTC*b3ooy&}IC-j$t9*@D4w2dj6tIaMYn(7he_q-{R2p5;qinty7X6n!`xj*t+Cs)qrm*=J!Q z-sPNZ%b%3hnqVx4CKXcVYJ#|~0j`sW1P+W5 zIKc&8)JLX-u7ah~#Au=fp!oKcT9W5IwYCf+BTOnd=kc#8zLLI+n5SLeBS9wWVl6lOtFU5YMU zQgf0!@rx#WfJ661v46%OK8$K~3e# zlQPV+2Y}oxskPb&?)fkkcwW^;=V*`c*S}bliNyXpkUHD`$y<)6>pYjKpSQmt06B59 zo`uA$Z~Hrx5&1HjTfKX!H_NO3;ohdQFi0qXi(O273nW@!x(|*benK<|8yn+-t$a}S zIkxtryNW6{s+O{EXtItAdG;Xg3cI#2pS1i4WX!^#nQfYTLzN@J7g~*rpjIcG)P{b@ z2dg1UV2vTH@tiXQDP|k~p&HP=Up3w1DgrPkm+ouDeDg9aT1s5`kfe&ZoO#DZ&j37H zYbxdw%ERu`a-~^xT$c7G+KanY?`L(d<)!2CZiUnL^h)c4d+1X+q;4%*d@ge>w8O}dK? z2tlv=T}s|1<^RQ^aORB}KMj|SJ8 zk9L1(2Y8vO^2@M_4ec^bvw(;5Ii7O>L(!oU=;D+~NQH-kvH>fff|Vr$O~%)*36xe^ zL%vt*xYp=+T8oZ{!Age&(v&`&2}j!V`-e#BRDj0qO<3O?z7q1U&U#6RLNZMQKn?U= zwCqTZx1F!!*V=Km(%U#P9wH53pw3~Dd^0m#u6oo912c69+|HM-Nlfiipv*i5G;O9TD z9|&7KOO_;Vs98%-z}`Xc<0bj)-~|7F?W6C1V?O^ml!AZdO>ge^@hjc#AuTbV)5)J- zr2oPG{MYyX&%^&uex=JjQuCXrnWcRzVUl~v6Asabos!Y_^1{E&|E8Inf3ed4?fy@$ zxmt$BA_cE%gwDdj`K-?gAG@ofgdxn|=g8`4=U!(N0!91!+wU7xESM$b5sC?j0}i6f z+vCBk#pK>#GT)A$fG`(~1NOb^r}T;}Ii|WGngQ7aqh#s%k*Fz&f#AE`KzFmUncOwMb;E!)oN1)Y%rOMNb-m#X?<$26Y)RQr0 zhGoDSBY%$9^KmujT}02TI2mcN)Str4R3K%|3@Ivl$MHpdi{-{Iqxp=KM^mXUs8?B^ zxGeEA*x}Ku1Xl*_0hhlV;_;(O!zqV(4^{5iP*n^YpAi;%@@2Eaa_>;xBnQyeKV7K;whe7yXP2= zZgn;Nv?wD$_`C~n)NWpBi2jSk>t|b&6YrhqHNFpm%_%;h#RLrFl4lIz9ngj&;Ya1Dl4PY%u(FKZZ?I#$HhL;!Ad_RI5VHAKh6y`bgV zhJqtgB&&XAOtm;6pGgBMUuhJcw9_L$^|&Y(4+jn6YQsZEjSW4rT*C7gYZs|MwuM}N zIS3dZ*<;}k(2n|z-6#4mqBvG3s9g3hR&(*^$>tQUs)hq`CoUy5z9&87<;J|iGY_>I ze?=r)5MiK>m&Te8gZu-OSsq{um8MHuOh{eNwj<|*XwmmYQ>bB?V8^I;lx~pm-UTz2 ztz8SrTNo}ESXr|-*q>f|m|sjN)lFe8?@?Rx-h9s+nUQN-Wdbc=U+Xl5ttkI{%CH?i;tYKB}{FzTDvriQNL^8o^XI zmJfz<5H5Whc)K9HHIlB=e4pT~q0A6Q-<0}!T=JFB)OE?m%#STtG(M{%P_eoHp@0)a zsb~T6>1>J9pz993E>bSVI7`gt=Ikjok)DZk7JPIPBjRAOKC z+RB1k?)ca3a7x2KZheO;25St`n3d`BX^y-_qZ8e?k4K??D7h+H({^E?~ zKkLZ&H?8EydW{LNTh2T_UAx8)6%K7RXn5 zNUq>#LoBB1Z#c+@v7a_13y6mp7ODL%vlIq@6bu*Ur!>zRAz-3l9k$B146op4(S0S% zup_qw)}oAzq7OF>v{KBUqn6IrJ}_!c4mlL^9nnsTe_nOAk`K3K6|MuvbJUlSjzMG< zK^_gk^v;z)q1&=M+Fyb^)GG3o5!8@mW9ej}sXS3gSTQFjOSH&IKHHR!7{lniwSoDL z19I!F5UPJF$AmYP!gBT!88c&a`K{N23yV9JYP6lUF8#?T)4{2~SWgCX?w+GdAM}eE zbSVctpH|^G+f;>}^)`%^MO@p?-L|A>BJ@HvPP?a)4Bdk#3sTpAa;_6V-5Fsp@wg5TvT@b~K>Nw|qJ9Jbb640? zCrqC>2KU<+sz5XHz|?M4z#`c39~G5p^-x(|;|)2d@~9x!+1UnEz&#)qRJ~j%{JzvF zG5=EgxBrJLhsOFg;8T6W4ynE&XDM=6Q2gDxY3?0ptyG#~w762^-kM=EtS0f;%V#3m zcDlt)vF1w9=*+)ZM`-a31ei^?pNOuoQr0P(I_2o*s4o1Pt;CXE@=Q2Wl1<*1^@?w; zSn9D{`CvtpP5OxwDgz@#mIlt?*XOjVKv&nbz1!qoqL&T{@FTBD%7&LyOY`%NNmKpd zfi8k37j8asx6P>U?kS#+eM?w*K=iu7;FfazE@BjQxSuG3>%}HiT&_}=!J(%(Y3#94 z*q@_rDlU45hlxgdfY(*7p8ilv#WWDvmfEE>I8~w=o|LIhP35#|#|#h`9wuB*Z@j^E zrQQ9D#ZLO?FsEX4f8|gc$(^b*f`MBJNt~wXoT>`7LHyrtf4H5)=v~FS{KZQ7WLk5h zd#!i>cR!%`Fly_&L!9Rq-FHe~xRZ5Yn!PA6-WRkGSa9`$4pq`pqxHk*CX|4Qk#2s# z{UqW^Z2G%DWgoZ8NA4KWPXPm2T)_B2i7P?Iqe;*-;reH)H0YdBWsrNhK!>1W!vvJ# zd~!!)NSn9%KA==7r-7<7^c7rF6cL7WDFAUS*r>>__&}%X;bU_W-^a{#FvX?1qLX$o z;OIIi-LX0`t>}$9oX*s5Vp%m(#IenIQM-i35Z|ko6cXg8KYxQ0O|lR4Jc$oB?<2g4 zm)YK9khy#gtQuXFzcWXfd=Tn2y)>hz8OauFfZd1W7+m@cC#G;+xAKJfO7&HD)TTC0 zf9rr$-ItPadnR%`v6T_s*3v+sefmITSpxd$%k>6PgMyZ_S2b$9J!1!A4qP!&1DCmz zSJBf$Poj}@;kqz%l(9K1DrfnCfrO!R;xhpBu5yRyU7{H~^wa$Bg!O}mCU3H(pP}&% zCu>8HJsYLfhWJ{)QTS>=plvrQQ*D|xDqQU)gBVD3Oznv4F2&exf;#S+zZ+IxS;|*J zU5z;tIGo{%E5N8|;BxguR}#=@H2j%X+89|y(7YX8M;a>JIlbGn<1)%YrssYpE;Ujf zN8Bgl)gvZa!*5k0$EOdpNjxtlN>U&=Z(&$?EI7tczHBO7#`DK1YztZ9*9;7ZV5wH!^Y=A3`nE9p4IO?w!@fd|`Ak6Mh=uFQ1%di8O6=X|QJpF!K&PWI6gR za|8dg-$Pn`X{<y=1PkTX$v`qs6N0#G23kj%7owSu9NJr$Egif}ON!ou$9n$WNfWr8>sg(dewz0)twf`Q zSZmMrQs&BM-oFwQI-4;wM{s=nyXNNG_SEuR2Ecx0-yaT}%FV~5j&L6`%f~g~8aePi zzgjiz!OQtKBOZ0nh>s7vxL@Xu{Tuzwj#)^|TuTn2;Lnb5_PhtwC;dYiryy@|AX-Zd zc^#0BSaFom~~G;kLS+N4zeNB?$gT-NB!uhF;XRENr$ zSAa=^>_vp=`kru3Tuoiok3=&@`%|3jNhc?m&kq#Xw)Kz)aK^0Tt2-yOKTo7x_d?Z> zmq#tCvd$yfi5S#h1F&{mk*t6=LVbMhctnj0>t)a2$zH4YQwmQxhuid5*H+8}J+ zRX5B1nx|cv^xf+xp8*$XD)t`Q3!IxA8jI{5SQGsm;;qAON6NuaZ9gxemDv=^f<^hZ zgTGtrSkP9VoST!539)d{@H2G?*Z?k*epL@ZT@Df@@+c5+Nkna+q&hP_%*nk+ zyGu2Q=Df|-kL?=;&$ebwjs3bQ@>-09hL+SW4VZdezqRnKFc(&n>LoUR*C`=IMHDkS z@_T${U3uvmgbkFlJAE8Y{MV@O>K8AYO} zZ(sgbXA0X=_|VGW-ab&fG}2zWc_XLQ$>38DcEp?{2CWm|I1=Rk;C`;q`f-waUUe~E zK(WnHJ9ebIg(?7(>ckTO%0N_#02t$dD?VXq)9>f|^)hko^DeF}&96fL2nWJrA3cvM zg2(HLsXpZCtVXbFBR6t~3_tX+{4Q3Q%q#P2r3;=fM(kXC@*mMH@1GEXpVkZa2b@xq zuJ%RfQTgS>O_9`-e9sm=@(GM_f<&Y{d+#hm|0E{p6zUdbER7Z|mc=`G06oIPTV}OQ zo#l4gY0{x#367Etti|MREGA%QH!A>8>%Tj5|D%lhrwRAJX^a12&i~gyk^cvC-rw{N zO}Vez`T@1Od@`iBV;akM5FC9B{fkw{9EfbQ_ACBz#|90hRJQPzUOox_;Du%=N;W@~ zZ2Wl}I^J|$aTnV{lI)g*>aN~yA_1u{KV+{~bwo)UY^wBV0QAqxe|THVX5gEkZwII!Qwg05;v-OA(s;qey{O%mkA48O?m-NV17J2-kyFHSi8#ZoB0yK}X^(t0y0 zX5zAbu)m*tlW8+Af9tBsqcugdc#wZSoH6_ftHRC}>%APJkm!6i8o(~wEYEc#)T!Ic z#7u8-@Xc2!ce@1u8*_I~w7Ngbla}nlQ!o5WInB#S+3YrP@tQ^^er`8!YY84`8798| z47rPF5F9gdWT~%uNkE{?7ALFwQEcTJ!ti_+3WY%*1{tDS(p(L=YU^8Oa_p$JlFg4L zdo1cUxS4trs)bhU$Vnf(6@57KBpthbWVppLG5uXpBF)c^#u$JC8}lh7QYUcQ`)%32 z-cmCxQlt2cG}TSOfLPs8I4-D;rZUd)fu|fIf3WY##zxljqc`%iHd#;6;;ezz!PCk` z&6{3(UbT0ALQ`{anq@7ZNV=y}xHoF4=TmPA!HIND z*Ed&0h!RIJuF6TmlF*LYp@Y}-om zX@&J!?x~1T<4wJ>8fG}_^UoUSLBJN=lKzpAJt+PW^KhX|T;5--OXu+_W)4jjXPKLk zRgEC>a`{uMc;QydtiiOQe6l^n%eW4UD2$#NILH`ig;_2W=XgCjH)s^~(6WcZZ_CcX|W zA1zt;f9l|iob5RgF_xQ()GJz;dYt)^$$QvH>?C23^Q~O$gF)kxlJnk(4bQ3`{BB>m z$E%UVxl>^!J8JX-5w_z+8GI%kdffa6LW$KV@5Y;G(;eLXMLRv+Zv*v8R<4`d9%kP$ zhYi?YvDFjUhTdY^aQ4P%j%0Y2e?B!d{IEN(tWd9X(#=|_SIR-%qMMsHCy+M>G&LPu zv3sK+W#%$vk3mz)D``x6i!WQh6P(qUQIspKYhu}l;IV!53-%ouAXc1peLre$Zqm~H z8?!T&7Vg@ir3Z)v$nQ2>A^;ZX8!+B?yz zMWMM~MaV2@J4Df4vdX{uuQQ`SxhMG8>xnmYG2xDgYra6g1lcU2K{ z6P3I3Xu$vVV0H2xskD0ouVA|@SY6hq@_COssTi9*{HJSg*Hrwr@~KI{U7|(eR?+h+ z&qix^VhEq5TFD-`rj6$YW9>&WMR}Tr{_wD?s5DTN>UxF#17X*3Sm9y5@?WftIZujT zf3Zx7CO-J>+-yiW-J^`)|DcSr6WQ<%=-;6KJ%owO%^o!3q|y~m1$O!u%82wIugE>h zh-Y=-AC!^y|AjI#zV}j=7CroL)8v1xx$l+IxBn0{eKbnb*i`u_;1*32hLeLU)QtwL z^J%`7>xFVrC?<)x8P49IKM!?>dGxHqtav2)ulqBTuQ^@!=KXGbnfa~7NxPyKavJYv z8r9oaa%#zF$u@m~o|oj)bku z@w=e=4c}wqM;z^_VdnGqM~YriS|NxA;8?7fm4Gr_1 z2Lrp{c2i}?yGFJ*g>^4KTZ2vYG)}91{7Vc4s*fk;N`GSk^u0i^AB~z?LA53C(l?xm zGmOQdoi5#+&P6@~>Oq3(0Q}Xhcq8gUKg8ss`0gt5W!iFN-Cl+MarYhr zD+xzt35PH<&)mVwEwY2Tz5X{uNMu1VVUL&)>Uo5NRlv^Mi_j@NMyiq0Q7>Prhi#JA zVa;fc1_xhG@KFC-h5a=P{c>TBTPc&TDTSF810jz79wZq~4TVlYwa-+Pn1Jkz_B8JG z{_n=7%HqQMh15zLrw8d2cCSi{eosko?6>3{yeSm7SQx_e7fDlCuAzxm+P>5_t}!xw z<$bko|LHFlyt!WM+^Z7^dE2crq@-){7i)jA8kJxVfzE~P=9a4Scu(iK_mix5HuZ(m z4|<099{z~gaZdV@QAZU;p%R(ztX+J<_(Y1=Mn*XN?m}f_h2)7x!m;9{KlfZ!w#}Rv}#99beRHVnYG3hHx z&GDwtYD%i6^r;Jyy1#{s^@3#Qss!C+NJ-aVif;j^8>{B1;lSpEyrQLjc=6d^6SK0G z!S72isYQTdnVTQ-PBSX?_-6FWeUKZ%14xGN zhK043^6Tt(k+;!#pOB$2>(GnImD|nOq}DuiUxuvvp53HFui98Q>(VJwhAaB%CV7%O zlNw;MmWTisC!oYq#>u9ULrFWI!IQ1rfS8gBuDfzOl}=37+-za|yS1?M-pLxyFXz{K z#L4Er@U-EiM|4Qn0&4Kp?SFSLgjFVcxFZ?f)z!F}UA%7*Qddx@7pxU2#36t47i)Mi z;?wm{^C{HYv~^Y+_LG$TUu+O@E3l>v3Xb1DOGXLH?1lvS*MX|pcLs($PYHA9IgtOkafV8n|1*B$UMMfsR7`&sheXdMzaL zDUQRYP;>)YY-}vY&gvSHnZ7&d&S7B~dl8FPV+OUGUAZ^0D94*uiuixA%!FVHK&==9 zOoo=vlm|LBSxen$Fyg{zi~$NJTRVKDtW0o><%pN)yiNTmdNfs1(3nERj9k8=!=v_3 zQu@Lo+Dd2IOxp_GTAw@~c`q}?m{o9GtHv@tY1MgFRRiqc*rI3NG-b=X;-nM$2HmEJ zbJEr+8hW4E+NHv!WGN(6Fl`}e>d5`^RS={9ef;1@j zlTD|*_JCU1*G`fO_)7{c_AVsfs-e&^axMri?INkzsmA_Wz zH6zUR(wfK_UXEw{5kqibGmElVyt~>UQ&>e`;a9){eIxEXvwPOV}LSC zav@J$N~>#r$;EzLPn*d5Pq-HjF{32vAlW2pkWOw)Om>{?gqWnGR}XQOQq!Fiii~=t$1N@_R|JM&@1qeJH5? z;^M}JIB8Ge561M*$Q5Br{>0#%pWTeOwq=#65IEN~m;Xi)af0IDE1ak%n{X=y_~lT5 z$*`FuQ;R!?ou`s$wW4^Zh96&`)K%x~7GGDuDUe3*)m0rz0Lr0Qb8C(DB$M>wCg5em zt;RXZbT-M`O=r;}Xq`1B&(H-MNa`SoTrimBXrXDTriRCg#Uu?Dsz*bVp)hc87BTpq zPeAAE5C?9sf=<9VKA!jDx((sVu@f4q9-EkB+K@S&TvkbHkGW%08a(SXCQHH?wEsi zjQR;|k=W_-G1~p`(0=9GuZr$1f5P}zt?Q6Jw!w(!LncEUhKhWwNj^JO#x65;v9{^l z$SGKJowogM-PR|I{jkwJTR)HYH3qyLeH5XCbwW}>C8!?b&V(g=trbQlqpY?jNr+nA zqp1Tj<1?#7;Y$Ic#nC3UrG8tI1Mt_TpSH_9ho`Q-{8TBgdO%=j$`+glE}hMvpW5#p z!&XCtj3l3wkJad}_m3}iK{3)1HL%Zn&r60EaeUHsU?l1veHt$B$F`5(#a7`>v6 zrU=!VtAI!4+11%@*75M*$4%T%Sx1zA=Is)xPUscq>~Xj5*g$FY~AQ~hrqrmS92Su!taLSg}EWr@jQGAZb|7d znpXiH(gHE=LEPzAfJt?Oay@k%_Bw_5Yn?o6Wt)6gy8Zn$_Z&+6=}$!b3v#es!922R zDuQEKXMPls;v*sfy(axG&f2Lx6QiB_+{9_&aTp7_oNa5f3{^cGGMl@wrg*is{h4_v z**?=G=<|YC-;pkpdJoR38atZ}=kb8LvQXj~IY)C`{PHBsrQBVyNC*jWGtO`j^itTt zxVV16Foa(|a31Ln!gH$j+smZgk~aBT{IcZS@^l9{+&p($A|ce0&t@Rk=f>*sg8=@K z9<%@*u>>yZl$LIN3V4NIJivL2bk-_&RKIQ^A2$}+OfZlS}9cQd_{anmVD~I1DKsNWR9NQFAcD)A0-;=&YGMV ziFp3j)tx*aZy2Y$!;LUW-kuS!MYOsaZd_}9SFM-v3;vGkcgtum{2oOld>D-N?VIdp z&Li91;?&%IheZ*OXGczrhi=AbpR&7?-ZHgUL!BzG(_-e?y#e{{smoAktNB&gy!Zcu6AN9XjC&X-?x9Ik>+>Q&c zFY6TNZE~$a_Cub55~8zwDL0w{cReO~d!rJ}X~!tI%@#36%n|Q%T5Rn#qRO^(42n46x*GP>*W;3RB|85waQ{=D{12t_zc>HW1|oL) zHcOmxR3wMHUEZyMPYs#^rsKrP{Z3XHCmE)h_`g_t&u}>Vz5Q262niBFqDRyjEqW)q z8GUr4Btk^*y+o9V&M-tzFnTwmm*}17jL|zm^cL>_+|Rw%v!3;=z4qFBAKN>};TqSA z>$rY%e$Vs!IXN;(a8AEUvT3^C@hFb+Sbhfis$$7q%kqE&#|7MUcbyTyCgH!fx8RbB z*CpK`^|duSV^6MkzN81cSuSW+8X(`=LMh#6dy9!7f!$=Bl|Q+NHd|y%`up_sANTaX zZmxP^ud_OZwP!rv7`u6R z>^7;;HOf_*>;C?~PPG1Kij<7M*a*1{(&Q^VJzR7fYzG1PBVrGlfTY-yyh3y z+8+pq-2Yp|P$Sb{sXq`X^S9Cr!sC&GOU--AOrA4h*fQ*p%gqUF0C6@>*7%py{xsON zn!Y7-$=hoEm2%{#eWMg+IvP$o=Il+y;O+j_a*Yypp5$zL4o1W zTzmeUy*T*01Ou>0x5#dUHMiQ(BTdc-d}A>#hPppV(iv}+G$;;7WglrV*3#~MvwRi8 z#k>}ndxK#x)@2cE=lMVo`%M6BZ<|jMRv2rAbf+G7A5YB`Of}xL1k~)=I7>f*$Hn5} z5V43TF*4@{^1URWHqSe2x}bp5I`=kb*z7i6YnpNoRr*{^daSCw%p%TZsv-Z>GW4BD zmdGhRtBJqAe&j)UN=_-n_vO#x>r|H99b0tH`_KFcN<=>x8d6B4!m>__tEv7Yz-!3* z{_iOmK=>%ZZZTuKM{fvyDCxn3g zIH~DEpPpu*;C6R1nVPzj!%Pcq^;U;fa99D^G>FBuL+1Pt*tVKky-hN@n=KGc_>pLF zQTq@A-s4TxaIzTm_{c!Kw%hh?MeUZa$5*grFG}io$3NGB{qvP6?{CoEsDiJ= z-+d6G5?bQJ0^P{`fHKorE-lH)a*r1OuA3|s_ZO=rTprE(1?3(p3GwtE<1cJsw5Cfz zI%snEdh2~gw_sf*zu zR5qK1{dkUt+%sHtP*BTzTE3CsIOKc4+ArAf4Mj1uJ+E3!H>@_UITGwVUb!+)RV%%K zp_0t|v7$qPLNEhxm;+05qV9C|>+9aQgZ7HgKgSx*dkdiV%Ug~KskIA}-w$E}hz=N= zWi|VawToCyN9!v}ih<7@0rPEh%ft78Q*^(1e|1LRV4M!WhpEn-Qnbj_^LqGn9!wlL zR5FkP;Jwxr-%$66hz=7ANd3I2Yjo9qZpzk=>9m(eh}Sa|910|OVtWW{&2{2-ZTO~= zboOs)!NNzL!J#2H%bTgW@PWc}%E(r|#=ev2)`Di)33Uu-ZTJ}X*^DjxP#r^=9EZNM z%ng8k6#tC(+{NWpUvYtWnTmdjK8r4c7e%#zBFckyPmX&;bi*KV6=G4m$G2rV3B$gY zt?tP&vEAJ$gbOc4HqH4|bK2i9OnW|9rS{x$rFQ#LHYn#pD=R^q4;*155P2pd%JlqU zoTC5=7+0Btwn>Is%n7z#o3z0uz6@~H1%34>@Udi$J)>sLlt)gz;{stfw~25UR!Je% zuTcYa+3%4pYaw$3MOqf6ER6dzY&dKA9yop7u1c9who_JG#(~HA-@LyeJt`)WwiA%^ z9Th_@ZjW}P7`rFu-P=E9++oTHgOv;5#qa7Rn#}a=Wn;GYTsXXeXZno`tbQ{M-3rZ@ zV+W!6Zi#JHpP1lb%qrgJDj!i%6e3QjLM50`tWhq2g-XF+N2Mw~Npdea!yIFARP5)q z(_u-(<(TJA5|uiY+B{@`HtV?Z?82MK`6Fi8mk*z04FFv7iu3zLtY))aeYhO0oJY9# zTO@VzAI{#tKbvp^2mhPvg16PWrG5vSqYR1T69}zkC?qGSs&xz;u(m8vWkj;DgUQgZ z2toa?o*fZjr5JXF{Xb3wz_*tY760uo{@c5dR{G$2aISlDeZ$>)Nd>?BupV}umH*+z zA2=?9ds~0tpqb{@M)qGHQQQXbPsS_gomFGBGg(}6mu^=7!1+tt-RZjXFGJ?P0vvx0 znScGeAu}!c(w{xce{u@<BXaz)I1hS-9xRw`*9fs0A*&2 z8hpvmMSZ3a^t|3r2HM@v(M;^Mh1#{_FP1YKia2eVv`!KpW{>k0`sd}|<1 z^6D%7vLObM(KCXNOe|WsI@Vc(tiMRMVl#c$nA?!$GNw0^)ac$U66>zeE;Ao=4N{R& zjYsYgaUvAtuscRAm2U1{ndB;= z+fN-GXN2ejBO|?r9Y=L+2(#f29JdTS#Uh%7{T~ivUtDaav{?nh=uG)$07M*fQI^jG zuF{0qblXFVQ+*~yCko*ceMJr118W@GoYMKZk}NRPQ?iw0E|-_zK7L=U4PGC?&l@Qe z9eYO|W%Co8(&79HCiu1I5JhQ#;71wUI*;A_ukraVWm zh(MqaT%pbQ4VjhdM!mGIG3jl0?s@ao!i9|jEJws3aUrLAe$U9TpmJ#>+0}<{UE~n< z`x|P77I2Rc{W9)O+uFV$khciZ$3`);qqVl3X5BI=dp|?FwsRb2_ZS&ZTur%*i{8mE z_)?;ZS4S!C#~vHoq?K)%p&Ax9(a8-Ob&0>Zo}}RlS_pya-%}hkbJ2 z*2x*MMeUCPeKH^seOH3HXH2OJQx4YSL<^f+dPD4j#sQh8hzBO}sG?Kfdhl4EvAq&O zrE}E8I`ZlBx-jx%8#EX<{S^y=)4H5UH=kEqhpslXz_i(G#7NC!TI%T1#IVt1&&Ok0 zayv<&N9UyjXKvF#czB1(<1<{uJr=5t5DV{zsZAO7jx7tov}%5>dMjrSPyJRVy&djc zU*jFopy?YI(yxa;K|J?BTZ8 zl(p8I3X_nIk^z8n)N0pQN2}$ko-msegpf8)89%yaRk$c?d!SlB{4p4)1--nUuhCDPq7^gPqkm|z)Y}B;T|W77M7}`h&Gj4>!j1p}Ag$fNA_0Uq==G$?^`z`}9m0L> zH>q@eJ(14lA__W9#;6Ci)OZ?ceOdCc@np$+RQDYny&`v)1@?G5S{=^)IA*X=Jo zhb=2&e_$Irb+?$fYNo4HwfECns3dki`sP;^ERIGB|73nTy-nLN)@#S7MJ4bkhqEOHq^mSQZ@_iXHyYRVO6CWZqNvsqN5(b_Eih zv8S$%oG%`3&Z{jE#LQdbP7R^SwZs+=0mgYWa@eY$11H=$Yp@JB;*yHZdqm0xIBBO6 zYCV8!oL023_(ZSp`TuL(_vVE4rjHJLT4?XJ{>TeF>&L^|?&r#_E~UpeJn#O%$+T%T z`W^nkkMjd;`lg&y?+uthGgh^M7l#Kfe+Dv+N`tUBq19O!`axfumA>t7sBn zcKPOZb9=G36;mzlBYpPy?2`Zbi$vH~`SD?9Nd&MKmAR9C$nlr|Ny^jySLpCr|KCH0 zxvR99(*Ju2=i;MJKTq|=&RA9A%N=RcvVvhT3v^m{h?bVtbbzCyKMxhjOe_zy zB}r6UVl-k4xLqIH*Uytzgh$GM%0Aco@*eYB?OJC3xfn4 zbMVHOjk^fhm0Mi7cfRmivEjYsD*-ap{jojt+wZD|Z?cmRdFEud6H@&3y#3b}1<|?1 zqHTgmbox3=H8DK9qmkN^Ji;jmdN>Deb!>`((n%PnO=JiV`g_rv=-F7;wUl z;|FZ_JRgKU&v&W$xO^-a%AO(Ag4WW`@Z%FKwMbg;F7HnhgloI&P$EfUvT(U!9tv<< z2W@qshkM&`RY6*H0BeX2W%f&=W|@_8d^nQzmx1M?(Polu0JEBDRU)P6=6te)hO@^Y zeU@aIyTCwnkBYIjOFcgqe7GK<`oMNr!~*buh+yT_jI53)n}o$i@w2)%)+2}J)WY4_ zrj((6cPNFplX_zfc>|n|mzqzvp?9*NmGYr=+`8xe^xc8<6?kk4i{ep{ zt|mGrvuhs=l@go2YQy4W7&i-pV!6&%%(TjqX7z?7CX2?Y z&VClZM?6$@brDL&IQ!Cy3-56-GGAr^(}V-~606JKQP{SB;%n>TEL=3=)-8BoAyBjX`F{ z%{!-ynbgsdT0`40`IFk^F6ra8nS*_UGQc=3N|%s#$#i{60Yu`V69@eeWkLyE^R-;G z3eDm~J#x|7d$fyZ{WiHD`E$kg_}w;q?sOw@JbBkb(W25WnJSpyf~C(Ir1OnVotFKc z1)D_NOFo?3q7`&E(7+zS&~ooZ#@516iHBbC;^PVLR3Tw?>gsJ#J+n~VDSeStamG92 zb?4W+-LsrROe~U{xN+He?Ny}nn^VOM#SNwpdbFVO7*mRFDV`2PPD3AIZQ*Zp&Bk`0 zgWqTI(G4@f8b$5Z53Ji~^#OW(i2NYXh+tAIO$3Rp$S-RZ$;^C(9G67wmt5ZnY^ONq z&swQe5OPR0-%gXZ8M?=(dyhM@U9Imyl2AinHjPhUwC>fC%>`&=bj?E|6@p=A6zroAO<+>z;+X

~^n9;F~XYO)c*a% z)>uMSxDqE95Q`!aZh*gLVTx}YNS*EH)6`%-%=c`;w+4xdY)nxMn67N-8vR-jPWB(@5rW9vXMT~?nxG)0uA zw`VYI#x={=AlacI7hLW(S)=|r3Dq0UN^?Z@@Z}LMCEY^@L!7S#Zy3Rc6y$I`Lr_30 zvD(>KESLY6*U{ONw-b&0hMDYsyK=m*>^$?9@|9-vI`nkqZw_!d?k-=eH7eI zhVN_P9X(sRm@nJnPa;JjCrG*GOvI&DLH ze{mZH9zmHPSMN8M9+`@ICgwOmxyu~ssm`ffpCOSLU%Tt{_lJTl1wMX#M1G9ltYfa) z??@RKP3*vw2+X}p?B2H+TV59(m$~OX2q4@sNL7xruV zoK(uytT$L*uHLsii{y@*IvYd0I%4*O=JaVL~|^t*d*)ajr|#BF}+~(qm_imm9^W z<-N)0?LC)VALioQ#>}c)CRaW@=D1!vYX6rr{9lyk4c*O1>%9K>!3kF6tXWQDSEZ8} z_5(70N8SwZ*XI0z^FG!wLApM;Hz48<9BHbZ-W(2JtZ_I(_6hta3+~s^zZi-vB0X%e z?f+ih-SUURFRuIuv3p-zxV?ER|Y$9$s{#r6cBh`o+ z2xm5STiXK1a=GYajIN2`LTY|J$($u(8)3d8>QfP*VZ*|R-V~%zfvU@ z=1oge_4j6coP^1vv(z%y278f_fIoHe#NjK`zTT*D&Mi1U(zWE_Ktb!5Vy+x>oKaAh z4MX=%xyNK$6k!=5*OsS=LK-1QapcEuv!s-lT-6M$E_{;nTcngnxhS>xA>HG(RIT^J z-mx;3g*=s$FMp${d_5zz;OY=jN z>-_*mul(g5dMR~!SA!L-lc2Fc zSO&-;mEXoc#r8H`BvB>U)aF^ZtR;Q1w&AG>qO85IOr!U~Pqb&NFiUUv3Y|=y7*%Xn zvY-a~g^*B7E07c)M}tQK)M|W>SdGegU$8eV_gZctMiz2~s`My&Mei_;i00g&ZC#A{ zetZ5%lS1w6fDZE{wlPL?4U{X~N2SVj{J!zO^zWC}($>?W+-<~YyM^!3@51DJpN_Q9MR7FtDWnuz_4v^C_%#QHcOdBy_2zsNL3a@T#rkciK@w~T%7 z1;d)ym$IZe^;}>!+~QtEVjdP0I%NZ5PF~J~BWXXxf07ox7-^kLNp|sF)}^x%wLE>9 zk4=NF&Lf{=al^Df=RA|{gXZlJ#-T)FS-1iy8`&&_!~Ai^X;km=v0PIT02YLhHS9&th0S} zTsiK-^~cd#BF9j?gQ$sG#W<}ZN2`_<^-ODV{K9uvd)Hc`Hfni`hou1CiC=otk6=1a zhDV#6UV=2+mex6+uQ$88o%g(WQ8c!V4jo-6FBYV)DwUWC0u;&@ec@w#BgCH^#R`ewns1_a5CZdII5GUMw)XVw(`Vc9V zCO4NSvvSh@H%B!C-`Lwr?t(fLj;J!oTEdBZS%gAGXrp9&*x;NcbuMx}#TxMxXvsi* z#r=*zPvC(V$tk@6X^ASK-P33Mse6s}B!GNA96XxQdNw?Ok>Bqf)UM#nbtXrvwH393 z)F!$)N2!?NKYMOi9rw>rvBw84*ri+rsW71l4>-MPat-pjSf6V>Z!9ixje<;fJN@kd z{VSiYMW`qxBn{PQmDp#GsL2t*MeyvieGD=dC2aeS)=?MvDj|HGvzC>e@iRWiVahJn zaUivPs`Z80;sb^?)E_twN(7*Q;cNZy-wNdi2?PI2O8(0+q)CK#;&?6%uie%iUqxZ} zf1}u)u*op|KSieb?WXl&-yb;tLuJMv-o-m3$tWURmhwJjz?y*4q6yeIw-H*x)y;slIrGj!9VK`Z0S>B%|XfHV+S;s5>; zis$+NrQql(G1F8~ru&@3x^5 zp8mo4HbGv08I{Xn!VMP-)s=6=b^fveeSTnlz_8=N|MmfqSF>+(Uf2voPSXUyp92+| z*M@-Zd2ugr;o|iUaf$iuQR%_ASEbV|>LawGDGOS*3)xe;2Zc3;$+m87TqIo~lVvO8 zqcqNdm<2qU@0z(w5AB_fgX3~^?Lpwyro+8~@b^<>kukR1gM*h>$t9GZ&kPeLMME0$ zEWi6}LKm*C!Ir4PVXVq>ba`b6sk!o|9@9@uO$w+_1ak`-`tY097z;KDQ)Bxm1i8`g zBD0yY0g#zEG$d|Wee7FcV(e3TLki{om=n_lFTROM z1pCk!M@FQ@Oyo@*a~JymBnL3r^e0l{%%ukb$s3ANtk#UQY;?R^J3H!Z=3Rxs*^4f5 z*HfMu2KGJK&x13iTh9qKxJg@9K-t*M7}-m6 zv35IQ)GP^%C=759XPs@vVhxY4n@b`|;(kQ#M3PsTXbRt{nP%Svx0(+mv{#V+VE$7& zSz@Aa9pITg)a4G1?g)igtzPq0FGyjzI)11FdP>1-lH#1k%Xs!Nx;4 zUK4O3nA*L%6-fmm>wzVQ8{>XsmKhd}5(%cnDQ77+y3GS7QBm%n*RlYvG24k0A`JN;!TZ)nbkrY0w^y+ueF(8Kn^lx{(V7J$(<+iPgl z5qFt>ssotiE0-oCg_lkqQ8e1`&8 zqxR7xk!tRW%xaS_DuXYcS^~?+qj-eLde5wmlmZpYNmZgFmU?AwOmcXkSn}HxtfXQBUTALsyL9 z#DPCO9t^fjG0YIfH?!X}oXe>1or?k1DIRclg)N!n16#dT*TZ9-rcGo~i*GRb0|Df{ z@k!XX?!6jn6%sf_F7F(1Vo9O=`d#)T*BGwaFk%IFpvO&rp^>i+rZi?(zZ7B|%qsWI z^-(wVJ}%MiR{JZAB(752+H0k8`GL2<>U%=s4eLrFX?8g;Ab2InXQtHspHf03nXjRYDMhzvX zuQzvKN*(Q}*EL0Xw{!Fgk)IRkqVwBp-%eB342^n}yUD2V{AM-iK6cnQDXjLzcZJvH zcsjgH^W%Tc&it>?uj7xxJPg+T^Q%MaXyw`$ftbWKUO$X|+xJy6UMLbmqrzU(rSkrj zJ>X&P-CS?xhfV~jJD0`Rx!48K%iE;t4V#r-%`ek4-NeM0rvXvOuv$>w|V zoZ_oP#~Z^t)^{xKuHDnM{{YTiaHzBCOk+7J>#~65yMqUK47grqjh>5#O+(BoI)t_# zO|3kA#`d;XHK~?Ia*0lZNckCvrs?yTb~8Y@RNLR_Fi)~1J9H)&CAOcBuJd?dePdQ_ zO5MSpvqK^v#_P3_keC_UE$R^x$9;+QU4dIsf*mEXlZW`?X&>j zD#7}BSsV56@v|E4>5Fp}B87CL5TVg-u{;P2iN0Vs9fzW!%VkSH6x5$dN{# zY^+FQC`!v>d=lpv}{(*iPgYSOB=421wfDG6+<`(lO~LFLsIISlYOHtSalPAH>W1XuNXBM!f? zC?zn`WY=7gXJTAv0RWKZbGqQ4qdimOlr>13d>rE*I|(IM>r=O0PZRsTFOY)c$plSkL&vQx0Pu zqs8eG+X0wRFAPAI+PW${R z%)h|Y#^Wwa=^*?#NI1W3kfHHZ%);+J0#|6q@Awtf3~WHM+NXW(B1JIGCN7ctAZ~FI zyJpqOcGLJqjN0}e@ZME^i>a|G zATb&ts(eUf$-+_8 zi7pGfc4Lq+GeF_(_v-DBn(!Bk2R3^MaX1b7mqM{&?rpm5%;AB%ig{P2G%l9VpSA`~ zuRm%T_Oar!zGJh0K%`v={(aAzYVGweQt}WTfSP>YLb1=lLcvb4dR23!8>-To$AidH zoINp&cAtHn*prr+?JjOybM9J5e*ZV16#WflX>PrqfbY%q;Lv!pZ0($zoS4hX-mE%w zzkRLq9R{B^uOB*3cLK+Kq%$kQV&-+2T0P8n%b;^n^jcq#z1g;}TtcmTZyKuBq21F^ z{bHS-#(ASAud6wG=^|7}1sW2l^RdDURx@#*=2d^FE>Obd`r_c|d(uwD$ezag$=p+- z9wv30XmPqd1;=ow2H>iriYs2%>l!4b1qCM=+yNZ%>Bu=ai{GZNO<|{;V0$pL^qdR1 zzT10j^j~_5=HALBrAI>LY-*Of`>t;_f3zb>>i8;#%|V>Efos^W4DHcD}R;MFh-a<(y*asDAA zLPg`X1c-2-NPZ~6ZrG3NfNq`(^ux0M^Ux5h*7yc4R|t-hS~J=IwF8MExwS$5)fLc; zP=o<$*t+@egyGTB^m*TU=>MLFX7oOx{yeeCRF}j6RB<4G1W#P`AbIH=pYCm8MMaTr z{|3+~aA;VDY2IaxfeV|6f8)}3NVdtaexaJETBVFccDx7dm4JP~PaBye@W~YKucdEB z`Oyg@N|6D{qsaRRk5QwV!=n0Uf~wZhn@0IXiGtCo9u82za9)_{=gz;oo;+^qu}!w~ zS`K4+lxXAYw6;%VyWf!T*O@wgb)Zd(<16jl5-}!up#bP-2ZL7havkPXM55AI@@u+{$qFJUq-Dv z$$!VTV13`e)srGDr^DRA=x=T6xPD9@4-PJ{Y7+f-HEDhGr++%IpM;{@GZ?ej&gTjL zDgAi}8I}b17^YQGe-s8LBrvZNK)eN7sh&B0%dloKY4RP>Nz1WwvDc?#^Nc3!i#2=q zWo)lcRbJ7VGA~Q{XW+M}eDnCmI|>G(W!`<=f`$m;3>Vv;_)&|*40^Sm3_p@`H`jcd zcjGppVoUYH?7ON^SWpP)fsTR%9p;r%D2T~igNf0UF?GQuB0ZrE_)G0=E7AUpOZ&;U zr={Z=PV>>iDNacIplHj;>~ts0T!Zm9X5%k@0=Z&8MM)S>f=EMZ(UMh8L^0|L*6j5P zJ#0_8fxH3C`R>!&`2+wavyWqv{QQdB-p5HN)(M+NbKYAArD{^0wf8lNjAZc&l=fpL$RDV6n9M-R56V;=f+P-Hhg;Kbry(LRE2| zg=|cCf$+Bnw65*yQ{7hvjpe2d`kz{;s6p&TCS{YWa-eX@l=orTmb2t@W~NUuI{rm) zlrJ?W0^AO|!*(~Fg5H1UaCg3klzK%^t@~(T57JS51;J06c$|WIbs^&N*3;0skA&+t z0eQx7%?_j{(c=a~o+SVye&TL@UEY+*E>M+y=+xm4oTgMi9fG?UTk z-MmiG2<eP+S&T=&|dO-h^?fC!18qrxgvAQ1Syrt9iY|^s z_U8wKCo?zfqYq^!s(3z-r@VY8*7j~@H$mIco)>oP@T7twls!)6<8yn6m+o7!?%~4K z7_p*EsN`9y%mOmU;7wb}8FmfMK1t_&G@Dn&_T8>`I{5ODIgtK24`uE!Y6x%4283MW z%QJd|(o&<#FP33JXZ?oxM~5Q^`=6A+Nc_}Eq2!HuZB}SR`e%qZ*^lov3fc-b=^IO) z*zBT+h(^dI3|Qr?)${Q1r>;s9$FKo#J^hbblN#7j52QRbA0nkGSMRFn-s$ zj_TF+O(YT~ZUZoN3dNE#4a1r?5_H-m>nEmmBHY}&%EezY0bd!hCAE zNb1IP@`D@ah1JBR}n+;OIBa;b?r^SDO@x%m|TbwrBfYJsGB!>$+6zH=sUG)?^O~ zTkDvqtmYK`Nzisproxq&0i~@|Z534jZzAOQBNcjo;;hH%h%CG0_Nvf)XZ2XR!`G#| z`ODH7(8AOP&{+Rg?b6#ksn&RebvmxZ35D9A%y0(Q@Qbb~vg@sd+@rmlr4t-ST7YxB zsW-}WY;1nykTIFkQ?N`4Q%_gpE!$p-}QgzGSW1q+vFVVEuu44N>H^d%K z{6UzxYnBG^vvg{DHfp@#l%^P?q(=_%F7vc`w*$p{Ki)8>WJu82Hm=_bqXyk~?yVef z^ql9w^GRsDW1RK;C2+As)4ly9!MDn|f0a;;<+`x+far*`+@E86s9MWlukzW%6C-Dh z(85pYMr?ea@WTC3cP~Cd66!hke`S$=ehf)y1(s?MpJp$f=VhZxo@fZwLCQVR4I|9c zX9C+pCN9<4;tyHHzv8DPS};<9bpuymaE=3?+($0=dyAA_9PpbKKVm0_om$3{Dj9I^ zp;;<^p67k*a{$}hD-##uun@+%THdVdCXHOKZYhykp|JZ;_T8e;A$ z(WdyII-?oan9nFxiqW7yaMtTIX$+3qdunX<*q(8@`@!4}^N!&5eRdHW+XEy!DFiAC zGwY#WN-FlNCe_Ms2hA z%9kSOE9L}Na-o8X32K#;bHy40PaI``{BRLRwALYWLn#M6HIptWOCnxt@%9KYlP;h=Y$xdt1wX;$ChdatG$*)vI~e_Yo<=H@5FI z_ot7|lWKdhcNJcB`CYHiY0*aNBTp_Uf8BYDcOHKGzWn5!DE+H#J^V{yS)-hjAj%f` zLTNfC%|>f&`FzxzDkbwh5@83-wnpYl0;)bKj{!t!{naZ|*@{3c`>%k4Rl$x#ZCb5I6jRaY_CM2D<|!U+S8UwaSu}H8Y^% zo(NKqHG+Kqt_1-h)m@8+K_cbw@do#N#S{0MWQ&AEMp59pK|4e@uc*Y6+E78=hBHmy zZCBHJH~pmAqCU;dr8XsQ&HYh9o_0Li8?1~bL)AbCze7Ia4O&UXY?sogR)y{=FS@C* zT~Cv*lV=J>xZ6^5o`%oX)qcXy%LNb+Jrg|B)?nhZl)>6CNf(A2Kc5J6Wjs znorNYL5P$V$|mK61bJZ>TYr*)mYx{QZBrTvIL?6--b7k+8mUN@BG6+)ummqG)dulH z#!P-rcjqiJgeEVoX*l9bOf7mvr$+Yrvyo>I9y`;(;HKbZQt;TxMgLfbQX_}Bt%!Kv z^j1irVg|KmhAYOSf8;hpIMp#tV2BdV_LWW!{PC{ZcnZPzQQ_pdnAY@)+P(7S+S^Db z_JBN-1fkh9gFOS9*)}klqppO8c)99pc2fN-t`FzOInra{x8ePViwqw;-CEa6s z_@lIg-s1J4*;9m=sSim;_Eu$t&E$}9)p}Yc9r9Z)=R^*`E46Fr!?k9{PO8_l9i*jzhYxSPLn=!)1J`aHK+ zBA+&vF31p;y!<~{Cr;%goEG`d)($VcHUGgnndd@#?cy9s}jQMKQ>%bm{v7Q#DypA;Oq_DH6Qa`7NViEtOQK}$T`croiV`U6M z+Z~*w%u>57yH^?OzR+!1f5FzS@?Oq=BQ+{4Nwa_W2pP(mXz?pZ5mb^s0ZBmcPFIe# zG!nlhU~{($6T4RAxS`y6==;`FsZ^N|`oP=XlgvbshC2j+m$CB-2=-=sCL*CXERYb} ztTNaI0s(jewyeHy#bl@D=}KDGox}UAIia~?pOSWM?APt@7)b677I+Mc5D35;9}Ij5 z3b4r68=qg9j+ddyOD*z`m@VLnQvA|2tgV^$uq6m7vC>bY61eKHj>`|@6YWx%TFXXV z>34jGM;X^p>XpHIv!o6kO-sk4xkqu-oJV58v-;?}(rmdw_m2QR1s*}%xacPM}metvFpM306vvubR_+hPx z^7bF}hvuV> zugFDyvfXCE6c>U~R>Xa>fuQ^S+%<~!I6{K_P7K`F>W z)_#1Fpu&>Pbq7q|gj6D$uWgS%Z#v?QXv*>6O zIbOh2qzjCBazrZ*-EISIirQ7kT5zZp*NRs zPq;5-LX0T3<-_oljvnna_{IHbZ{_WdY0AzXhk1BFGZfb8&7lI;aAxV&LsER>W*cHr zzW2&?Jvg{a6+UYcaQ5r*Zue2|(C7_!{m!njIJ`kNF?oNh76g9#REi=ysV^=kt3mwh zq@d%aL6<$vV&nzX!i0Rg#+9NR=lcyteTR)?<|PdV1Z0#SS2N@y*Cw2%DnA7{IFCKY}p)RGFm3Cax)0*MM> zop4Im68@!GuIZjh+U|O;vzhz;M6O)qp$^L8Ff0T068p5id_az#yh!8GxU%Finadvz zcXbe38u-*>sphEt*&F=8$eZEJ8f2((5GcY#fi>b)Z1X=!^w+cKmIAMr2E)G>TJsWJETpf&ML3^e&J+2y|uz&o_u|46NT!JtYj(o0623ommDZaFzGKW zW^(55;75wF{)+U~*K^Ryd@nYUm&X2p5p3VNlz@#Ic4lhCNmx-(bZ4Z~1I}Tq@@Z$M zIr{$}LgKt9%1xl^8!|EGw>9mZrNZxHmYn77Wz&>_&o-lC<@(f}2%nQ`ww^wO(nFrh z+Gtzc6Z+-bo_ls3YK*tU)DFixhqWGh<7r;$i0t?Xx~9)Pa8k6NRlj?Tx*v6vm~(`E zz$ygy0&tvfF;yWMJc1O>^$N_j)mh*hZRs#NlTqFV&k2r&s4yoNTfOiXe5US<90vDg z`jn5ZXMS_s;9j^QSjJ7L-sYDNfhm2elE@!du}UIa1t4L*4aM#FCn{&YxA31PsR(At^1wr3`I@wnMRI6Bn9?v8v=w)2or;YnAkq8pF$Hl<#n zQL+7tbt7*L<_ufqX(EC6plWSokS!4po;bopAa*h!Ztldjn(lM0`@L=*t4H{4EJ6k* zEt_}GYI(Yl4s++qB4r;wi@BJQx=oy{)ASk6=Aq_2&QN(Ar3#@=WnPq3RhLs>@x>sC z;Cv&g$Gi4viYBYIPEmrK;D z??RB1+mfqco8RQq+QHbu8~(;^Dl(qf_IGqGmOF=z(X;@QZaC2^`|b(YOPF{#4z3qC zyj!&P)yZC%a@YIAgv3=VOV(5A6v}b+x~Z5tP9wBJX~HM5qDyL#+QAE*VP4GR36v1s zjE4gu5nz5j{gHF}Qt+DX55Fz5OZQzXHD3{ZLpU8UAbv|jnRPqEz2vcPU9QHMk>Ajs zJl)jd#qQfaWsIyc8WWe(^MxsXC;)os*qP+xsr0^FDHgIYwr5K0*Jx1tiQ_4eRg!qj z?t`aP{SCQvoBT}sJcteofgmsj;3c4lOO$ujMen5*)d!8j8_qlTF3A^pf19@&1NV^GHPLjVJ0=RoQ81p5`2y_4ZrbR?oE7WnckL-4Kjp$Q^1eNK;BJaGzP*ltT)D{OI|tY>e)I^{_65OW)4A`qPCc%#^C z<8(gdLp|aZV`NK$Ol~P}6j}|&19E-Iy!X(5-N^;#!i?T+FE1_UJtZ~U&PkdIn|^Tq z&?p+3*kWZU8Tn4^eGQl|A<0^rV9T2%Wozxy#5Q=03;MhbR=8a|;KDk6ZA0wX&);5$ zcax89F3URP%E)@9k%wgQ5q4A%D_T``&&d?xLKllZrQ@;SAKNcrWDA9!Twxp3c8iI6 zu6HBz5x$5kEF>^u5grw9%gMPpzhWa45N9)o%^mSgP3RBj>5jfMI@r@+BMxI&ti#D7 z>|NU=7>K&bU|UgpAdjrAt|_{d=0472K)6M-?;MWYQ`>N^OoZ8*cvH*5AWr^Rq?*0| z$&R^C&!}O($l4uTAjSF-Qr%0geW?L#I3!|gl`KoES76R(kh6q{rDZLs0N-tU8=z>7X zj6O|FdQ@)I+9N4X6>Car4UH2&&b8cCYn$8z_1HCG#U%A;G3?LUz-&GZptjO0&C&FV zG@tXvZPG_tl|}EpM>K0Gq#(_=S2p3kvNn6$JwiR1yKwt?EM21OLTP1>19ai5IF4)` z1CPzEO|$M=JA?LYO^J|0@2qp*AL>;_Ic1l>7}-+D;^@3}EEv0Fk(nI~jbV=>e7=w-$I1^yK&Gsg8S_#Hre^rHDc@@Dvo!v2x} z$d>{C`Pb+a5tT4fanxAU+2P;YyFUH%pHMxUKjZ%Iv>lGcThEz>e~>fg5<;arhV9&# z=vui6lIu=Kh6CezyALY=fyTgNqG{>+JF{c`)x#)<>!<3IcYpmC6yr_@iKF{rvz2+f zMf@1Nl z@>KJP*jS<6;sXclQoi@n>lQt0Gx9~j+Hf2- zle{_WP1ASQ?721GzIkJU?$t)3LY$Y<`YpdjwGapg0T48*NBep411bz9isM;-pMbw6^t8}K z=d(lUkEZF=vYVo^$K(EigTkdH&%!O)owx`W5N~X}ZJg2zmH@^iIJn=m8qS?MV&;88 z#adbiE6!H`hqAW}YV%+BeyLETrGgeHRva2=ai=&*iUkM`r8qRWYfGUNcPVbcgC+#0 zh2q5$G`JOahtfXzueJ7>eV#e9XP>N-PcrknuCIJ1^^5=?rVK&}f7FSKKCNYd znOr2i2Khxl&J_&d3}sh{<*D-#E}v*2McA$W+5S0YxaCR|oVa#|JFp8AMS-(t& zQ&ofley~4sf*CVi3nYEedG$%_>6}+V`DCYCrxtm#F8%OAlSM^Wqdns7X)&bL5389S z>fY>_U=~vJgM01agL?A9Bz|)}QqpIZ$9?Q$Kr6j-e(0}xWU`-tG75gmcEjzea}lK! zz^~%Vd$?MN=Nq{Y^1|M7J$tev*ZWl1`oLwZUz_rbUNFn7y;5oG9gI3e*3Y5(Dq*I9 z%=6Bz>X^N*LN@1Tpo4rJ@scd-bSH`9gI)c63sod$U;+7d%Q4U1G*>y)uAxUUoJ$+{ zP{@?8S6>At89xiyV`Xw7Vf&N*xe9dFZsr@j)xFh6Zu_U$9zjIEH3N1LdG4H!lo{1B z>;yT~=TZt}a*^jq_W@7346l-O1$xqp7x@}Q=laHyD@ztYJF$wjGxUuH29eayeqj#d zjBK3cbrLpVM!{pr-coXkkXPGK-u+P0fz55{-`mSxPNkEQ4BZMaJ2KfP)z|zy3kT|- z4N^KLG!Nw5Tutc55=gpVCS*R)0>Z;QcewY%0UU>u*}oma%Y;k#RND(6Qd?%}U*FlM zEcP0;4lS`g@F`D>^0|Tx{w}KAqA+_UbecMmU2KZb8$j)RM}x1{FuzM`4Gh!xyskGj zNep#JjaR+fRD>d3K)kw4cw<2Iaz^>W&m{(pcJ_=!hv-{fvwVLEOj*VSavKs|H9Qh1 z368rdDaD@YSSAY^Uieacg0h_+YDkOL2ryAH)GvHUp72P%*tdh8@*4;G&gqu0@n%f*`QeNXHCf38=+6I6R!*@I`wza}c+~W|_Q>@a-K>O>R*-@?q-vlt{Glb$ZZ z9;q}_+1+=52LGyUmE@j$au!RSc(D6HgPGu)`sjBEup3ylz0el~90p@|Uj$lhOG@5n zOXxG*ZoBG7`KB8%2B`%{Q4|4c%?dQs80t?ruFE|L8+p~Ry0%4&bsWshJ!;c%S`sZb zZeD>bho{e&*CoGDU91#Swf_*2ppNFx?*Y5oo3$QUR-#I~SFN&P?>Uug;gN|GD=X*H zL7UQWgs)^#l)+B)XT*w%{SW2X7}olJ_44p*vad2Aaor>Wr=CgPO8Zi-Y{J) z6d}9d>-1q&j!*JBBXF5qF+T@9$&;e8N?=UE+B>}W$zI8ZOR$14zY?W*S(W`bj1ake{^85;E>dN&EnLT-L@1*hKxtLReo?|qd6iw#ad-c0L;zUw! zmqrX-O-PDPEMoX1Jm3zs6VA;V$57Nb$N`Fq-L#NhGftF-{3R#`gip+=VIQxQ0cuQy zjVa+df3zK%hSkZ{ot=TS!>N_Ly|(GF@(~GHa7M*n0trZu5mZFuS@Yl;RiMkb*I)`~ z;qjGQ#iGeqZ50jUigeRC2lm~eLWL&wte9Y;ND{eOG0D~=-ei9T8?51j9V@e}`)bd% zJ0D^68+9Gay{$`(R-45+%OVq{>Nb)e8c|D&{rnPJy>ebUV8<_1G!Sl*Jy!!Hy~C}S zrnwj+$C`fnmmmqOs-cQbvP_3MBk0`Wttjmx6v8_D5k-!o4jA3XC=EYJDZt{9K-Uk- z2UCopaEJN?%vf}vnf0F;^{l?$TYPM}i65H@Y*=MxG&UJ%-duoi)YK8`5|UMyNE@!j z%}kg4@fd9S<0Kf?!R+f*|23w&DfvWw+qfIRvF2Xm!K(?XuTCH@YzdDf9I1UxAj&fM z?EsSL7RP(oN>RKZ_uFdpanhav&bFRZ!!5WY$)|xwIO6@4K<#CdbkWmNS&C!$dBOQT znb?V^uPRl+Zbn}b8OHSy@>9y$Q7Z@}xxXLuzPZX%)~-zNcJ)yiw%XJmDHDk?ubfBc zCKG+%j2V|F>lwgJW*Xq{{(wyW5^SoVT8mb3O>-xoa~zO>a^cEOyWmuEnLadGAvLZ~ zoDEJYWkcW=6?GxDS&fmnle@E9Y-E5l>`%vCPPGAi81(EM>@gjY-%exlPX65cT3!F8 zZox-ySINc4!GjgRvd!BM_#no@%fo!R_`$!hSOFo+-mVTxm#!HGm)AA2U5M1m@1e<^!zpFjd~4n<1?xH6ot zo}5g`{Qjjr7Lph5MsrzaOF`fe2!%; z)8>z#Hy#v8afB8ddZ_O7@tWUFTDR|rgR_#}CCFDMzSrEwvx(r%mm%8Nu-!GOui!{W zSOBGtb?l@>w3a@C?~CE=1f8HN$(!?;JcFZ>g`ByPq?gWkqwYn1{(+U2Fz9)5QsFKM zjD^L>`O#N#@hY>T6CB3ZcW4v{>ZeGo8#nu!*9?LtS7aGh@&a^TMrX}%ptkptAAvSf z->}paJ>hV0G=4fV(N*kK=hJU?`4$$^atvXZMd7Q#MLtw12H&)xG;-Bh{;ByP2%)3i@SD zI!SB=Hh_niCnO0O+j>zx$v%4BM=M*j!9+Lhp5&{b68&P=-2n`iI<^CTFN5o`74DTU zfGde8kv8{Zg)o7|8}xcAC+eZwUMj+TNuL|Qenw>@D z9R&N&iz@(nzk+~e{!}MEeOKlBGp&5pXj6YgvZ$Nl=d%VH< zzr)6&u^^HwM`B)GG_#<+^O5_v zp@e1?l=sTMfk8nN+WI50Y#DvH%!*qx^6Q@Dt@gUlbXM%&QHWy4N$najP9GWn%;iKc zs}w2c!`_K1nkrJaV-Kn2L61<|i5ka)xd%TYT@`k#(9IS=FXmn5b>b7|zXbKgiix3< zcG*vM@%2_ z1@igcb0N*9(_hUk_HVMReC&HC_phqdQE--?(bTDwF=cL-Z3x1^_f4THB$2gEQ;tx& z4h5!{7lFy3J|*eUcflE^3d@HYwo7e*;(8nlq)WZH$^aEiD$L5OO}gA1FpYRwt}`v7 z)CB0=E9^CgdHx0)lBnvFKJA^&nl254s5cZH&X*m`rSDGk49Zu3D2llIC#JjKq(R8TRaCV_i}XJWe<4->Tn=4)6aveX!O*S z9;xk@)Xc3Ru75mzvL@%tyKM2O0lQmK3?T2p6^PvhNCoF)nbJ5+%&nCB0HJtF4m|)1 zv7HHx)v@b64=4FBIMKxUDQu&|Iz1gr2sT_5d?=~W_ zT>JKy;O-twOjVz4omUk_+rd{>nMp;rU+LpX+-DY*P3v6#{hU!H*W)7Tu%T$? zlWZovFC0P6N7UJ)^1&b6NmtX5f^KFTCeiZqD$x07u3H%=$07) zW=bx9zOibZWWu*Or1A}i7YSKg(P{Ur$gNYsI7j;xe0u??ssrcYSL)ViT$JW!dHhRVi%+~t1L^ItQU;Up@6 zEY#68U5_6Bjy=py;E+a3*ejL=Z1nIsUBQ_V9{^|vgg`(ERQ=Vi8ec1xOF#Mu9SZ$q zlG2U94}ZkmVtBWM!hc1Bruns(WD6=D8#MgzxENN`u9-o5W?2GMxp{;77Aq`ooxfB; zfV=Pw6yE2=<}@a4rU&~Xd$A64(uL-|p90;__-Gtl3+rhi!=0#EEf2A$vooQnkH4H> zAD1_BKJD6dsv}glk97ef8m0UA#EyFEKYMhn!}D)+y1G{g0;OBq8E16q(h zcB%v=p=)a}R#tB|C{#DJci?_m`!5GlnIEY>@PhV0EuW_M-=&;){iFTLeA_xJ3CnJ7 zL1r3KR$mE+^FAyk0dE;`Hard~dG7)wcu>fETjOqrn#7(l^ij-%6s!)|XlbwLBb4X= z_pJExiXw0|CO)Y2Y+*zDwV&0kqEpc9_=*O{$ThD|>5w>W_h{CD{EAfatr%B18RJPO z)ThTcCAnnuRd{Y+tVm44&~; zR-LdT0V=DBW`4^?e$q@U;zQ%3qHw-T+q3wHeHeS|SN)Aks3QUx5CNdkfTvi5u}o#nX5bIYZqV#LpwR!dJo%n$LXz-#43OE!GJfG; zzuR+;sQ9ElX(ez1SJ|K?>Wb*$)O%44bmoQ?@aj(^RHu-uT-t#NhDUeP-nUX~Xwt(b zsHXr3QWOr&4m@IBUG<&(iG{&lv{8>BSU3ui*4Rq!atB|bfi6xb_VzwHQNt@yo_pn^ zj{zkSSgdbpQK5>$nw(3X(R<>15=nAw%e?)nN9^;?K;aD;nu`=_9OG9z2WUawCJ81f zX&0F~0e-X+;aAW|Ycz$?0$-%EpNWnZ7H*q3O&C2RigYCYknotA{(jTkQhOy1zvB+z76mI9m2X;T_X#Y16|rVGO?a2Ok^dO!CT1tw~1Rj z<~UI$c4O-=LFdgYE@A4V42!LRNVVC*myBP%QN29oM!`m@V|okkGe7n!lo0(Q?z=_fJz0XP?{9?cGng3z>MLRLhf7%cy44PItL`Mptb@CThVFB)#pIhn) z^EUocr4&LlXrtMC7I2UehQ4mlR)joTM<;9|j;NF|Q1|c;1$Hg>WH34l5?xzcm*~w- z<7CA%zNSJsGp!BwHm!5AGUM|R<)NnXc!y!7cB<**DS_> z!u4KnRT~F^>nzE#x?0ZT-j6{PG zbFyQRK!q#z3yL;|E_2{MYL-|ZmrHz?@WGSJ7^OfDxO@5Nl_|CmX*>~6t6ctD01oAS zuo*Gt(M?sSnbJ92b#+TL%V3PdMjc>usugM5d1p6G-o5oZyqt%SZRtQePFcJ6qzagK z(m9F*+=IGQ?C@(m%kVXcO6Z6^ciH{c4fRMWufo^fz4E;e3qFUO1`MhkHCu|m%D`1P z!sg`gDLcmEBkO|zDTRspi>7&uG*$j|;LaNLwMBseO5=LYb5SYSOh9AaY2?^QI#?>; zu9G$(!cnnR=fv?kItTf=GWRu$m=yQjRB7?`pL(SjWS>T1pdx3;d+mH5pgXKm(!P49 z(;&n`RTmL-tkNDp(PZ?B&P~5u??>lDhZ|k)hP`_evm1$bY)LhN%xndo5NA2I$FGL* z2X3a{awK+ioWCIDzh{(nyTtm3stolf(w0#LbxO7F$@|Nx0>PtL%5A6IKOyW3<&J*| z=DQ+TV-U5HZ%Aq~eWYtXw%Z$%5D{=INIjIvPQ)%u2Qh7?nblp^V?d4VslqfS$#&=r z)x!5x8#OaZ%h3uY=>h?GehQ}v{0aTLM_Tmq7`W$A;rBrKF9c8e4V-_EsWh_go`?dc zr`#U_dF{~vs{J9%OT$xf_UUN_UR6;C(jb~-wZ8;qH@poCSE5Cfvkf~yEUs$%v_5I? z5poW@jED1y18lJS7MYfl85e%b_W_TJg(A8da8tjVb{u=wCNlV4=baoZ*DTQz$ECVs z0rVc#4q*1h`jZTcR$eqt5!q!(uW;z}GD&{S8#L&W&{8v2)j&OOAPi~>Bu$~KFP7I_4tboVK4gz_>j z3)z|_*)+-6?8&XlDh0_3ZpC;1$AT$JxpLkU+c|KM%l=QxRD=YY-KI$oPk7eG6P|xd zZ~SXedj9`0DE$lnk`7%rWx(Khb9U+?7bCcQ^fXI6{knt&IL&~Y9^ zO$E(*FGz|Pp?EuA^miVT-8wQC@Q~oa8@091hlbXrJ z@U+)u2-w)@Q#*0mj#S$;M1gd!p;)Fk`2ppD9Vu|2=4{;0AN{pYtfUp;9O&aVp@(ZS zw;bbkT)GXzv5D?cu!Iameb~0MUN~d{lNk0v! zTU6}q+(P5dkVh*j16tW)w9@q|?VW!S?tNi&33!0yj!YUsAl0ztOmO8etIraLZ;0tf z{e3b;G|nSjZRT;ZFnU@Amei6mrb+_cQ)nZoaOBeL?Pc{*QdYB9JJP^@5{N1%?%US= zm72p!H!~U_=sEt#=^wYa%&pcb%cQaf6Z)pY-7@?74JSm%V%nD}SN6L=4ad|k7vPE=;pWAE?z>dsLs ziCTXNAXQW0!n7cM-5|_{w)n zV}<*M{=F;TG#D*!t*RNS$0bfA`nKHceyh;6OgVvt$=ThX_!!HFvypG8j~v_BlV+&4 zd_{>w#Num=I&|bg{;ZtBktu{5mqq%YfC<&Mg6UDG1RpmQg^u}INlE>x2nYxKyrdmpru@%&|1^Uu$8KXt;= zqB#Vs*qSoqQg7K7e?mq*S^vnxOZ9@z)ntpu)C%uI@N!Eue)&Cpz69GO|499$>uj3t zh|f!Gk53^|{=vIKnfl2gp!&<(uaBQ{CK{;Mq(}5eW(9~jl~(9Ms_=nRoQ3<0vH|K7 zR=;7E{keiF?B%jD*u2jXVZ}mX)DOlp+{slTbxW&sD0+RH-RosNQ*r8@4Wqz3Y?B0_ zNHDHws8tndYzefWH)YSX3}qtqic5;atL8&;<(QM@6m`Hs;O4B7qrAr;kWc3DC)%mt zN=b=Ek6&*B<`9*0rdqhPM!MrTptDylzz%P?FGfa=<0Nb zQp+_CuzXTcN+&+e))}p)mc~RA)GEKEI{Ddae_k9~etrhgq?)@ED90J|YKuy9-Gkeq zqZ~Doe1EWOzo$m0YYYb&b={J#d^BDQsOB4a+h+))UTa-(eGaYd6lXW(pAU9P+=YzK zfK}f+W`$EhTCHp(tdqU#2Fa)Rc5Y<+gX)WTj=?-B2~D^uUoX8TKO2nZa=FG`i669% zMjSvF4fb;@_ChhB{5R#nvVO3|Q&zTBxJbt6rrSvcD zja(z^f1$zsOOE>=BeaxFpMHz<{7GOMk$&yHaw8e;H!4xN@AVj`Ye za^*VRF3hi`S(u280n5|7RD`N>s~_(94BhHn3J@4p-e~0*(r*UeFH6rrN7c-!w*5IP zngYOE$V_~ggTdJ?Yeum+0j@h^a$sHRjG+6Y>M~hXOvU`2*-& z>QGVe`a!Q|DKfUQhKqFQ*G=~BzR{R$TT6vl#+!Rx_B1c&L8htHLQjXDEiyjF_$vmC zJ>(s+TXm zrjRCxgu^U=TEfRQ9%EX(8LdUKq2*y+KUVp&rM`BDTO9^2rDeTK(eXjbm3RGj5LQHU zGdl)z0^|mDs*GX>A8;r1KQ^hmNVJ95?x{SRyhbJ@xA zBBk*VB8@mzQgxzSHFtN%WNFrAhUcEqjg1C<=nPl%XqH2L=_E3|up(LXLNLgYlx}QJ ztC84FF5VS|L|?z9A!Y7iVK=qM(e%{sXZiFQHri$}Sov|`B=mT28g%vu$qkq~a>3@~ z`b|L1aKbE!8oV0EPvh`er%h)-q?E*zs7>yh*r2aQh)}bnsF>8Afl3>6#G#=_HL??R z!PrIjvpKrOXu-L5e8RFDvg{0kSV-Vvq`%*5Q9MbuuseQNw)9jYDE-AIs4PQu&k$Bp zv1L;bY#4g`^|OnKqr6SK0Z&*pN1kgNw)dbu;88KoM?;8dv#22;#R!Xr9^mj~1naBNfVZM9+IFH*5( zO#Ug!4W4sxD;u=mZnndFPsERpg)Sn2F{$v4#5#n`8>plO70sZ`)_rzQfl5qnix9+mA~3aCE$f@9UoT(gyIG|Gc$~@6XnFX1OjK9q5CB#-mUn%Lfh*2QU(gCF#Nr z84l4St99&zXgURA7v4pQh@V4wBLvlq?WKT-1B6LWPi<7KVAtD2@SkpchI^cwx;OnbCQFj)*69xi@G}3 zH_!0eN?>&%pw{G94f~$j-_uO)*BPChW~fgitcF7)^NU*I@jX^cDrrEIQ1+$|3E$y2ydp<@Ngdf1U@;Zujja!!+qZF6a*Y zg+D?>KL=9CEJPMO#wTVnDmtsh^xus6xy|VN z{b-zF&3XGn#RDNHy?s1SCV9Wo@FLW)F8_ToJuC+2<@lZ}VT6Prm_V$X$98tcsUp$u z{F2tR5Zb-D|25(_UzKu}#Pc35!zCoe!|ejxZxu-;2IF0vlk zBPcGEJ2PN_us`;ti*YyF#VHNFSDF3N_(%$^(}o+1A?*`8$b4kqO%93PElT)~HTQU= ze){TU#*wUO2gkqP9Zj{?R!DLmNEqW~Lo!9GqfDR<@uot)TNh?+{ywlXFdVg&d$=Xn*DX1&_s%r4_FIPPTw>*dtnp=1 z{O1acT2Gt2=bHV+$nl##tMTgM+mz(X@(FU^ptl(R66EIrrLqI>3SkSz)U#v})|*w8 zGPgH&6PNq=maJl~s)MVf9NF$BTMQFq9zwMcW6d;Eri16TEBYJK3Yf4L$82-D)cfr1 zUv_);L{{;Af=}I@^KXA+=lm4k`zv8ceMQRjx@M!lN+~I9@?#2&s$Z)K0c(S zH9x=JN2=9w0Y#_O=wBp#&%t5B>o>ZhgW4A zFe6FDF19b?;_eCde)}%=v}|-p4HZ!pZf_h>r0=aWHil3u*wY4NU5DnIjw>aFh}A8>804t>4%Tqu$Bp3!LY?cEhbChhbsx&A>3*b-^8>! zl0FAlS3AdVy;L$(YXp(4RJB@M#FKJ$kMcY4fBPP8vn}r^I{i4lOj|-&QW*|xm8?~?-WYe2IXU|*$4uPk`y#)xtP1OcQ{}j|?vibh658xP`E+id z;^C2rcW$<9RtaF?luS*SHlu3cuhmTmCh%aE)E1lmY|@IGWUS=0_D#n#KDP42*}LS* zqR#4D0YFz0i6(0kyBn4I5djTUWwUV>$TYW%+x3|S9 z6PpU>?OdNX0@Tv)i-23o{hNQ-k~4;pyeWDU!ki>j>{iWnMfLdgc^9u@#t!>w#r8Tm zvpo*E80H+kdmR7TWJ`D_)dJeZ`!r&o<_ZEO(&^;10FB6 zfVfL7pDu!Ae*@+)ETo6ytqV1@F4l!;~r!r0$1K z>z9R_o@Qj1R2%YXGrxLH5engKsa;fuhCQ$%+u-c=ra0zjnAU2~@gy1xinE ztM)fNHc%3Y2xFKjk%;nqaTDDt#VO-5EL)Hx8(+D0E%I?jc8m8Kv-e`RUt@wSZ%iyH z$@p=u;amfcukuU(??g9Y!kuuna_W`(;hWmg;n?sXmSSDMP(Z`>PB-ifD(@dLVB{>V z5^}s5u^3tbjTMuciCi+gNG;;d_A5TANgihqtRlxt1HW07fpy%uA5rqg4MT+M;$jys zT)L?eH%(L3Hu+OW=~Ps-x6x7CzvD9P7LLWADpMh~r%Jo39$+QbXJjO3VpLj#&rv4>t#ZT|4e^lN>0Qn3l z55bbSet&E1l9`hd_I<%2(Yo-~#NfW2q-e^lfS^kd&%V>wO^I;Tmj$&A1DaPI^bXfj zp}|{nH>`|7JV#BG>BvO0PX0~nqu!&yN&`N~5KzA_zHniCjMOhzEeJDyZ$>_o$p{SJG7)kh|iFDwpgqh>78bhqNL2)+do&{)j; z?vlL+bMT`SYN{OjBRb_|8cA?NDOV+pS@OfsXECeIREE*#ba5C;Wa-0ub#biBRBVA4 zw;wIPGQg<|ghm(?{v{|)sIwMH*=Jp1OWQB4DrFXVMs|Sm?(5mOOR<~2ppj{qDg3){ z>Dw0{)}J1&Wg8jUd1lu*L%IF0ai^E}3Wo(bs1&{;lOX>Zp)i zq`uN}#hll>z6kfkc{8Kk7=a9rxwP+3LMCvU@-N|HrDZ%&f>m-?jTJMI1rX#iMZocN zvU9D>S94T_b6?OKg*wQgVMa{;Xe9A|JW51}hOH?iQZp=Pex}wSEInd8hU6>5SrX>rwM`PR_KUY=jV;z<6YToHx5dX z#YD5lzx@$XDF8}1p2CSz*R=nx@Y7?k)j$4aJU!ODRS(c_FuF&cnRt2scWkQcVU;$% zo*7v4$4KLx`E9%Yb;|?3uSOUNt9-tnFVWPevFgfNu*_tZmKVIv$FKLet{-Y3VAv*& zKY$|rfx8I6Jik%dfa87iU8STT6`DrIB1;%4L+U@7kXYHYOaJX&hP!V-10XSUv0=`wblsz8J3CLRQB^eJ!1Sf z)7A1;^S?7RQvV=V33~7RC(GjV4+ZvC+`WJ2R*3(_h<$?QBn@I&7m;`pvyk%o=$x_f za)kW<`b+_W|72qr|7oHo_O8a<%OdNE5euJO#zMcBl~&HB7#bw1y~azbfBWq@7Dfsl8?`TP}R@6E@zEN?to04)-FSf_T%C z4hyO8Qs}zC%C^diTfPi7^3Ut|9ai3BU#XZkt5XV1!RHL|kLf^nUgh@i zII}w#W;(~*;xVcOsN5NQ=#pL=fzZPf6MMrr)$4wnzOS(15|fQUYxE{Fl>XiG9)S@ZnC(cjavnqdnwo z^uW|_&veLRu%#nmQn?H0<0@tRpp}bm`>$WvBOy10sCI(G&*N5;lGUw&-x>J+8*-hq zZ<2fLU2raWNSsax3+FAF@H|SK;+e7IESY{W2M)KjQ5QqJG|6}yEkI{VK}zov zhWSfC*cwJk>Yw#3Gi32&CI)+wT3#t?=9nE>sTO*^SMMXT z)?p1>nLgbehx0Eb?l-*lkHbraZ&*%&>LavZe-j4SIj9)prmP;>)Tz-fMN{Cdy?6poc{7EQ88=!ka`U76U&Z1b(xfd(t3w4PI&KF9mlBli!UqaFU%jNXn2?#Vdq~yr~X*}Ll8Ev$b2k8975W-U3519d~f-S^U2?9nF@em0@&)mNRWHtB`TG+`W zO)5dzJ=DMr&;IYlDzweDNzM`fhF}o*ykbh|;CZLx-N%Z`-m;ezW}8$i6XQE)1~jqn~Z*kjy7=0{yy{m?cYv!sdW=$HpoOm7kKCyv~8>u4OR)l zDgPx_rW45+6#bSDZ1Vu)^o-CXc3h>OhyFoT=S3heQ zM;Czpt}f1{ugO#paXA4U>Z<>zd6>q&sI&^th_LtdI2wx$`u*nWTKdT~V-EiNx6juK zBCiT&RtG2ANJ^vKpabsk^ZR}V2J;jNIV9_hC_h<*=jV5JZds!C;&W-QF1rQK><}mW zIE3uii`tqiErXJi^vW9RJV6D!lue%wt%MJ(+?CS9@%Wcc=edXdI{xH>7*}eqEL6;c zlo{(i9p%7#NGbHl%?|y8V^-PA#ATNxp9v<%s zQ?VT)NCC>``b-M9B)K<(nmm|J$lH?l4N%I^i(TFZ<9>3lC&86chnr?kM=HnPW(m6y zkiW4yAnI?HkR{_8Mp5Np1|b&-zBO;Zi4n&q5T&l};kTM*f5@Evm~AP$-n`rmiZdyn-^Fs34d{-t?8}Uv?N|ox)hMu~9t=_D-=R zckrvx#m$L$6vjrZsc4=fUI$3+(XSsNfX6>>y8Xy&C}wJt3S=}3y#*l170bn2OEwMm zl9#$3B&|H<#5)y)?jrHUEKdXw19*@2Sz{FCiqoCg96S)pAr?Hov+&DbO6E7a)DQ1o z7jrT=J7P})fuM3$9`RaCwzxyftfM-aK1XgX%v6MZW)+GclPU(`C#fG=czi1D9Ga7P zcP?r5{&r}`Nr?!M>z$$sTq+SzWWay+J!UyV2P8nC|9V#5=i7={uK38YBevo}yPvB( zJWkYK(Xlh_+jq#ztisFqk5MbPKU^Nx*ay%$VV@ue$EWhGx&f!~K7Nr0LQQ%}6-*0a zbQab@k6QJR9<7ZoT}^*zKck!DUQSVrMJ6`tGTph-HqJw%2E=izh>9cbCRVNlW*sKHk1G~$yq~X4np%^5xI}nKU`3jMOF&h_t$+|w07#XDQ@ke`W(AhC9bDa< zQ@((SulYh6kJ%C__gb)t-;U!qPmuB=u4-t(q%M##w730jEdIEMwZi-YEXm@kn>rB z%jSBf?-hpf)5BVohB;JVru~i2*psQz@=!q#_v2}+*R+oB7!Bg4+?+MJ^+6BE&3TTy z?d%V;UUhkuPp8!CL}_;tEyaiWAWuxEi#NtHG2&;8~?zze}yoRb{IoMrWnYw4gFBxg55LTiiDDjZWAs zYO-@|G=h1R_-o+V3ukZjJg23!&A zVrTc%GBDNIDNa1Js>HaYtarCL^d1GU&DG3lz#NYmQWwj>?-U&SpN!NW_wwa55Z|0L zg=MK_=$4;{wcoA}$Ao8>nPEmeWD2Wier-1Fnw?+~JuYF|v<(=4EUhE^8j{lUV(2LJ zaV%?>l}o>X5%yQ>NOLkfHM)w)LvUAuUWwtpQ?oIEy3>&dS*bg^$pikSo%l(co@bW8 z3UDX*-mG_Ucpn`{hC1l0c5T|EkD-*VLrx6koJM1;T_~pcb3vr9w_VZW28>bi`-jXg z_xj+40EWqgl;kPgQvYuSb`rL9c&wpp;WVR16)7J(qNy?t_q(*ailMtbFx56O*Qv>I zIOxl&pGa9E#{-+<2Wf=xJW@-pn<90=I<~~b_4JCwLd$c+)fb(1Hnc2-+C-F5n&;%H z8};YlT`kJ}@!Cli9_NA|#iVU3g*PV;$z38^s*wo>dd*NHP5my$kGhIk(+&*Ulp;X?j12$UthyQ|MEVq_rWL5*lws>4s5dj*wU^6w?;DrzgGlg0-j zyE7b}xI zTV21i9&x+rkVgA^T?38|8PX`88e`&pG09CT+j`Vjm6wm}pO_Q3k2L8gd!C@9G!3mD zelU$Ep`ZUrzg!!NE`|zZMJv^^h;x!?=UQeao(J>^^Qo&Nf@zOYip1SIJryorKYSNkkukU&yUiQ2J-}^8BPz5kN`4LWIKSto;A1HFZ1;|50MBS_K+YAP$1I`^K%8b+8z)n)>Fg$X)W7Dn;xhnR{Uu=+FyxyWT-gVucsk4b&IRbG z4?*(*ykdia4qTJ;1EK6^OfA-Gt@FEs)xR&H_YC5Yd1&hEJRTlaMnJ&&`heDR!O2ACVh9k+LSZ`O2~0xd>pclY|xOuKNG>T=pbS6t>-!irA6oaMl^ zj-%7Ofi->0Tl>PxU@9g=(?Ebu&Lfn=TDr^|F0&tFd#G1^_` zh(?*reKmhWaZj9_a=Td-5Cfd)xsi4VkR;<74~j5-Q4yGA#R-}HKkR*HI9zMnHbN2v zi6DB^FlzKJh&H2--r0yc7`;c-=!_P#OZ%@hK^W`gSj)aP=^fG6@OqZ|q3vNIcaRDF0>neuF2ItT(ene+?EMPaM(J z>!Yem0}&g|ut9|^`&Er9gi_^qwBOX-@$dbeUuQ5~@o2Vh7-k)n$0o-6?0t-2sf)8D z^O3rV(OAjMQgJf(bD1LCC;76x-#N{i8j>H~U2!*b-P+9gS!44cYyKZ6`bd2={o+#a z^|ZvV7)62afu=|=E8V=D;y`M;@%%AuFvCs66Bo6z23{E`sYU;b0c@A-l10<84tqgJBpryXx&nD z19L+kpan7#$KTO?|41$0wo;_1r3Z5$5=}}@LSC1xvKC&kd<h zL=&zw>Fb|$ADocIUjx0DMjRCZc;p+5@oL#NgbXIt^{p~Ym6Cg297y8p!V0>;{JXqT zi`lP-Xx9UWmnvQyJFHar{)(Z3u~H$SU%&BVW97RI;k@}MsL3ft2a@k%DU3z;1RrSq z!WveCtFMYz+r<>9m@Da2Xfw?CozkN|X>#XPmBZ{V!C2(5ibwqP6p64{>}JKLplg4T z-E^fKT2SG8iQ#@jx=;EJB}{7fv#dR*NHN#zPTi_PJpvgt4U#zx<9ype1~j@QHnn;<*(-6)!^ruQbt+Km)?co4J0ub4(e z?1D)!Z_(500*2VFqj7F6ch7>9YhHIgpL*>^jJblB$rO`v?vvt^p@E?QI!Cqar4DnG zJ?i<$4WEf(wy>5#JG-`BH~U=C+H0$9dripNL7KU|SQP*#Wmy`^&c=w>O{`UunH23k zshZ-_Dx`eS64`OFDr=C*-A`TGQI&l`A|Z>KHWs`I%^>L6Flf@>7&eM0OKL+j?Sq1J zuwc(ajuqOKr)Uku@2jCTNQl4RlXki=BxpHwXj@oGg*x(8cK5v1BP^}qtrI+^bwF<@ zpHncVx9vvUEQ~J)L?;;EX)o67oj7QFj)eCb9uC>@jbQ`W?*pJ1jt-=>WPVI$apGW! zSEwmfZx2i5Qj+q{6o0tNaN!d}t01e`;+xKLgld#~drM4JE-?g(J zwVl5AY-``=8`CB8I@Zr<{A^$RH9L7Sl>qXh+5HXQ{y>67W!Id$@{{;oC@Z}oidahL z<6Tb|DKeNTr|^#Mk~CRnmP=1Z$F3cXAZq%?s^YN4Wy{5g{EV7ab3oc4j93dxo`{9k z`iVQhBhc(KTsAfoynGNTeu_K_)(_lm(e9_Kv;p zGiJ6uU}zoeOSPuvHnRM%V;2eUD+#3^{vWu7VaeH@dR^qMu26xor4^$S1N=pcwK5LSM!eH=;W&*i_L;6J5z@?%%*^ zc?i&5!Np~wKIMx{b2oqOV`TruIotqsFuOve#(Vlij;oQ3qbxL_k@GtBJ(m(QS7DE% z0SS@}PO@eeHho`>Zq;Y=d8h00qxQ93N;{$U9nTNZZUL6b3JH)&XXb_Nb|*XP2Ko>1 zO(p+n>G@nd5E-f)=6%|qB}WO1u7O;ZRmqkCML10w&P1jtbp%q2QwCkm+rr^&meW)S zKx5L7R?i?rF5eGVSVMzloQ}vK4GiKnKm}a$UXy}iHGDEmZq8U62;aUoGGgks+Z>VY zi!H^+L9`u2U=vjG&ay-G>Egx1)FicvwFe^4la#b~S>tR<_$pzfTqoQbY$HXd$Zjo- zZ#Jw3QiH-8Ixa#Gx`%dAm8_iQ6W#E_Nv%fz8~i6NTqR%NF78>?t9nradvzZ_gcgae z3ooeAu{iELZ`24SypJcDISSTAh-$V^d`QZ0)881>deafPPhyDRNCVG9miQZ62MB}> z{E_iw2*GcHj~jxBy-&v$r|Li^$8IN#7nz#hru-g2Y~c+Do`?LsdA9YkorZME?wXdR z)9a<{xd?#QQmvS@ICNBp?dxWF_#7{{`{RoY`9xlJ=bhFEAUhdKca`uoro0cKkD5g= zR^KF?GURg(3FN(kxe0OV7jg(5K7G}>cMi-rQK?C*`!IX-d<5R0)3jAsC_FzAd@+c9 zXUy(YmA9yx`mJ8s^|b!iYWQ@P?_ISIM$8mp2K2~DIlgy;ns&M$T2cvhKC0u=lfUrV z8PKSz)cFZ&8!B}#nI3b@jHonbueY<;$+TA)b5UMMtPpT{_v|^6^N6DbL~RZrEbdwc z=U0}|MF&SlFncrYmYQh$Z#H^xwi&qX$X-)GA-jD^X`ZlBA=_vJ9eN%oKc%1Qd?Ub^1Sre7DNF`eSfaMm5K-!IDO>KU)=d&vA zjIpey`!4fJ6;0ufmo??gYwpD4dOb%F<1!0VQ^Jk%D0;0`KeKP7Ovu8La?f=WFO0*p zers&~6Y<3RBY{R^D}VinnP&Cl71DNk9PBwL!gFd>I0Gu8&*dwRO~r7|<8qKppejatqdTXkx*;{X<- z7UA)@11Zoeu>De-kDWmd)6_3;sgKx#3$#(*fm(1!D_R=p;Ca!-@$9qW*&1+OIq=|k z!rnrCE1%CZGP*F930n%a%O=JVH+sY5{YoB;z9>qy@U}PZ8Uo7q1Y=9>7vyG*AF&`W_qZ80HJk{+ptT9TrluV-vFv?LChE?a<74BrkG0 z{9$~4DEvd|y?epycgEvG$#Q6csmPn&>bp%oRk$XH2r}sr;XzrbPtj z^valG#+sGLb>BsgH4KN-_X;kIl;Ro4gQRKAeAWYt5(;zyalsy+t9l%nzk&1=y;GBn zxP?>sx>Jl+0|hOjKR()9!o*izd@%b2xDOf*g|uuRE@VQ@htEizZ9J}*6cXGNHSLd{OpaH6Wz{6r#1)t(n&krj70 zwrKeicRbXH#SqU-pHWV-Dl`CzhyYI<-fl+Z?dFb7Wwf=H!%S_Jz{ztU{M=CNP>XRp zom}Bl+&hkhNA6)v8IK=X^uTfh>NXCTDf*_G5JVSj2oyxS9e(*)DM)D`q$E;@-=(8m@Eg|_l{6sQNjGJrg#pvbR>OpGevqx^3*vZp&O)(2#@->-Kx$8}^>*6v%&%@5L8^ z`YZm<%X(v^X`O*b|4%v7$tVjnJZ(aj`mTh57lD-({W*O5(Xow8Ym_@zgETe9{QK45 zriY|k0~9F)%=grk6WFLC>9;e?m;y0Cc*%*ec#)a2s<__bqM=w7J%^TF}A3#%u5va zQR8A!%eXaS!P{&n2UoaD42(f-J+&m&@ZIibWc^ad&qKca;bbjMbB0EXbqHlxSq>1=TtT(K@;)IA|nqp+SpLl z0XmR-dDR^hLC!|5KvzgiXhSfS?C8FE@ef%IzZ-PJ+MVqz<%52H_@@E&%Idwo!XbK> zc{B^Q2cbC~bi0tLtrwG!>KCv#n(}RB-`DR%sVF!~H1s3{6aI=Zg}*f2LpZyzo3fa! zf)pae*9fjQbM(T_13={f7^V8ygnnZ{;7~c(kJb+)!rtIBzX4kt*o|0{wj(U;<}^v8)im6? z%=u}_ttV^*cO-uvm1Y%E!CW-r5>q-~7}KP>nUF2Q-#Q7|oZnE!ZTrGp$z?L9BQVw& zM>$HT#EEYgpW!ziV$01W&}~TcdAYEVH6~ORqvBC4o3R!9{ECF}mTj=fw+jNl?OLO9 zt#+d#*co!#=0*Y4y*_?#b7zj=8Yq>co)|_O)H(F9=oF={2BwM`hAa9HAisf!3EQdb z3Tj!qaFR$?A7Bo?7ZDlaX-U-krD;2c5zy>zBK+dzQ)3#(#gb_ntzmA-31zYzW%<@| zy1Lj|ZaAisIUdLlq(emORmn`-s>a9vJz~FzCR89p-HwJv&~z$}yt)mwHVE0>bq3%_ zmEuD_By7ifQ()ieMcYNW^G@0pS1dv(`%5TA<+COqCoMMBEkytFL8r^ujzZG`2fNru zikO{j0%lt%&$^PdrdvGD}l33qTzk zASp{|126T>Bcz;LCM%!bCVfAhmB2vLy_!~+QnL0sIWd0SXkJM*^JbHzWYYpwBy4Pu z_;qIS8%9{vN@%)BTSh&5rklB4svlts0k>bF+2wlOBhJVv)jB z?WzPEC6C=tI0{kV`8I8F0v9#)?+I);BO~btBS6E?L*4_N#B=`iTzTxATa|0Li%Cg4 zwECr$qyqj28xa&O2iKZCcUV+GGZ)v>>9qpTC}K!!!(p=L-Fb5pQsN=v^-rmH*JX$+ z2M6i2rw+!H(EGEo?j~c6$+@CMqbAiXUWZlqfM&UiOpp}SWPMXs!5uc1SzjG>jh3oS zThUShj#1cBnZQ_Sg6%}g#k|4#knFo?1g#jR8Zr()N(@X^m?ylrCQdYwG1Y83^QEZ( zbhxA-6t&%sq73^w`pFc>v$<4N#kZ#4+jy;6u92AVLk0H>ODRU$DLDnI^!C*o{Glq4 zLoLFnrRpfBUa`UR9WwubjO2+$O%Kjo$-TNz4vb>O!M;wOup604qTKvx{O&bmlh{~mgo zr>Z&ALuz5|IV+|COIG-Y?gEDo7q|r%JR-*7Sxu3X5$rFw=-E%>SCu~8tV-zsFG_$a zy$bGtIk{m5<6kmTzRyGnKvdvPqVmp-CbPC_*pF+84SXF*z|x$RQV*rEA7_h~6lUac z@|O)o!fs*S{~=5L_tAgFfn`@-0=u7nVk`(=%kgS2tSq4^8VXXg5-<7r)o&DYuSfq$ zLmSnio8d@vblsQkwA|?COnSCEy~$WfnHZ|TuDgN5lk5yC5q2_lj=%xMK??IPc36vp zf7XG~y6#K#j|HM5%^#Iu;yaVRaakBz@marXDnIldFS&RsiX}oUquK9GWh}!>#p0p3 z>KB*d&x-pXFl)u~R(bjMs4Kr+tiq6^-?ff|$NUwVu0G-basQ|nyO;Sr4tkc$n8-wr zc!cg(e=EN_r{kiK+Vpk2$Oe~`j^&TSwEuoWU>S0+*fU>ou^uaQb1W;7I(k0wc>Puz zwbJ5rXE_>2tpCk)SOt5A=1;}UVg?<`sr^?aq;kc6DB`|&wU3O?40%fCuP_w21(xyr zT~S(kN3vk?f4EF)5hiB#YnC<^M;YAl5#Pu=<-FnMY&~PEOiqUhopfG--+sji#a#O9 zc^-JCo4clG7ZrLkgx1ABeviM97-!ldawAX(v7!=sRp;i%zAwj98ed9JZ(VmXi(Y2c z0Ee#7?XBiCUFL0NAK_nC;-8g%==8UBImSd#8rMW0nzO{cIZ|>Unk)g z-bAZ^rB3{}PZLHdz1Z&(*}vT=NjGfBV0X^A_h@X0nV{DIH4*e6CkykxoX&3&;eSlW zxhG@EU!s>L3U^*JrsJWPWI-mn0_$afGt7gGy1~Vbs$VfwVTi7=^5x`ve zq2UPtAZd0Mnc-NkHHDU9fOljlfe!4GY*XLZvs8Fk+Qo2}Q3hP_T2-F=*~3lolKVOH zs2&cuLqgY>V6pR0`ZV`B3X>M}`43jUunua2wsZq;(iJl6KY@{+9k#$B^hmy*gYyIt>#u3V!( z(r5+Ihqe)ICMdTb#il>(l@%4ihmzk13_Wg0&}23c$g+B0th#t&@3m9Dp+i_^$T$ff=ic}{b^DZri!saKo6h4^yaQ{*) zT6I@hwMB13YT{97ZfUvc`)69*A@Y-@VUw|E+yE4DMY$JEjmv%T+xMjno`>8D4^F4F zRgHV;s=5!BRuqg}<|6Xkxpm)9)mL&!XSk+wP9y0=xYpxo;~O}8N#n^nC0D6SvRRi* z2|*zZwfDt7)X;MvW9xc6qC*%7kW~5R~*o8*!*&V@i%vRP3iOUg@sbtf7n- z&A?5qm!)hKYB7&D1uJ1kkdYv6q0#@8roeflJ{LY2yG0Fy&~g@Y z>V0O-&FW@)v*00K;v{QqCf7JLusds6W1M#VSuO?NxA)uD7eq?BYw5J1eE83coEQlr z0m>~J4f6Y!VnJ{wY%#iI97lUvYG&C(RW$5ipyLd!D)X=~sNB>?JqG*QFNCt*Tu>f$ z&hQGrD(S|WMW;Guh#5X{uGg+Wa#N`l7Zu*V8OQ!UImluQsL1FE`pRii7I_iH>lT2F zd4-}3S5j^@$&IQupQaA1C=_0Cb#8@> zy{IMw+GabDF!O)_<%hWdC10O!_m-9%+ROwc!nA8 zWuCNINCguUomny6#*l>&DQOlOK8I^&`@U@{L${MY5i&8lpxn`R4ywuLK_Y?dU}R~U}8K^@2PeiFWR3M!=VXUZ*A7I=p72{bPV z7YIu?o7+|C7ezB!#B@G^wfxu>%Ymz<=@&b}U2i{Wi`O1sXx>_Ss@icXe(v2D`KA;) ztb%Y%bxYcR*aV|^5c9c3w|Q(8B5jDQ#$Mg7o^o_z+Jx65%**TF$a%Bsk|i41E6m4! zudkT*k&Rj^n{SQ!$P%?+2?r?gK4B7MY$;5}@<4vz}h zYJGbx6BkL};U1^h&H@y%K`bhX`W!{PC%$WB_gscppRjZ)l{AUe@tA2#{7!n^>%z8g zK&%~tP-@{%F zj%?wxTF!5`^*#K4;L>E|=n~(ANj5=?&tqu&6}|tClCz)fekd4I#u{mg>@%YS;pImlyKd5kEi)`HiFkN1!NV#FO4HrR;7uLflXOm0@G%XdCS)?dg+wvA>mM2#8rj}9`^_D%8Nwhb=fC~<_^L)RE7nD(Qjq3rA6DRU-JJG5B>K{^EMUz*LJS_ zUorAP;Ldy@MN~uRor1&MAm00*Bk#=o%&%LGE2B5d<9s^!X^1$#uy}X?0HX7S`P)2@ zkp4-9=A3~U|;Z^O0Dc`Xe5e2;OW@It{6*F zaONhV|1RMqR^WaIu`0Ab2Z1>)+E_E+8ak540wrJS&z4}tMK|#FVp9LJ=uZsP;q~=* ziJ&laphs3(#F(D&T0lZfNv@BWQLjht)$ z@Nbk1xVrj?)?~$$l0h|!p8DPzI4(7zRaUKMZpDKf4$tygUfQiOjQ#@M1+Vds3<_>9 z`8OzP=JhPnl?Nt7yJSLj8zM6_9FvpTm%yjGMw@5=oZmsW1LpQ^s+428WJg0uX7bpz zmSQU3UeVg;Da5=(S|1Z=9Y8EiOJ|3uNG}4Ol!01X>x&9rEE$*6j0(+}{3x%ewwIry zGdw>`9>sI?G?Xo|H-F@42i2H^;tztZ%|Rd_P#-{R#!Ap!v6(Ymb)nl5*E)&fcP-iq z_qk{~Th8EdNUnBxYL8@{yB2S09%CTM2# zz_GG=Ld7;LikQnVnXA~+FSC-pb}7|om){${2Xb;fgj$YY&gxv@wzh$(xY#_V9SP_31X(Ym;s7HP0Z+`*nJkAtZ^gaa3H_%y-r(8N^r9 zDhTHy=y$^a!6Q8a#CImwTKC!M{t}BumslZ!Y=ac5|nhE0yp#pjQYo% z{EV>?Q_|p~40UBh5R(KuLn2fGgk-4q+zspVIJTHuIT&CdNJ`SIn6*^k@R!s8EAxA- zEQjZYr#y>$EGjCnwE)@c?v0KKr@D8e&Gf^*N|E95jl^MtV6A+4-5Ts5z9ub$=|Q0Q zlrMW2^$%>DZKV17lsB#B>stB7J%15TyE%z)E(b+u|FS=#o-S`a&;aD8h)YZSWKcYo zZDN1yX!G*A>+J^RmskBLC48alfT~!x;^}IHdD2&J8hA^|I5T5oEn_!XLFVJcH8Fo% zf$yT>0LI42Si2J`{G`OEb08%GR zERw{z>Ec$@JpBYsX07#p_}uV`-1O!5y`yN|z$k4E% zWlgSlG1+iTJrQ!#O5zGD$^);X{xAv>m2*Rb<`$BRL(bw2w>Pea4Th_Y~)g@x7Q~RNMeCp-Wq7`-eRyKG=Q0yOUI^ zC<1ybx%!d%Kgg~B4Ca3!!v62<7oPF|8oKYILw62$|DOfRK$E^kPo)5+nD=On?~SJ~ zxch$BPXK`CXnHS{yntfeo+Lj`4t|$Opbm8~@Abs@l8IgAYecs)e566S#JgsT-|Q0F z;9z#g{t>xR|3lYj(eSue5KhM72OsK6OwAxia>+3XT zyiCApR>dj?^$2@5-6e9^JUrf+uC&!Up5EI@^T^aVdMSPt=T_+8QqH@@U zc-2QYc;-{YH8akoA4(xjxWw_Z5j=cB5(n1Kl+r2Ql-?e!W-P!tmmvTT{G57063RhO z4?q`_!C3>7LV|#jQd;|v&H6>{7W0bbhH=Flqp0DQsw>JVtcgcyY|v)qoM^}v#?YKW z(!-+U%%gE8><#Gpq$%gHzc{+Zqu>IzWXh;mGs`8KemWX9j&K~*zt7c_0>c8sNjVZj z0+UK|#LcF3P7MpX78GPfW4X8%CLq>L3#_`%%1#Y%PLPZN=qz^4fFvt>Ba_gk?BL7F ztmRDSYnM6}WkhKAM=tez-s8s!P9D$W1FwlHmr-}#GLcwyKTbU2dm|S!UFYo?9&EcE zd8k%coz7;jY$V2{D3kKxZ5{EMYG8iop#dRpGBZ$pHR!%%S|~F|d-3M5aMSwD$JQFR zu?;AyQ9|1pEkRdd_%!QL?wS9dL}UCMeZ|qCBa>5~5K&)|o_X~HG2R_i4rvtDQMR8z%n3BV5AAafDy!>iCc)TT_X8pCnCA$hCD1 zjc!&gY^$;tszezME31XJ^93Hg#wX@;6jFE`h!YOxgksGGe$EPAv#q_DG7A<*#B~6-89f4MBe8pzI}=YY=L-#-5SaMKSFXO*@#^lob@I?z36fF zl2*AMnS3Uf>X^!~#E9!2T3IZkL&BTQIFYcK@$>DWl$@?;*e-MX*WUE&>xD=b;#V=u%F^)$mKY&z0uGeemRQ&SyyjBii$k^1e=Y-4RrFz(T zn{t0dpG1M)kQ{2A~T~IBml{x6DH7owyf1x9PicK}cdIbmvgYEw=KrVAYx{ zD{xU>2)Yvo!UCaRJNNU;{XAxtxUA^D02W$rM}JeJQl)8rABm8!Fn$DJ}7~I#W4-eY-rhgorR{tjL83F&3er^4y z@Q(QP)chRQ7kg!<49LDAPJarjPM16xJ5L|INgq8S^y^QpESBHnC^zNy9Uf8<5&q_V zy$Gp355Q=u89;POPB~7XDn4bTql-m3x4V_%QX>6{L%g(G?QM5NN?qDEml3MAGl=br zG-)FZCCzFMq=wz1Zu>Nih2STb$dU(d2`g!8DO@ZXF}{I^i05o4V=^c)=&huZb`sNv z+;S#QAR7yD<~HTc9M88#Cfxc8vfxL%tichq$Kl+Fq=NQY9q(Cyuis& zts{oJOG8Mm_INaXJ8e>zfW`CGg`;iwQ%hmuRFoEsY(Cxv^WIU#_p9}iDQ#Rm{%=%} zoJyae1&B)4>EiYsLlWZzdcu~P{Y9ln??!N4u95ocYH<)zmVxSZwKcP<&%p2tZyz)L z*2$^@+a*TJ#||6}4?=6cQpDW@F+Jl?pl7skHP>~H8J?#GtKy!QxJW@a*j9%j1z06{g~SPakr0 zubRG0`F51I@}hmMaJFG#Q+!iyUjJPo$DpjP2_cy@J}zT(3>?TTLPu+F1pomn4xTKy zukF5qpH9rh2}E%2XdXbgCuh!8wkId4_L+Vd)*4%Wt6S%ZX^ogKWdEf9esx;Mjz?8w z$K?CWhqPj*^48Q<&5@}yCjCM^21ELnjqT1Vy_~$%%m{cg|HEWX%cMh%F&E&DfL&{& z$947vvxK6$V{PEe#`zgl$6u({(S?PRx|7IV4Vz?vXq9)cFQ>wzrD7I-QoBP z2K;;aKClTVv0{f$q<0r5@H8L1_nx+pw@MaF8C+C!>TOFdXSM;dZIBZ83V!Rb<&Vynq9X^y^24fcRjVUwTB>t21( z_l2+J%WrbABjIDb;RtN`e8hcz8ZyFS$C*ItL?BV+NvbapjL`AGx z+evqk66@x#qt(!VrXw~Y?7v7Z+eMd#SGFlX^G547yHOIZPS)2+k!` zSL_Z7PoR!Wja0H;_&CZY`0eIKdD5NjyFj`?cYc@FWUipTCWwQRK{yty+3JCBk;zJ( z8LgdJEx6n=(EP5=Dvm^=hEm84)S`sNm=;j zPv3?AGJXHIoSpmQypP$1$B~?q4?lgTIPfc%_9}eJq5iHQH^2LFFlvv zA}>B@?qe`>0VpJC2CoaV@005YS;X_qO=$>-)xdkK%$p2C)%_yC$bS7r&FEsWv*5AC z$I+{pjcEYYFLk%}rT70N|B{M5=R|KUPyb}&K$`zf`zSCdf?i*h%@bA8e2?qZQ_4pe>`5Pa2aLWhE{gV%b)y{c+R#zj)M)RD#7+QaSVb9bd z;mP3%3)qeXq!w{)_ex0ay^g?S;cTfaWTCG|vzoVj;9q_lqx3H;h}i>^0e9B>c6)3J zs;x`(Vos&KtVuTCaV8cD8(4`Km-2nx9eDKDZ~afx1C#lx(L~~|)w!PC(rpT~>O81w zq$id9&reim`}Yu-Y%BMdQhsCPaDSWJ>YySUO=@f}_VL^;S*d=9iQu0U?d>`VGGn14 zzK9{ZW0vyy)*0XI-%AP5!j6O`{q4Pb^Y71q{A4`wn#7Dpi$?q>+K!itzbTfGG6R;r zsot9B{z3TS{q2eGFTk*J#@%nZKYl-vJ8zC8T+ecu{{B||$4?2Hj~;bouP4`|n#Z@dl$K-Wg&wFV0QTFkkb!lt~y6@)8I5zEAP2+`wNW zGRSb7Pq#<66~i>kXKOzfuW0O~-`&8PD6ee9 zPxP4Tw^}+-L0cXLujvRmfRaQQ@7dKjJ4-P%#IQ$XXv<%)gKcd+(RKt=WpmmcSB_Q= zBZ*FG5WWmeHbz%vxUX|4oSh(-T?8;Vs-yS5PqZ+78F4aeAglsBP?20RA{gRJ=Ng7L zY@Pm$;uBP$X=o>Aj0cypLODfF963Ug#Yx&jG82ZRLD11k%9t|SgH$(1(br`e(1KDu zd8CT?an*&l?v21vR}pG{rD)t_W91xsmKAoB|M-buvg7?Y=H-J<(sqEkx2cUlU|>=O zObCn3Alj}V5$M7u*eF==!m(o%U35?3>i6~wb0M;j z6)UrlZj&`QQ2c;J->+GG(&pOU)OVDOxWOQ!>@z5dVJ~?_p)Xl*vd?DMWd=Vs}A^VNng9;yjCvj~ZtT9RmXJN*$AlwY*x zVN@FPo~Py)CC$|ua#l;PJ5oXUyZwNLVEsV>9MTv-?DzB5rpak8p@pfq&?m3gr5R50 zs%BW82B0N98kQOo1&dmbml&3K3ZEw|b`xT9R^SwPU~X5li5R?Cho!n}>)K{zIEOHD z7^p~kopB-VHt!iCX%t6;7Hptb0`IrKC_t>p+^M%=FsY8X33(v#NP-IQ#9XoXX!$gdh zEzg|dEb!@z68q#wV@gc_{lmG&+3=CWlKlQ%*i?%LXFl_2N=61W=)0k^?u8*^K9B9# zDvMnbUJdaK4ndH&fVX?)V<$uR!yQvuxg79l#W5&jCS|1Fl7?r-$Npuj#~ab@#bG1- z)P5Nk;RIUctvm!WnvSWkp>V^+7%by@00Ve8IrS4xDf_z;0@Ut>QD^z@lR;dj>Xmkz z*{4#{bg5{T`V;Re`aR>&rF?151aD)p1q}k&7y;^wUS&fs3PVy#8m>={dm1F`GKMPo zTP1(Qn3nrw_m+Gi+y1)0;=x=uKSFypCcK^v){ z&b53^pBQ~(l*{|e_Utb}+y9Eh{cA0c9J=b92D@{>>ShcR+^L~)B!}~)|g7n*C;Z0 z`ophY3Ml1@-hCC8TcGz@oy791nLjU~msbIQNDY8=29CH}47!2Kk6WG4TRQBdd;C~| zu`#bRBbXk{U%i?I<&O;4wPh^1l`XfyV4(5~}Q|3n83%ffN?oQ?iPq8!^)gKm~ zv}h8ADVO9P2{u%_L(Kjt)g|6D>2T?+AAT!#K!UB2++Mka+KG4xRTWS2>L32ymf`mB zsdjb=)Hby`+P^M%>(cwx@7Uop?PkZ=J(C%pn5KoUjh!#(l8@icqr&Z4&C;Tckb*44 zbUf^ab2Ne#z_Ii%xBo z#s$tewe+_T{?EvyiP1Vk0HFg=!1j|4{@1R87Ziy1+|Tf#y}ho z{2Zt3eC?P)N{?okLYxsHxz!YRMyx6Bo$mCZHyfn}3g!w}a zcTvV=xDgi_%aUSbj|#Jmc>}#&{H{TFq_~$vO=Z(i+a=PiXwlQX^rFh(Eu4n-=m-07 zg!R)rvZTc-2cvV%69$9r!RU?s$b_&3JJH~9m%ux`nBp6DKw5Xh19qi#YpUx6ewk)1YcE($$A?X+w7B&kA^+T-s+D581Py9hRlk= z*XF~g#rdYXZbokaeG7;0hW}{kfPHrQXwT_G0$Qe~gW6)}FBp#f z|AgU;p)s6JiUl+sYD2guq9`&>8}Rk^f4`=H%ObonJ|DP8V>k;j9@|zY{O3O#?V!Te z*bnhX9f1i?vs(W_nnv+^# zx5TaCisK^WIF|3=%jL(XoStYyoY!a#t&eCaasyM%=WKY9=+KJ4^vJryRDhqH(#5)a zF)DOm+%rlJk%#B%tcP6~7#t)4RhoI6(p?AAlW;o`Tpc&4ij|urTd4fD!QfuLPV$w4 zu=K-+qo%-cL9^&m!iU+w%~;o9UBjp)lk+z=Vker025V{6QBL6W8oB1XPJ8u3hYGPZ z#lHCWol6Tb2%l4fBkxL{hFAzZc&nSP z1(SJmgZ)S&jdIuVg4sQLhJj{!hefkLfJBH%-g_sDkdMkmW?*nJ$x0FXsZ6{)4|q%d zy8UFExGnjHtJ)|R#aXYQ?_;wvZL(+ zmRP>}qCPDETDNT=OvuA3W695K`!%O1c@JX)!_G%kJH5?;Vy7DnzTH zz12uy@UK$#(2-J#mDjY@V5D=TvyRNNDy959+NRk?k??8^)<-C|>WxV;!qso)~xnK#0k%*iPBP_Ud$M?4PORa-@@ z_2j5$Qk=?A@@Hu0X9cKyZg}y^qz+kTvx1%MJ#Egh#oUe11~@jqmUa^@o&t4{oC%K$ zgkxso@-q=OymTgY-L^5xrSge>3Sz+gT-Lu2zk=J>o>c<~CVkV)LQU<$EYEU)Wug6+8i{Bw%V8SRp_xd}&Ch zg4WsD*{{smwv>bQ$9=m73EJT)e*hus8ZdD|I0Y9>nqU9nXk^+w=zlJJ_P*jl=~_}q zEFrP18s)mCg-0bGe&^OP=tibu#H*a zPH)3KA!;m-Ko^w*kAzsDLgW39m6H=rl8r*9enZBAf%73 zX`MKJpLfPtI4d}*5}@Pv@{M{;fqv1|&^OvNd(z&HvF~ga2a9?t2V*PIi8d3CFEgCE zhupW637MN6pNWDuY&qkw0w~z#D>h4_S6vB(&ppp5S(}1LcXfEMLfe4AW>&miJZF_0^6> z(GbWRP=hjzg7U#Z3E3ONY6)Kze~6c%bm3la-5K4fZ3r~1Q0rg0$x0_A>yhmaz$j({ zkB`UQlb-a3aiL;TS681t^<|&)0;bihSAi@>?_FOOE65;*nXeuU#y2Onjx?+b9cjJ# z7CY!%@kK<0+I2@Wbjv8U#l!yaGqW~J=aR4g0pHi3NR*)1(&=hnN)~2oFu-oPNmq+Y z4#8x;6x%W%l+v*2)CHDSSLI8ueD3}Y>E#h)`)+jqhIctc6{a1#zL8^Cv|0S%8!DNJ z39$emIHIuG@CdjN?hh*#Lrm?c$#4}e7~EW?@U>JecxJexaEd@P)`-D3ca?|3KPVBl zP~Uf-k&)7K5cXgszcVw>2UasEUO^miWKo;+n>PL;J_lkG`EhTzly3dMsTKRnuIJyN zN}`WHcguA@UKGYP;$ErJP&pmu6%FFZ2-5+i9tJ{V`Xld56rE!+7X!I97Sj~`6Bj)A z>?Lt7@SbZa;9^sk4|hXz*zSZM!H$R)a*`{S=3&hH{EE#uZs=Z)@<(E}KM~R%>)#t4?*8q-Z7W20tg(}I zxR*`&(=E(>987vxypGs!cpn;RZ12V3{S#=U`U9E$>i{N7xe(bibZzPJo(c_nZhW~t z%Pde4I7Fj^dK~{71n9R*sQkB=<-C~$XTKKmV{v?G`IB)`okl+?yIae*3f;j#@aP{M z42y$*;<66EZFyZM#avo9pzS+u2MlaT%kmVnjiTT$7 ztU~l-F?tI(3#$I!=Mqy&$K0({b=$6x|BrSBia*iY-%w(7H_YD;#5B_Zexw@B?#ka$ z=!qAm-N-~cged;)Q}`c`<()9hTBIas_<>4IiAg4E(pZFH{rW+l++fiDin@}m>Jcci>CV>^1O4smr@_xrkDayV zJ4>k?KV5$Px$7a6#z5x-80<;p?^{XK|slZw(jI zV;jI-YE0Y|-{;t!pH<0+sitKw`B}(`Q7%~j!j?`Eya7?hm!$b;y(lqeAtx!(GXhM3k_r_JN7e%=dk9HBj}m1Cqu(U|RE z)RYp|CbetrH&o)FLpQcX8 zUOCL6eswtLaAN(?MyXcj|8#cVVNGT09tJ^?C<+KDQq_bKih@cpSm=;Qi=lS`A%UQg z2}n~wKQHU0MNF_*_D&X1{$U&**j;b>kUV-Hmror6C6a;47tmU)D8qL;g*jp7HZ(Kmq! zkMZfIje(6Vm4P?=`hcjd5s9mO$pHwmv~|ay(MsgtTnAZPYXJ(!&{usFKXRR*me3hmH}Wre>`YKLQbi=!{?Fp)yfGMh1HxS z(n>J+gm_>VDwiWge>GcX?loM(qB}I`LInql6QTW8*Wq8bH3&VkSJ|unzPJ;xzo^pM zKUC=%K$XUJ&fPn*_SbS=9kogSQ*8@Nll{MMsSpUwG5bKGX^T=WB`bR8Wq zrD<^xQH6ztO)0=A*%qtu*WsN$HTU>VR~^|Y+yPrA>H6IM_tm_HMobW`N=WTQ^!oOe zN$s{9iggCA#*63s49DfvRm{({U%eNIs{1f0BI zl*{?kWbbmVSAJm+n%@;Oz3kNXEUc(j!RtCgx3BEeOhNRtcb;0;fx`YHmg+JW_RC;I zuv%=1$*cs`3XJMl$mqA+2vhT_&iARMOI1dq*Qv5>aA=Nc_MCYMpu4gNe0zGo8@jNtIbClrw3@Kv9}B!g!7~ZkoDkADZI%;G0%nX zhA2Y2qS8&MTFl&ZWu5i&UYc<=xL&2ngyUP+oL^hnT4)?oqZ!Izkf@S&yb4SAu*_SGstusmAb3cFI-HPwLq#ok%rwsO zy??I=Z>dXoQJ1nUgeM|#g8E4-ED5ajfS7dP^lP?Yoykc7D2Zy1u)Ln;gtT?GbymJn z(e&-<@uw}uBmO1gg`S6=Z)ohg^rqz|M~0R1KG>9p`C)ZoSNwE9f_zc8fWLfVkNK4C zyR}#bEy+2oTu9SXafBBcJbsCO(=1ZJYEeQ0W!%r`S_5j zZSqoU)h@RNSQl=&C++4abn`*WAfrix;6!dWMqqAgfC*vXLQc*TZo-ejLw%S+6Kz7sz18%ww5I!D32B4GZ# zmvr)~v42B-bwXxMhY@kRyW)pAMJfXTKmz~(W@`Sb=pwciU4ILG*vc$zv9;u9k^LtB zlY9L1nPK+17Vr6qI4ibV!{0}YcR+Bl$sZ$z?(ZW8TjQU-72Aex17PU-)Fs_*^kjTe z^E3V-k7*0~QyGleTS>~;KU*t)RtfC@)5{+)z5caI*#3);&y1ZymC!BWfUU*FKTNM# zAZWv9##qRE)b$TRH!?Mc0_o>!HPZ^N{V4bWS=GCtCy14nVTD>C?}Nnfk{x-st}d^4 zrA(T*lhxw$Ug+<3SmWE6=n=)U3;Kn;xY?tuE4zA)Ku;l1lad}w zu{`Y_@fBm1oK=j9LdR#~PE>s?_0dldR}Y`+?69(q4b3N_Oe@*f#SV);UmJ-~g%zKo zMiwicRZ6S=jL0oHY^tNk9Z%l7z`cMp)Zx@WAs(`~DBmW^$U;0VS zavHnHW#{#hWTO}3b(jfvCl>i#BsmP|nE{b-P`ApM9VTmkg-&^235MUMWaU2h*!@!N z+p^Z0dgyV}_6U4XOffr8=F4_5=wr9UJiBjK0YS^qa$Hw&rtEgU_BvcdU@ENoqw%_v zxKeeAoS+BysZ%9))x<6tAYxA7n3LZe>N%0v4=%o=<3eBL%ZYw*zPy6By?D&|F{jeZ zn-xtc=s?(wuW~^IGfry4Od3(vMXu)CRvTF>m*VU`*MRfWB)*G8BjU{&F3+gEpJBgd zX0s=Zvn(8G*0PQ{Dq-vKZk*9?-~vV6h04k#E;#6i^w_g>yju{)de-IpX>LD_azJPy~*=D>kc!@RIiG_uwl?A1f@H%|X zpymK?4YYGJY`3!TD;+VIO!vU3 zyvklFg@|Cto}PiKN}|ALi_SPPbd4j#x*QY)ErzzCA8&1~C84D%7hH9TWf`t!ok_7> zggpAQ!&YcOhK}cp=e@M(!-3gzO6`ehR7qN%sogL0C!uw^Hk03+H(?!4_!D*-RW#TY zj+a*8Q%=9JPVdp38_<7FCm-hLE z4XoViax!Q0_C<2klA`nJ!>)%2!}>v0=u^W3<*m+YzvK^UWD zzKgIvI?D-x;-F0-MugbFqT{`Uy0T*sTpcxH*3ZeOYhr>dWX`;z2z0)t&=51Za=_8WXs9wXU*35LyUOHg zEisTXJ=3B640n>1XS#*G9)@Xm+ALMO7$Xy=PuED2#!%z+S8`2Xa8u!ri9_UBUkO-h z+;1!%N@5igq9^BlN7FEcu;>~;@8w+#-Z^>Nu>vmwSvOFxNnlr`;lb|?x+;%eybp^k zQV4tMN803deCB);rcUAisu-ZsNxXo1%bi0hdESkLzj>}FJVE2L7`ppXv1uxAE(MX8 zl1?tYjK+G>yJ@g$L6z1l4pl*Zev3ri;Eq|M@}bnR6;sswMUn5IM-s z6T)?<;M}&Z`yXbpJE^mdn8tN_Lifq#3$!he+d+?PX*|a_Y}^+3VzysU?RFeRq{a$_ zqmBmb#X!qouHC+1`Ew|ags+^ftE0_>J!ua=9Z*CQJuAY&;BbQS)Q@`>bS38`t4mnoZiT2dfjOG{ET;cTr z4<$sVQY1w_t*3wGw9OdoZzP}O!+A}e4>uhdo-eHbb)8HX43je;Bjscp1oJ}Db_Yny zE0yg+W%1?il_=I3^!I&p*3R8K7g)?8T%{`4YF9_jW#O3J z^JJtD+IIIYm^;v3K`8LNozpCU|aH6yvsqvelo*cXmjrL9RCf6B81zfA_e z_Qhy0tIdXVMxTHQ0g1uU^A;alrjfpBR`8{COVJpIFO=NfRoYuv=$!J#K>Ub3MP=8> zYqX)9K`kibxwX0`1|HCz!50gN4890F>=dS9c{Lc`FR$ukNB@;+rO+>QB8}h?l{xO7 zvRd-~s@#p4Qk?{doC;;;K!i&_eSS#AjFiwsxWtEgWHiXP>27t;=ICn79nevHr;TRq z5>-BNeSB509aXsdfs5_yg^&1G(jrZKyHJD84j$sbSLoek67!Kw_oE47kiI0;nQ=$# zQ2u2KxeUJV(V>Uc)|qMa+kG8$>S0K1&x>ZI_}qv4vaxETp-gF2ez&%y(%#R7-PMYv zavSZk287kVjotlkaOG7XcOHqCwd_rt`i{I0v%sh7JzI>UW1c&Ua`1;lCn4!IN}D3e zQ_9G=xU)vW2D*7xMM_D%o}J0(2RttFPqtg*5UrRM<}G3Ds~cGYVPW9Wx7R39h|_}5 zk(l>0*Yh1GV>FM;jD46uq%{XeoQ5qr=@Kc5?cbl1S;$%hRK*0rKnALF@=4D(ce@K^ zCT@&+W}VL<`4l4#^0=M&!ChlnOK1aKS1WGMNa@f+#8_uU(=aX^KB8v|ZRe~b|1mE6qjeiMQ8ci zbsmKpr=FxVwAdZU>0fBeJf<#fblrP8n#rQ_7$xnpu$-6a-Sfe7?20awDx>|R$a~$l zyuy4+$S%9PzxqZQ@j*DB%CCLSGm=Bdr-@3G`YaQ1W-x^ZhrBW;nP8t7% zHC4Sv@rfr|&Y`ATD01>5COy#4^bIbuvdRa+vZ`a8mR5IpugKQhYi2S^NRK!eB%}8nFS= z;;pofC@|K4!4Bpn7?PO}IuN4Upvx;rz&SAe@?|i^$8uh)6f3Ap7 zVCr7sQVK_LXTx6EJ%5IIel0E zH2qtsluTyNcTt0?kt^ugVk_)Q1E2iD?4sd=K)2hy6S1=4y(7J}9Jm)Nb~jg{^dkHQ zQk9!=Ex$JN!CAZY*{_h==4Qtj|C=wqLK^X5_rjLVrXGKaC0-8(@qK$@&h z5fzPenSe;6mg{9`?I<>E;HPM|UPFGC*B3nQ92K)<2!E-NMEBi?=hQrqQ~JGyk3b;L zA|k;|neLo3*(sDagC%!B#udfsH}RG}$fQxKkyxqK4ZGaS0{Z(UY?WG!S0+<9rO5C88RArom0xAcovrx5RnZ&#I&bX8F`An-?Oj??BSqUXFTAWU9S5K zsV8dPfJ~T zbX7n;*xxSW2T)4iW3r|`*fqy^97uTk4Z67wqL#pu<{!Kqy#W7 z8IeC2*C1f>?@x;P{Sp5}d#vxP+PJfad|hOuJKdt0^MIG%!1{x??YtX5h~Qs78T=3c zmemadkNEc|dXBs>VBu9;F5IH2`#MWu7C6noHl_Q|r}+UscYeS`kZbC{l-2$!%);`1 zh+D0pwR7U1+?~HYP!2hMX-@)$r;c;?kyf_X>v5T^iw+CwUnGKI>aV!eyyDVP99duN zH(q*u2f8+vBC}=Oc6=B2jB)d#Zm5OtJhtQC|A#+!7TN5VBw4n2*0uI_{>I`2)Y&50 z1~MwGGVw-r9`~zIG><}z3q*U{#FZ4oLm`&{6_<}a!BI0bIagT60ud!IduHGgvNJ7K z?agYo`&-3td$_rP-cy@=oye+t8T|(7G1GcgwuVRK$_rUmDwy2Gc|>@~Rn+vP zqD#8kpiTa@Ha~0TVKJPcY;X`NS09*s7l=pxKXCm&9OPb38f*~GX@AeB-N`Xvok{w) Q?;lt;{&#Ch?6;5q18iU@jQ{`u literal 0 HcmV?d00001 diff --git a/doc/image/tutorial/misc/img-tutorial-spc-run.png b/doc/image/tutorial/misc/img-tutorial-spc-run.png deleted file mode 100644 index 153666a51a9c1cb959687893eeca3aaeca9dc3c1..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 147847 zcmZ^~19W9e^9PztG;t<2CbrF)WMbQx*tRDV+qP}nwr$%^-pS1U?)|Uz-s|A3uIj3; zU0wC-+Pn7&l$I2Ng~Ega0s?{+5f+dI0s{8{0{V3L85}@KHBrU@0zy}Jkyo~p)p5kP zvavKUHq*zqbGFjQ*LN~D00MGaDorws!fuQzeb+^)1|{=XhRazz*`W4p^AWE~F166A z?*B>|EEDaPh0v|f5h^`XTM8lSfA~?Wh{>s!V#_T=DSx3vvp{9&&$>psita=wRSC{{_TCI zfpzHH>&MI+MbGw`$JU9bw1>E>*LY8wR&mY?68{C z&ueVs`D5esDEDx^=e?f?Xv6QfXP?(04&w3O9|m9PpP1i5CTTmvw_OFF_^F0j1z#@W z+dtp=Zy)ZzZl7DGc$AU7Jq3U9c|Ejldp}z}UAuN}iiG|`y&mM!3CBy*9T**ve_z+7 zw3~iu>#mhrzUQx%(B^a&&;Vvh!{4+gi%Gc6D$4ru(2R9OHz0OqhUa+8&vd0$YT#oa`YQm&kHwG zv8dw;y0wu4E97N~S#OXBhZYOcldzbXs8m?0f6gXVTV&@%1;@&od>IH$GAUCOE3KW? z6cXdhsGTw~Ev=u_mD0|*oiep-y{FH@S~0RJ?R@khWE^9yKhM44$Bvpg(f)5YH|1M# zTU!$_kCmpX)#U9exz1hmw*G2ON3EWwvWSMOqP|1{w>V70`Eyrm(6nQpUB@WcC{*&2 zDzuS>+Bz&~W{iDB{gqS0g7ebR`k~7^k2((HFII}Nb|@(u?d=Qtun`VmXV!xdiJHXL z?o6KwH(y=uU8_BP57wSvo4;3I;NjX@<(>!~&GQtG-u9cU@>1WQD>Y-H$TTm)VD(5k zH*W+YC}Hmqtg4pB%$-^ek}fosj=B~cHiDkBYsf0RV>92|;#`jiNG*><{(>@mUh1ME zEWa9# zBpJoW>@yho<)LH$e9iGczO4nJOujhh$_FaxFot;fb-Y{^?phby_;tV@KE}-jVynBx z`X#|5+X_L+e3mc7UE*;LV-QYWc0Pouk+McTJsQtac32K~wri^cKbG=*jqn>Vl8K7# zMT>NA59jZ_>WF|xtP_r~m0o{q*_$vj(j%_tcaJ1{sl{j1YpO0+)@ zbMl73>gyq@l;Es8GPG~Bzr~<452gB#E?$~u_eg}U?5JV>9-2sd6_koOx#*Cd;z;d* z4LI`qydH|1r0NYdz!uva^8=yEV5xi^(iq;(=4Q7<6J{oVmxiN3Ca6N^IHFtv#0`t> zYnmm|Qn#nTu^4aL|Nc5@=^>#keKWTn+-H1hhz5ZCP^8DP5g3=IILq zXj-NDZ#dF4$gihyPHz`nP{E`|x#=mt`0pnM_lM+H!mNML^4)@l*S=~#T!8)&mUhEHzT2dXpi+zr6B$|Hr}^hE+clqaAn8h17b)a#ufy8#W zd>Mer9TbQqO-=<@SN0_;plpRjI;)OWh01ruaO1as4dhLxUjemAwMGpy6DEq!^?}D1 zm@1F27d6YE4V*7c@kY;nA{Hx^+Fe)?{; z9Xn!}{#u>^yY&7|K)jK8SFLNU->oVAG#q%qzmqe9^M z(2Ec9I)XnpP#cX8YmFWE(ht&-r`hX!xzm@=FciVfy;TE7r$4C0418^Al>$w?;9)`_ z#y828hkU#Ts7>I81dD8rSkmAkOfxd1tTICvbf`l*=`TG%=qKUGJ_Qhcb~AF>FmmQ- zK!rg4fk`QEEP>xZxowA|SU&;xQ!OL>jL`pvcR=n3wojg)zAafWhdS^fM0xGttGfyq zoX8Dx&u?NVFxaq7f?q)If;(BCJ0a*~oGNX7@Ieo&0~zUch!rv200jH z1&5m>x}!xt6`|hU5-_D8%+DVDd^ct^xBi2x~3Vev+;K%R0lZ38L_jV+oeqA+z7%hR;!oW>-qaZ_+X9S;+I{k{uK% zJb6XX8Wy@=tHBL<;4V@DiIT!z9Fw5xUD!y!f15{62=fgr(^hht?H`K#w9YrK+hEwm z)!9i?<&G~>&e%uB*b58STkU{HS^suN63cP1C!v&^elX{)_6tjr8A?y$UO0Fb^wju@6buMDTFnTZ#giyz^wlR7I%7UoSw=%BX3*&rmV@X0Q^K_P zff1AAdRPEZx)m8RgPwx|^9-E+iUSs%s*nZ&8qmqL9ybYWquBwB35Wz-M*JL(^%pn7 zb|e}jq$uPED9pA-=_(+X9; zW=_TE8&hMAtWM=v#5}ML?|loQF1s{28BE&y)CER$+=MOy^E}_-o=6i6usUNYouwaW zhOJ_aPDRT%vtx1Hz%2NpD|MoAKxV%o8DfjEMy!t+kyhS(YH#0E+qHFN`H3Gwl>1;b;4To6SQZV2O zqn(LwZa)O{3I{JU(_!UEet8V{=*9VZul*)g!HToNER_Md;i7IAQ6(68%?HVM1H?aV z1@W1ggJ)pGF;HFrk}H~0FC23+A#R265?D}JwcDx$J}a%OE8Gu*KzpU-p}YhC0tg%G z`RA$`l0^rTJgL4v86{WmoVqe6oseHjg6Pg(zvGR);AD1joOJkF1|~y{2dbb~QfZiB zCb_qn)39ZeTM8joEnT?p=ga^!A~Cg~=?IqvBp-j|G#@C->8V}*;Qp%C3yhM>&c)D1wSn5p85oNbuk zr8DAp>H>0shJG?!E6_Il?ue~CanOjd2dfg^y8d6S{P)uw@xbr|VAMseC;Mi#+7-Wg z;1qq@mF89a)&Oj=4d(oHCb^H4?797ijX*@7lQM-OGFuoBsk{@4a`EQxov2gBNEj!~ zo6iIS)&2G3)+ka>b>+Y{Qs!*A$0rKNenN3yaK5#6!Ph_utXd}n0g?Ui9P@k66Z09o z#_b@2s+s(0xEYK?Vmuurkj1Z!D_AH%Br#Rkn$VZx~kVsqeIz2=4BXv|3%z|w`G1z#TL{U|th zqhg(pYc-buCz&;4kR?q9;|~i$;e;%VuyPdygQ-~%`cn?6o6gW8D67Luz6x9aDa^&N zfbGINzjMVbOEYW!KtdqIb>vq%=(!kG=5Vj6p1MCup!Wg%jio@wqxbw z%FgF1f^ z&ALVDw09xxh@)dB@?tA4K{3aa`Mrx$@e-!jCji;_%^j!~ALZ*OQzInY-Lz(;ro@U} z(`;ZU9ZDg&jL~KZCG{kT&7D+GG^QU^o7%HLQxsw+GMB=I-|NeNNnl>-T*ZJo zx>xaWBX$SMFAgM0q{#tyElo|XFiiwkX(pfGd=9A-y-Y~}=4wcwLp{ZmFF0{{4kjuYYD+6o!n-*#3w8Y-#y>-P-F3Die= zpm`WAw5<%8bms_s@p4$Eiwjozji+D-IvT_H*~qV)TG&)7cWBXIO8lCG(3&MGk$qhZA? zbgO2p0sh5eL4k4wkq2+#q>R`G)G}od{A+pJ`;Osoo-0bVGh_Sn8c8RC^inCPN|GK2 z?r)nctP;}&$OyqDRI5n1Eqv3T3QXo+Jc=`JjstL{iH}H-{OStbs|PoDHLCJ#B+XBQzL(D4fm_qw$plN{K`F zYfV!U<8D`c{AiYdkKby|!6y|o`)mUN%uc-;3~;b@Z+$cYa{(lmW}Nw16>0ojIGZSS zNbDt0dhCKS!5)O37?-Ij!XB|b%AyA3nUUV_tFl)3aB0U&U3@ks7eEw5H|KoD=%y24 zKvkcy+=K2$lbpa{GfMHGmy~J09<7Y@R_l0wYo6jAprE~Nq|Z86H!(Nr@@b{jUR}O~ z8t_@@Yn-xcaBZOqS~ccdnB^DNi}J?B?CNk;W`+Sycl{m-WP1_Lkc4CyVY#Wf)Cu2$ zj^dPp;d`>4m%gW%Bt4u*`~ZXc>!pRqX@U-eDy)gcz0d!e3EsT|ipD!_FXH!$H&Z-* zIqP&EFk4W^e43DkylKz0IYq1)+$nYiP;8>NiqKD-_FWCnZg$lWiV2$VJ2rk{iqZ_< z4NX<@9KIltY%GbQ8aWQm@A`N_sRqHpnn(~?G_|xHg$Ek%iB>pg{H%0_({NC#E_D{?uVun18Ms zhf@4a-&6{CEpHFa`|Ax9^J^^A<|ZP#eU-1BNDmgTTZ=oYC24iM@yZ4dZ9>wjRiBW_knMCiixpB=aV)pkEDrh!VoXuL=~rF2F?ax-_F90Qto}l27a3b z3f<5=DBuzE3Za4Ipi>wBZVv~!a-?rnNf1vnijIDx9OWX-3YuZB>Xv~MV+^%do^ z(?(UF|8fZ_kJxxahZx$!!09 z;(4;n*^(FUZod4ieZhLc zy{7&9-u=(jxr)|2t;@oGzreM{)~y^P&5# z=ZOZ(V^e+IipbGkQSl{TgS7X1(ijrY8^Jtnq!@t`MhG@^!FQjNr_T2cN6XT#o!{}u zB0#IOVb}DZemi&@tXj8)L7O+1SOlSQ^y(z# zXVF)JnnHvE+jtFWBZs(I|HN&oxvsj;<_^R#Q#=D}W%W4(mE3i8e|2-L?Nx31XdRx( z$R}HxM*8>z21-gn2M{6bL?nJd9DscO zjQJUq;X45k5I&HIz&ClPrIS@>C$)L!^XK)ogl|@9sm z>oHPl22UfFQ|j{TyV>vW8ut&`-OmoW4^OA3^F}9FB$7ys{aC`Ld!mt@BZyV!xKw7S zqPDm|i1-AVqt*+ z%>2{5dpyopU%MX?a=xC@TtS_rWFD*fH>k>sVvUV&yR_YF3pA=#~pQI z-IwpII{^P7p?!Jz=r%My9>095C@C5C;?XWXO+*J^B-~RCPjz&7Jv}`!F)`(woms%b z!3~j%fCs;P$N`}yuB@noeFCOdsS=npk_Y@|N+0y4MgdqIZU*RnFx}GMzIlsJ$LOF# zf%`B#azKAbDVw?RtcT`|Z){}v`T6Oopo)B42o-vr`EV5#EG#TJVxZAr6fqR&CmYO> ztB=D#AY}o7Di4pgp`jrrIyyc+0I6bQv98qH8#p#DZfI~+{9}|?Zx7(QcWsP~i~_U) zef(?~c=+KMBEi=WE}*n+U#BgfAFi zpJtoCV0@UE0=&8nU93%X$XLW^a@3Kb#CvpIOc=MaV=l?hV*KA4vR~PaW$>h8#VjYV z@yi|5+{oW~;X=b4skH*PPV9?0txJ;g>_PlbH_+iN*5m7w_MP_kQQ6rf0W1n1~s-T&^>pTfa_BiCEE{U!xa~eZ4=Ye0XZ7co=fDSY)|a zAVqe%$ToRw=b>4QBO26Qa3L|2)=D-QVnyWrSJz}BRU@N@EE!53!RmJK%2S3pIY33x zL9kZTrcLqt`n!xQ*P+}^FKyv9<@>JSl;KQkTSeO%PJ#^yYkrUXf4)7GJqjqCFm64+ zoQ&l8q4g3)G>D7a6nTRo0UD}sP$Rz;QpkLiaMPL+rH253jla#SX24N7nunF=ar#o} zz5hAS1FLvKMK{VYpBMxVawRUjIN9D-}nc} zc(Gd_Ok|R$uh*HY3F116&18-hJhs_;^pUvtk+=xvyJMxl9EPyZu=FxnA_o4em`-R< z?x$fB(TrIYF%J68QQ?VqGCXEp74FNx^V|)_tK&vzc+tDzdelksU{*Z@S5>|vEJaRMey-SlS)M3o zMJr3qz9gmwqv@ak&N{D?;%;x+T zayz;V7}oxacE*H|`#(ASp??5|gy7@zPaA+C`VU+gen&zn`|Fu^6A>}d$Uas{YLgEPBn&)+W>J}nG_Hz~51tKCNH+VN4 z>dmF0DEB8PUfUgHQp69vfF<;+Hh+%eWn7eEAQ9ytzEW=rAu%^wmOOa16vEiwY880^ zN*pvsPg(gp9LOSkIn^!Ud=Ng05h!Z6#+?6Ov%G#7zr^V4zVkZN4B9~k4Bjy|g$L%L zB%2jg2Cg~2ydjDN5XrqA-qCBQkaCnI#@W_wF=AN*RamjX`b6XWRj&+VKo}WaGO5=i zP@Za3RC|ahgY?RocqJ7-Ad>fj6id3;AW{2j)@#Ue^rfR~v&P<-Ri~qY> zjAxO+m{}}o;@jM1w%t_a9pYp`7Z$r>0g z^vua<%rQ&i#YPcB5NxghK2M>7uSpsEr z16v{_uaO;by*1%~XdN$nRS+HWBM-j6`2HaQ_Dnkiw;K4we^JHDcPu3QPN(Q!Far>n z^n!{1##O?5U-{&4QY%0leLSW|{4bbNA=EQ2GETZiyL|#|_*&v>;EaEx%*%L@#W4&( z9C7?7Q?xfL%w4AGvBk_$Ci7wsAu^i6+B?}sO_C#v_BV7pG0O&zh>8--`{3X=jkfNa%5O{$DO=e zZJwM17}~OHmI`e^QeQ{N) zYE`p)Cm-PYw0+p%?3`r#7f$5&;^ntK^@qE5Jt>@BGQgR%A zcTU?!yT0D8-+W*=e{5=M!dj-DyW__6Nj&p>VSz4mm%Lw7$8+|e=jNSkbRTvcq}H#k zqb^)s6xsUYtcXiliIbOex}d@upP^!VU`{T(qxd9EM; zOM$dKbTqI5pE+GIX1(tp6dCR3xIMB?IQ;8Wh4i+TmHH^iQ^mNqHQ#>k*vtVNZ&_5Rx~93 zDR=;@F%ppha7>4r4kBQ=|2D4??InhQzug3-qobog_Wo=9Hz;~K;z9iTKbC(;RBR+7 z+J5=lr9xim0Kk17BHktc#})l;s9d_XDy7tmCXNn;m6eeJf2a(q`ue$;n3#L_;r89y z4sha=JVZ$V=Ou*v-&$uxTeJ>_{z!ObwUcOw1&XYp7`;UX-5Rib&C z@+Tm#8pdtUOY?vIrk%-%VG8?U6W`v3A;3o+TLxF9|K6?OGba50V=&MNtG&Jbhp9d= zq2H?RGp6DGh68>hdP3A_kk_A4+N$E{0Q>3Q6Tj~N8y68@l(+vuXh1;nqbCoWm=8)f zSM!I4h6?=I0REIZvlA0^?VcrAekaKJ`m7;0qX#_E?)lZ~!LXH}=IB6lC~^$w7yl^* z7LWQrE81Cup#=HYP(bDMWsA^5`0Y>E%Q@%&D;x~D_PgCa669}#PBo6W`PU}{pCt!L zZvW3zAs<;yRLjmeyRaZE@J9rrw5m!La6@zb+~1@#AZg95*)6;-+s3%)$T3{IfFL&E z2Mi=fzdf(q_wvsid=xNEO28w8d3ph$oPTMklpLpl7(jZ6jBjX#c>jz80swo=mMz5J z`A5+HaXZNW0HX)r_rv2qP5v3bhkTy}!sn83c})55ZedNN52U?mv&0Zn*Awno9LIfE z^9hc8?twd%*G^SYG@a>jX!Qj$RuPoR?G%hT#Z5}aMxiI3V{F4RzIvG?^cQLEmAC6I z?sM)eT+#C>ZDAv|pav1raEB^NnKGfJq_^Lgrh^| zN@3}0Z~>N65*m5awO)70;yAQDx@tz|HmKwEz8<@S&2m4A&t)Y=a@8eu$Bq^Tnzh8v zp9`QU;|8~{2kjbmZ%~GmWQ$MS&R53ZS6G zc1}EhpsjOc=(ysZvnFzAPV}?Xn@_>vDhzYZ>tXthY-v!GQ%GDDu?FvB$rk9g+sv)d zri(@4C^i&Ia;Fj`u6=U88bUrjN|AZKHS^H)d@*Z0YI`GYbz*l&2HBo#GJNM7w>+Cq zYk#6_ooi8+4WXfSKTx_k)F3|Me&BxX7DHoVi#`rh$@BL-4tA;Ovfd^rwhw=MqSczU z51y7{ke9x0;JLC&3$s6&A7n8NI~tA1cdN#AKG7^Kr;@LmpOCIl!WmVvvpa7uF0&3O z0z^FYK2|Kj+z2?(h}u|9>E*V1CSRnGA5n3$X669Q8ljuOJiPEDF)%E1dv+TEk4m6r z)_RYd&3^3gDZSo3t=B7wTtD>V!d{aETrHVX>yIdc{AZd)QHD##{XK(u4@4~(` z9`End&}asfBC%zFNq&D(AsHRgG=2`KDwj3)8F>57&~XR0TUoHPQ53Zvtt! zYF^Gt=vbZh{8FvDe>fc*Eo7JFDlDlLb`^Xbqu*y?9PPWDHcg60F`bL|M*Dgr8=?%z zGHnA59HJv2Du%HKX3IOF7j!UFWGk#FDqpp+ajPD$T%-PGlk<$O09yMNwvlp{#)jjc zJTsL-VUx?q;7x|)Z+-R_!d*!_m`BcJuk~!F7G$v-UdSZLg#CO!q$KFpu*y zCZXf9({0g52^+86&cqZ$4#z`Oo@V)`?SZWREI6x<(!*!uGUuE8CP~J;?Ko4r{OuF^ zA~q%RW2;0S7M`sbLn`eGvu_EQ9&h&Uuc2Y&`6D+wsKso_ChslJ)xiuyX#d=D=#V?rkTZm+?y%0^R!yL0rqFOJv%81dGkhFV(&+$O zhppJ}>d%A_=qN?px~@{btv5`!M1xaBcz(1bMoXqABDhA_q&x3(g&x;s_^uegZW<}e z#?ly1W;sf;t3(ywe;mVXrIG1ZKkKns;+Lg+v~V#f*P^(nKRZNG6hlgh@83v`e! z0rb%k2BUjqwE%muW1;q;sI$ApBL6B>J&xS|Vm%6WK%SLZ-UztCezMpZF?^w&MCl7~JJU?=MTY5?8rYO{KT@sz$NF4HhKD&Hsx?*Z z>-%0unYJ5Dwm$8Y^W<`#9CI`orXMYT4`O#4qE;!|9kaMy3!}~V(=s(J-VJ3w=qVig zQ5P1ITZTk?ghl%BGp_O0fQ%9$qOd|Wskt}A6=>>^)gkuS^f{?yTU;REpIl+4!!jWsZ&B~&L-eI`fp&f~D612Q`7*LZX z_6GncIM^~ckyh0C@oGU3M4Cd_IQBICVKk*{VM-d!ZHk-HrW5dP;X>I8!#Fig!dQpw zt~{+mMvlPznu`L6hfgUW=!a_YuUHLkQpSz%i=O&BHyu%DHqq(rmB_6{QLM62t;_C~YPww4Iw#9F zHELwKKOSrps-+R^N5Pvu)~PlMI-XF<%<0XC+Ra+4CQuYDW}&1d(7Zk1-TE}W z(Wm?P-^>9H6~8E#FDY2`mf_A9T0F;%hu@CBR`Rqy8sMzIHuBD{vZmF~G~EwB4J#$- z4a)B#wHMQJ9muS%zb0xnpf_8O?1sC^Xt}XT^|#&TKfNs)MLpw?>(0rVFTYken5kz* zQORwlk<8*bYm~P>rZxFlhFV+9qM9#O$SMp|$|qn+cbrFy$@~CsvOnrAKh%=)(<5y~ z4d)lbbJCQuESLTkriJUzgncC6?P|YteFdxmmscN)(H84+kl0_V|D(``n;uM!_Gq9I z6=l{!&OT5q(=XfQP>6TB@Qi-f3e9vIq`9`*p*C*EHPO&irPMmorQE{bl`@Hh0Erd-1NiC1hUF~<$1uUFwnV}<=UhTH;JVLBl#C8&cAdqYMHL5}+xRcP zeMK3f84YzTyPKgzuG8<2Qi)iNXue8wf@tQ>vD!{PvN(@D9f;y|Y&tq@W zAiKSyS$ZH*0_SA2F*69fV&Ts5>W^4;6retzJr-n5UiD<8*Qup&x-{>d$v%)4s3Vkm z)4wNUT_VQ)%`Xzn)9g&L5VQIz;QFRGKPc&@lpqQc@f_9AVb1 z1ron5Lw6Egza_c5^O#=}zgV=LY+fY`rgj#+PO!KNVgLFPn|x~0z|XIEweP!p8l{77 zZ)pHjT?Qve6{@AvNdPZivYuSso~i|LDD@}mI+gKeiy0e9MV`B zcelJ?GS!hgSF7~mh|;s#aBsRtqF1Tx$X;yMk|U=z|4G4P9%SjY)BdQ8H-i;^$MkwE z)#Z-R+~lE;^Qe}%TPe4n=U(NssA9(9tlr()xf!=*y_f8Eg7%-$}sIvD85- zF26I1f@&)j&y&H*d>7NqGSlfuSW#_nQ>FQGrP7UTwHSNx*=!g^KIYnLK4a=-PxwI} zSVYElDBuO*k5d(My`J$N-ki`9Sc=7~hN~;Cpj!?3_1yZIMJEmV4I`ww@^UC2POL)rqDN;hu*q1WLSyn2H#^bHjVh3@b(evJO zNhyt+i#azQQ&i!oL8xn4?axbjwFlXp0m3%q|@ z;?|+S-iuMhY+8v3hP~|0UZHX9;HYNJ6^}Bc`su-wVPZ(Owgj`ZiNxvLER00FVBun3 zFC2=@K|qo_y%C3+4|0$C*l^!{(@(^8wt?1Dw~R}j@tBtH7r|5e6}4F2F8H{s!a$^= z;c9n!TEAs}v_-7a%v=16O73jek^Hz7989-9jkMAa?{I7K8cEAO$|PE3Ms4U@Vjhj) zkFw(Tp)b8d=W*@wRZmB=w)%YDu?j=<)jK!nQMHO-!%%wYb$;b9$(UiO;iOJwY4San zoT^P+_(CGJZhP#$CCK5UCQ4eb$Crg8Pp_)2rGjvTLTxYVh1HaWgsfHbWC(OZM<=8v zY;S2)A_inii_0wHGPKpo{j5tlr6;3=uJEkn3wElNi8Wd(CZ**{^FExlHzIbwm@gKQz>u{nh>Tn!3_e4vqJ+*~Ow;(Ok1hNJI5UHQK>g5HaOU2i$Y2K%xHrEEzoYk}0H|X>U zwDi*1ZqButL#6WYkOI-W1u6~KYlx@Kz{pMRF=Ce+XswB}TTXk!O_A0~9g!=O)oi?p zzLRgW?+=!@rA=Xx3=K6eKJBGi?X;#*bmIoC#M5I`_H%d>YPWe5T#hELu~Mb^@J8>w z34kmBJT=)$iFU9_6qB!c)uk8+mD=7RE0B?S6WlGgoYHP5w-oVB8B*HW3a)P(8&Jxi zT8lJ<*O0C-eW~yX_%5-pPrXRwUoE=$1NW9$Xtz|E^nQRz&s{=;96Kmi_!;Gg6560X zGTC|BdR+N#j!QX?jODQX4(Yc8VasH@~NEvloTU%B zt++yMEslImQK8mcRW$yptjjwyj@2lXNR(>gX@c&UkQDu^(2}A(^`{g?S`1rrdhW~m z>z$!PI-=pU%Sx43bIdwof1RPj(WuO_NVrGP@%oaljY3P8+Rw8g$%LK{SHn;Fc+R(% z@D`It5IlLa_uRQ*Tg|(G=T(2-1%MV(sDGz!wJnq5w^hfj&Je5}#=+!pR5#?mwvzX$ z7Olm)%4y?x-RckqoLQZCq^?$LDY5eAq9n5xZEPeTr4(-^(>%IK{(#_ba>`Vx45f^T zKaPm`8P!oTahHESA4FeWtD4$>JC$}nV=490hzBP`)JXZUbOJRHvuei2SH>tT%H^>iy*qPXQD=>c++K|X3Zl~_o#(QPb})-WyiN`HQM zGs>)3sauEg_R2ud4L0$O_zDfRrJQi-ip`)A2FZG$`Dt3UO(zjs7iz<5{Dnwd2`B$y z+J272o=IJ^*Ry*m2o^TX+2H1VF={jNkYUOxP)w_Jw1uXx&t*r;B3)3edh=pnGvOft z#x^dDn!}D!MK_^7#{B7eG~)24C)h%*Dl2i}8&}C(H}8yA`bu_DQnTH>hFXpFEgX04 z6U`~xo#j&>e0YKF7&t}(#Zrxk*hs|~wx<-x^@UJtq(;v7bb{k4``VD;;MMt(y^K;6 zFk%X(*u92EdG+gxG$*5A#d!T;bJ02!1*e6G?g(*P@Of-TrD4|9!qK(l=K$uK12k7s zu@|Ek6&@OcUWz+RhU&BV{r8KvKwiSCPeTk$Q4fiSm5Z34ef6+>ZJKeSvKT&rQCwhF zmDLx7eq#iRSTRi3A-a9gTMm=BBZ{W$GMm}ll8ggvx4q_3J>dk5b9vfo*(P%i|7W~onrOG9&==S0mN(}%sDpi7Q52u$*viM?eww*5A`3ZlJaZmdv9 zYNaLEDVFtxGbLerWvS1%!p_ZNH(z~K zGhY zrca}pn&v{t{g+v*WRxotN4QxvlErJ+5Z`X&%`_IOx>AE~urP6h+ITZrqXOvljW0&x z?H|>b%}t^q!L$^a7^32tcW)kuZu2+IE#7IZT?^FW;o6JD{O=D80gq^=+i!r)8?L)u zo`#5D`8CE@#9s~KOs4ao5`9SRUsgIs)~9hr3X(DA-Lq4c3~x=_p;TR}IDW(gsu(L)H0`F4AOe)J_M{tkT50ri!xu*oF@9 zmnv>%XVP&l0p!L8R=GM)dCtA1AzLd$mX1pIDU{}7_C{>0O^ll~<=HAtxJm|}O5zd+ z7U{XXtvp%r1S>EI&PnWeXzB zC|b+BKGwWWInT`Me8h(ei8`1&E4L(DnB7a%&UPzdoj$E&08~h`A#HHcUuYE>Ww+aGfTyus1!K4 zwcO=c`^S7JSP9vwm@sOYz*I{I&*HBRp>BTsYeDul8qS6Wroy>St0ErtfvL&ohU8A> z?H(7^`l^qE5~?0Tx!CsHNs|J>V_rc}>QMG}rdC06omA^N61jfhVL0=T#z`tvsL|B@ zM1*}?U7G=ByOf-+MR%zy9;a_`_ApDTnpFb&aEDz99q8=46!7R(n9DQl+2Xai$|G^& z`6N_+o6|>}^OV~4Cg=6-g@DRr?S~H8aH~kTcoKG{{$ib8Qqrlq@=cf6)6u#UvPpQp zy=ACMGY7bN>41aj#gf?S6A4AeTJ zB;~}99$8LDP&-THSIv2d=dJ|@u?O!AA4xxF)+5*9T$R1TQWt-wn6Z%od3CQc%TICM zW##yKvT*SnKBHdrk|eZq6g(i)BJr3VoLHZhT$OFH_1%F2u}bejYf= z+_8`>U*19`=%zM21XDP(C78RduxI3KcEXF8b2%omR$|u?beTp&$m2Y#hKCKpUH<@B*oS`05-N0B; zQi~5wmOa?CL!5og}OtfL{5#A=N>L##`*-fcbE zPs@mLJMxORc!fRQ@&Xlntqj|o(tK&OKymV2mo2TF% z@&ToXgZ1K4PLf*ojVu(p}CEYjS(IUjp5q`OAkr-SWXmw1*}|6}9ZIgazIG zq_`*ydmA(B%d~2_MFmum+pT+$if)xNwyi24MKeK3utVHWXV3HDBKqxJuK8XOKLdN-m)t!CeD!OSso^(jUfX6QUTn3rWos)*PD zhv%3goH^11aWcwzvgw(9D(d`$xCheR9Yj)sw8sa57Ur#n)jStF7_~1qB`&1RBzZ1o z(->_zgrrTi&O)WQtL_4@v|4Geg`oMx^)n7d+FI>qD8+6fmDsn`Kl3<%1|MdHln#>1 zH51Y1!xGCb{5KW)m zc&=UmYMbmmQmP+w=crT(+vTDFPcC;~X8s?>-ZCnVZ(I9~0ST@lcoHl)1osf!9Rf|` z?oP1o-~oaMcX#*365PEZNaOCVP4o6Y`<#95yT`fX-ZAP!kFJ(lYt33~&gc16m4^;s z7V46(ib9q+z(pfClXb+T80S%UnW>^Y>&wXEJakg2wtA;|$~HEkzUL;hTBMzkrkAV} zG^o?8$G_f!8_ZhVlI`p7u%>gy23A2hEx1o-DjS8BKMnHsG9xDLuRkS?%hgs&9|i2eF!v znrd-uSSp2kb;T@HZ<(t$^4w~{l<|_MW_k2}gXOCKM6=is2yJ>OP$LcnQr#&bQsMk# z45G6vQ;iCqrHK(%xTiywtb_qRLI#Umpf9IkNo#)Il>MH-_6mM;58t=(kktA z`T`@Mh;m7`=6&72BbrB$SU?tOWV5nH0;DXNDFJ3eE92AD)yHG$D?ihwv+XlIf>b$V zC*;xGvQCwRAy-zutGrtK!}a=-6rlLB!9*%#r-(lJfX*{Ih;!M0y2+ESGCUI2WP z=QV3LF{=DnaHf=@?s6P$8v@{GlB1&%|02iXhjwQEtq7wPNa)+&){YD9G%B^}*XZm8euUO${Q=3>DztzPq8D zcV}IXlaW3)9V?vV+3G?RhX2;<1w-yKW$$G?9+)q-w@ZA@&Mv75GPm!=)|PQT-rg3s zQ!VZ|$C}%0c_hL&nbt940OjZnR|>Q0S=lyj=oLC8 zaOB=8M{qc*fOnspC0)(3>#WmzvuG|KvGV(l(m%bxK_=GtDYL;yEJlIxVj1NCe>-0W z^3=TFoDf9svW??k<0x)nJ(~MZj!M_U9v@gYW(SjvVX9$3V~=Htu4VZllAJq=p`%Vg zsWAV~r&3hFo&zOd(k;f4phA0SA6z<4an0y3Aa`5ivgs(Jl_wo@B##~>RoTNpxxict zF_^9Ag=o~7w>XClZMgEA;@}_;ctYiv=<*t1Rk8llJ>}CqHxb1BGx6ZeZe%%*WnAAo z^-0Gf@d%6SU8upq)agvJ8<9>ref?v%xvyoL0n7cqt5qzFKha^bSEzV<#R*8Mw6X)i z*+p9(om7vqn<}~Vuu8_$EV_rV>VIE6SP28pvbEo0VF}+Rxt9Se4~NKWa>Ypxjwhhk z6?rkN@X>cY60b6U*eV@sRT=lo`ApL z%vMY$wAclC>$;wj8p1TE$yO_0IFESg0+?+q9Sgcj_kf92j~l?yC@&-a1~! z*RNsK?zIV)Uw$8%d(}Rr*)YHX(!a!bIYr`krHq7=tZshH>1o->tF_dsBaxKijqkuRNlaqM!yn zH-pDm{Z^sGYt$BvhvDOW?FOm(M;mZOroPcfCM1a<_b=M108uS8@G@P3D)Z=Z3h_nR zC~$mawxE*JlkPrar(XTgp+wND(EGvXNJY887Kwn&SDScuI;C1K7k8VAbaTYGvy+)A zUte)rbrko$h1t3BRG@_(nG|rmN%!Q8Kcmy_of9&ko1ZBG<0eIkt1ZUH0q`<(7LsQmPM0H{hg-<2#2LA5W8zJ)eJi`0Wkz z=$jwH*Z&eN0!)qB6cMyPK!zKJsIFklVusKAb0%T+=(Yb2VA+CTK8oLvj!I3BT1VJLS}6<78NuxKCo+ zKJn3Ax8R8sgx<+*lZsBI4`J}DO2^_gwJCi5t06wwN`*iK{>}INr30fsV@lzR<{5A% zzEj@SwQG44gZ_;EFQ%#~T}nFhNu9xy-8H?mki*Hz5Rhc%l4j0Q!19!6tE*T5N$UN7 zupr?A`j}?yLl-9wzN%4LeD*@7^+yv1kDH|s`@h)KH_vc}oFYLa2e_E=?yY$;CE`#N zsfbcNMj;lqJwD7PrHeB_?&I#1A2+WrS2ZK8cvv*tMw~alKGRjJ)oQeOtAM`={5HZU z+{Z(;_tmeC^S|H>eNV~C)~gEA_wJ|-%L*bPf7|O45rg^Un*zrqk#J+CZR8-!ydM5c zeJO==*`G2+l-hGdMk_v%S<7aUy@yt6tvQJ;zVfNBxTcVw_p*B*>@);~3 z*F%37KO_LuZNmN$x}X>N+qKwQzWgkJ{-QIg<#NYCxI)k-ydLb3x@C{bC=aC9pXOCM zkrZ$l2@xnr|8GcaYi6f~yB2@rE8*Llec5U?QqFp%Nq4%a+`hL6H zn@~=0IptUQJG=42e}kmsCbT;fNQie5W0-kP;J3Z6PjbK(J{FRx14K$)PM zHQCEQ#pD1| z=8L!yBI$f?imFTnoP{YD-30sf6<;e;0DZ19Bu~pd_p~oVy@xg_k5tz;y(sq4t^cfQ zx*KI1$E?T{R{Za#p{S-^P{mbmAJ^Q2z~hWODfXLK)uM=&W35e^%{txDy|xN8x5t`# z-9xZ+h&WPT9`Uc&)wZ_2StCiOYPuDfu#^ENDi^iW=NWna?8uSwSi1ZPs_!hVgpXvz z6t~BIsHFM-Vf6Ji@|^MRH!u5Wk=0ULSBhqPcwug8YFJ&?d{YQge~gU8*6-@%@X}a4Mc(XymyJgriXAAj7qQY=|d0Qr1qV@I_s!AV$j8=cYCsMmY>aM$O6(A&PF+aGC|_B^s{^BkSVKYk5s zQM2a1O<3X+{eAU+xk&1+{e3B}TWyrE#&hiQ%B$V}3BQ;~Q}rM+8x14u{m#%@^vK;G z_MrRwyKR6-@zQjUGQ1*Vp-M9~@ko6t{)_WwygU;nND4tc;lTGu&=*?mF028VSn~`NUm+BgvZ)0A;0ty zf#thiUcn$R9mn6m)x(@Dpfp=es~K!M@AZ*GKGC&)*|mX_`L))VS-Jz+WbDVn&%|sy zcRx}jYPQV&Z?R2qigl(k+-ZjTdMWwEw!+LdiiFBhpX}T24u9q z4*nOd0|o-q^KKg(2K3wq|H8O3%9yW>{Uh9wV7b^D2m7|GFV!r%onBnN-?@dG8y_MX zs$b~>3?7`V)I?Zf5BAUWw#+gO9gX`D>!;L@Hf(fHJHqoIwvAeLdeqC7bHm1V^BSz2 zK1v~Dfpn1>yRmFT^oe+rJs2ZlB>aOzZh5$sf^}{#+0#yXXly-%{Ue(8_7%=9wfQ#N zP+V?}R^#Rxtbbb_dX-d^ig(>nCLcZu)yiDB7SHl%R$m&yfbpprM#i;7wYOhw)j@-! zS>?+GN%{E?qal!AoxDDpY~b5RXy#+j<8&tY9_Y5vxVzYTI7$rL2}Sfs`P%Zw}EaqfeB5je-0j$}+sSl7=%T?Z2BQfISo3a zaXqA0JA$GEP&Tk(xX77J>ZL>?ICCy)4$j~3f)+O803M#40C^vJ zsu1^MPGkwp+xIo|i&hHec_Lf)nzbt$n^M94UZNp+2OC^4)2Ua#+cQ7P*Y{+&o?ii; zRPsf=TyH8Dj`I+SI1yjZXb>*Z-<d+mZfFe zrY^ZRi4Z4tb7>$K=dT~zn*|k1EghYEZRcydmD_yc2vL?K^VqFUX`NnLZZMM#<360l z(QnD>myrD7S~L_1_D`ZVOTLU05zN^~>nQEuYgV?gIi4;^A%z|wk{U#AszzJk6c2{r z+)i0-jTB=Zwn&zEXPU{GZP|ZXx~&d;BAb~?dW-7N&t-87i5mtzee$W7qbdA()8Y2p z^h+cSZHc^?0WH(mym&@~xZhqN>-d;r_LZ%c^>%Gbo$(088M#Pt6|^`~NnW>FL30xu z%1g%+Nc%c`AVEAb(7dIFFnlg{_oqpioj}ygF8nCU>T*U<)3rq2!(lKEdgIbI#lBTx z+f@klsL=jp4_$Hqt5+_4`O>M9;2lSqoF@)~oXtNR?!Bq2f4@-vJKVy}zQm2>PH-Bp zp}wq4ji>@r+^85sWIdDInCiB5n7F}EJh46|oa-%eA}c(9vF&y0%+(B$Q6G-2T<0PO zd^D3OC@*}&Ignts5Nl=4b029@|1c^GG<5PQLDA4yQ7g&?1k5O~ejV_|4(h_28`O4h z08Flw)n95{G09F~u-j$^q}U!ue|I-6 zG6nx9!!aC%O0Y{ItThv5go&f}Zg!^xgs;YmJudabX^$z8R(h=I_3rel7Zzy`2iSAN)+@wTENN*6aSerwBP^-DR?)S*QyY^4sUE-_$OGwsTmc zZ}pJ6DKX+x$8}3b|cXWM&1y&hHTB_7KiyGRTGnrgTZ)R;OcmD zDaR#+uh^rOW?7U&n?c9feZ4irRdxjUJS@c?Np${PxC%oYZ722~49)!N;e-fjlxwz# zlo~Mc7ZzmED(eTyA;4ElLXgP4!Rtp2nAo|kYy$H_tl2;fvra+~8nY12pJ6VJ7oXog z#eYTtO27DtXw!d~*_&nSfOg4m=Mzju=ZU|4VTt*4{R!o!XS4;N#%v^kJ4$;B`qcq? zjN=&{CNIn|O zkdB?l_`64WdUa#sq%W0|>(P0c&Mi4O-Zh{zmQ)wwHjKy~PMhmpo%M*Gf>~G$v@7%T zAE%b--s6Llqm>a6=3ba0!{0F^#avnreTYQ|qA0NoYpRmMAm#!Gj3Vz`Wb}o|>T9E0 zV=JB_91H9-&XSqz4vHbo#sNqEGq6*VEN+!ArbZ?j_&Du1SX&A8CNF=`)Pblv=Ew== zkR`>xSOB2EH{f$b1E?>HC6FPClw8_4k3{lm$Bje|)^=4>n_1-1B%di0f6qV|t*w&R z5ABY`Ur;iZKbY+j!#HBi^34@iuv=#oG29o(Eiuy_&65n2=g>biX-H7W(j$U=(@20* z${YR_FOeNBS4-X#YPc^vSIk=3?SA}ujo`h?P{~ByYiAJzO8u->wU-Y1DaQb_BD-H( zTtl$6T=?Oem5S~Pd;YFSkB6_8Lm#*3m%GS&f}v`XPO7|n-(19U?@qiAPJDkxSe@%Y z^a@LxgV)w7GfJVRE*H9V%5-E5{O)P{ZO;#9tMwlO4cexD1rKX%<--#`iLIIs57X?F;PB99KciumKh>CJIcBR>Dz6(-xcfX3Z`GcdSt$pY^V^A?Y7r!r{K2xkdSEkpz z)__e8y`RBX6pugLX<`DA4;tha*CU1$(*@#%5A;!UPcLT-5l$MxwFp;@BNa1DcuQ_O z`y_}@kAmWMoX8i`ZFsJMETVn42>c_sJ?%1|^TC|`v8f~=reRrzdm}WodEx*gj_B0y z=9dmtkwCvOhyUA`|K4(kCH}C9Umf7S*tNhXeqnT%9ftAmmLXpR7Jtj};Vx#8wKrl< zM}AGgOamqQ3;qB6fI5M!V_0U7h5wHH9`nmiu5h%PzNmly0egCqy*C_FEBM|$0!Ar1 z`jb26>c+`E>W%gwSrg8%%H>h!0mYsdfm0Nf^ejb*NLM`PABS{k0O#TMj*s-!57Vg3 zi3pY{3*_!Y_Q|%E;Jtv1#q~Z-K*)Iq(|WkzLpOmp{H6bjP|1bpe~-sMM_nzwG)nwW zJAM-sIY+(wpTq5xiGGE7dMa_^cOw%GLhcw3DWP75E1aH0X`A8?X;sp4erlLRAt8?~gF7^P%gx0n}2mWsF%3&>72 zd|^ha^pKR)hFI`%0lr`<6j^C(3ExSpQBrxS*p}JHi|SIn%E#}Pvdx-5YPx=HVB&I- z9-?1<^`zrwPNalu*B05upE1wBZaC;0YdUspq}XpB03NBRi2l$k!Q(k>ehj)@BE)_( zF{Ud5v|`8!q_U#qJOG>#+-7N_C-gN;UU>tOaXAAqFdzJ%t;v0jk}=my9IToPeUj9E zviqJph!1C^I8GIlBC=fkOY^EP2jHyW2S@UU!Xeur@J1%sJH_3TSG7sj-JOR?t1RhC zJD-f_2gf7{Bz|IhjwqIuIAF=K9nK^GR(aH9 zHL5y0i+VpNR1w!{5(v=w$co|5jxtWlR=aJ87?JoH5lougot)70^)c&3{`s{0g3bG8RS@n1`gJ0D@juU}wp*R{o=z~pw51Aabxv-V1ll|U3Za4{z{ssr)o+m_L{ z8M_hk*Er~Y10*ze^9+w?v+z5a=ku-*`hNl{kYPXMRaSZi#AkFC=JiSM(;`pu4IUj^ zBpvRHSsyx?g;&T>%I)Gq=GET;DN-``X6_(sqx0)y3t3&hzS_MvEj}qyQ=7n6H=P&% zI@Rcps0iWk2i4u2f_eX867(Edu{!FPou;2+@7BP@>l^2VZ(nvAzH#g2TS-}$ReqIq z>5QFU&$6LmYXsOcevfllc*mrSN7sq39o_8A@v4^k3>cv0=qHX67+GCEfIw()VWpuQt&T878x z@zLn~$1`{MkYHNl-Z#HFn~e2pqKQD%yEU_K`Zm;?vo-ux+cf!yjjSvFZH>OKl?GF= zObck)nYzg!DaFh}W7%yX1C5IhUKt!Tq1@M%^wbytuonh zC4|FvmVNaHt+lqpRN>meg%-gGs?}*QqGnPz4n0xdwXVopfg4>>wMnTv7!0Sj9kO|D zw%cDl9Jpa)*MtPTL#QIIddxJAZkAhJvdKDbZT>V^Kdm(nCcs|_*MaWXRupWUsa~0H zsvK)I11UqH5a~WE+Mk472=M_kQq8oruRP$!Bjt7r?d>j5JA-BLaN_;=u!w3 zBQtoYKW3~5rfzWx4wJ!j$1WG+4i><{Vc4*qoBgc^0Y(?z_F)52p#Vbz>bArBpZY?b zN6!!w5sBn=agW~40YHaqtuZ93BLy-4qt z_-Fm`qL9xC#bCgMY@hDT;Pj3dTlxat^1O=z>Rjede{38eYl% z=1gs0@$gdzW4$TYf-D`DZZ`c=RI}>lvOePXu{D^ylsA-}H_wQ| z*nXH5r70{wwxy*>FVvq?lKaGaiIT_+@2$Vx- z8JIp~_smPOnZx}biW*&Wo`)$DhGJN(13ZJv7I|`xbh?7kh>aQe1}5U(rXBTrn*;wj zc7kIMj}&hYYqvp4ZuFTS^4$EDktgjpS{kQ%Ql-gwi+k%y$N0?4(GUy;R>!l2O*Ydb=|awE)~kI zHj*}Vo0aDGJ0H5L)?4j!udXOnD_{f)HGM!IlUSWJJ`9^V+R^QXiPAex&UeXX3+;-| za8}UesO;WBj_kxn(T^vAW6Gb{SXR}X=$9rizI;7i@9qgcn@Me9ICQ5)K=#p4aRMxiPumW_PJPK^mqvo3)i}j#-WM0rRPhj z{5a&zP`Z{)xBW&M9gW|h(Rm%NYX1Z|!H>9}WSLYV??P*SG?XUooP)E?=DO&kqWVf+ zmR9#Lf5%zBBZMzvkAUhdq~*vtQVl+g<7usmx?78*>IpkaX-oPJyLn-g+tPe?O4bUl z2yL&e;nTmsth7@$Ss%>Ro6`;o=EdMe-u>$nJxV5m{@9dvQE0Y%5$(}G@%Wrftc4%Y z$nim&X?uL3V^bnLw?#U=A;%V*s<^Y#274eXD9*!@S0|ql>Id#~DGnXxPTz7?UY0P8 z&6Jwkb~v4>rt^G56e#;+Mo-QNh*N7$TK$?>mD~Kju^AscGQ52DW~j^Vr_U*BhoG)J z+c*4AX9Sfew!K=EIthIaO1f1%jpL==xNowax&NruKHs>L3A=*FOw|h@#GV#;VT^e6 zh)0k~dz?&croM7sXXfd+V{GpTqh#mzEn?%X;on+kcjIz z%zt<>5%5+)NW<_T7FO^@?e)!sYLfKah{gNz_HS^yprQ?$&-SnnAD-qhEB7iptZav;rp7L+k#%CR0pexKiOu zAFo;wmGF(i$6nm<2XJejk&Z)Ua^6q3J9*G-M$X@C zWpmh+^?o*b(Wo7f_IUP&D8PpCTX@4V(DTMP3SJ~6np^#iR?R-#w!pe%#>4F~ z=feu_F2%q?d(-{9e41g*UuFIkb31#Q>>sj9Dx}?M-=;Y_pgem-&&v)0u8GOG~yw90x*b$9uXFNA_>pcyfIP#6A5cnk4YU_>LT$BEDg=x}hD^cF;v5Pw$GC$7+s2vG zOu0}f@|9uGjv@ZhHhYSJ2RFTVMB_bF%3;#{HTJ9az4 z+q=uD3qmd7it~ln#9?uoMmcLgn)tR{- zI|*y>M#b-!M70zPT#AT}@Jp!8t9iT&eXIoJK2?8DMLGi zFQ>W1jb+$HYI9|<%QjAyP_-62z6WLZd<`o3vu9&99ZV*7(L(T+HGV()%OOLir!6z# z-E!(T|B}eh9FQfCO!^c;q1T!B^MeJ#I&%GW}v825>mkY|0lu{9PqmK|yKYZn z8td^j_xCmN&RA3UrEblVZ>n!2Z-UARC!6^cuI%^K1L(q@)y{M%7WVRuuH-ON;VC>(TqK>T*oYY8C{MS4LKuim}=h3N|MuvsNm3heOLf{r)RvZ+z!lv<5r*nbo%du@;`3}h9)N@DRHvDw6YS-(CmUr=Z zMO;}&P-~5Kt_Yjf;9b3gCtz%PF=}~R51(l?+b@bXeJQfJW@j~y)ahz`yrR18qY@r# zi=k!!<~En4VE^bYV13^|u$S7_cJw1ZjO}#)V<@Mk#x^ilmOwF#PMBTL@TJ+n40Kr4 zyBYMZkgWhh2=42}$)WgtXkp{|3Gc;j?myZPJEqi=o^^~8hMPWm-2AIpZT%tb_T`Dx z;v!4&s8ITM^PfP;=`$FDw=}G2^qgAfhaIxHHF<%11=zMFB$>ZRUO*2wc?}XSnB)s{ zZy581Lx&BnS=z~Bl+9X#wH>+eBD}w@pRcu4mU62_8}ub4Nl<$2@^2;7<)BL9Emei^ zcI<%daf0Y;iuEC(KkL}*dQHfO?5I|%?a{|J$7>uJl9zpgR?>V*0AAx*=Fd#1gOh+R zy-WIX*S_5o&11FZn=Ww8Ni1}EYs=jkj{A_0F6Lw*2Fqef9+~O1_ad7ctqwKThw^Z< z&my{pB9)xRKny+W=0%DZX>RLG<`mAMYn$Cv9@^UNek>BGV*8VR|!~``N5U@VTCwTrf!uy zf#cS2EdFLe{1l-)5D89*Uuf?$pwZ87`mOXUjpnt)?SxKU_?QyFzLz56E{qWpA%D8x zHay2Jd{wwEuEezNpB#(7)p6e({&XVvZs8O^D0m3OegjS5u(h-1VZgaS<^( z#+Nqc;3+VpON$U-fI&%%*~n$mr1h@tMa7ckZ}SscV^BZtb(|DF<-bwtO>)`SvF89Mt=Fr0q! zc`M?$gx1@>;G%qO%eIEUWjJlkP)TZ={!9?M8UN=9DC6__g|!ZM%FO4{zK*P`c}6WZ z`FA38$@#D7syrrVR1~eMDV{H0u4Dm5tJZ;{l=C$|ZU?T}rK^qVHB|McBLr6T#*0MY zl!87~W+wAK39PfoT0FbyrgYnydyc#6LLe& zzwPM5{&#VD1kwyR`Y@&PYtGnVYfRS2tcDl$z_k%jG$8tUCObf{s=qGkt-|a7(5-`$ zX_1+p{m6DLFIe(2SaC5mML{Y}t})+V{$6D3*F?Uk;NwhFtzePAqZ)>uNH0uyf)lA4ag9t3qx1G8t`{`EP>#l3 zCKbu!gz4vrq9dmq-u3O+WGhI8cy4h_SQz^0_kV<~#ZLApX~Y(-R^8!h;iKoxk(mgJ z(d6QxC&A-*=J}djI<*5Ft!1chO`R|Pq`vYbz)p3e?K-N}yIFf)?2UyYI)Qg9@YgH? z0bnkM2Z9lYR`Y#te-jfBhxBua(hrZbE)F3y{Fm-D}jUM(y$duuoF!W z!Hdb@>qnTOdsFH(#W2Z8wRBdcFJ$ruwIbhS zbZ!HA2?c8Df*~o%phedl|Id!#yF--}@*_y(1^>?|RD^HUIr*+f5$LE0r)e@oueqQW z-VQwbu95R$b`JD0tCQhupx|`TD=WkA4q4&=6!IQl_$P%t7bu!Lb z6(sT<%nt{-UXO67w?DFA%lQMj7*Yri6>x`FU(xj4TnmSls0I!Mf127~vL=u9i~UCU z`09)(3#lEtu5D2wB~Ij+UgAcU%+1aH>W1xGGW&4oxV`l?ij7o>rHOCn>mhwFQnLZowzX zUyXgnSvGu5MchQXV8uI@BfO@_OcXt-Mz~``w0Co!^fJU?`xqyjE+`bKIgGw=d6}^8 zaCY67udQG~*F{Wo79Vb@ytjQi2soy{%d2$iwP{g zk(k%8B|!ez;`e2%7%NE5r-17J3G%-mWzP={4b5(C^)VJLV?uA7*&e?Xbf{gH>%0Qj zwmnuOwl6G-cvsQdX+;+S=MPbW=f{YSeS<{5OXrK0-v=cBgs1R{!}ERqpIBYDixam2 zz=dQROs$UWy-m!nT_ZzZ@(1$|_aUYGjv%rE1lvfZ4zng(hxz>LniI!o+qho>$XvwJ#Wn?jJ+MQ zYD>vzk7+UG=%m*kNf3A{nO?+sy>%jS)a)Q^rHX1r`#-)+QdU3l)5*~s6fxr;$e8Nx zP zwvojC%vS@lkYZKFunzYVjR8(jw~g5;4C_DIwKuc+C#X}MEWjjP_ogOL#kd&$H4q9! zG}VIj3+|BiOHox<76bk7W5|I8y>T;C=zYiSe+fnqFH%8Ao0lIALP1{LU-yOT3X^Ue^Pf(^+URR77&X|(C4Vd)Y%Rgkku-^0<^<)KjvERMG zC&l~GA&^XereV$uPTA&>REMv2)YkTkTy2&Z(G-l*jt_kUTjS$-hkvM5CL%-n6)(a} zmhfmQ`!_OrLWi+%y5)DX+p_)r&qL-sa=y>_xp4)@w%U{Jb8c~R{`%xGg;kNZIJBhB zTQ&GR;BS~^w0o!)C<)WdG4hpO4ipe8&+l8$Rdi!o3?>W!NYIe&{8D5>Nih8>VX-4v zN6HCNwWB3BMoz=T6kZlUTy&7ZC64u9KE?9A4d`LHO;s*=2vAOmN8immJD=HaM`rwDP%J!6n-1& zO?mTrd5$#XwxWu-d+m_z{GiwLb6JlbU!r)uKMfd4^WcejzY5 zP66tq=V285?ApR|^3$n6SHp2z_Z}3dW(}T7ZWnF&;cw)upfhP#;LL)RF%D z&K&!^3)NxE;5t^<^e@)eBIJ5&X(=Ky8m~l#8+0Rhd$#{d2wv=kBoooLEY?Y z7lbhu=VU_68>3ELkROZ+ELI`;oDjY?dpbUEYAzXwe{dWSV?V#g)ZgJ47(kC+{lm0e z(1nk|h9^2X;a3^1!;W=9&52OR6(!xWvBwn7=n%tgF?c0)SHF>{{vWRgK4a9D8h(r* zpweqr7wd808RD@uHIrk;12F={eV|w zFpAgC9uHxnTVG&FGOjZ?UDH?*^JTNQb4!D%1i(?NzIfQ$s#o`#kFCK>1M>Bt3eYZiJLPm`ia4CiIjy4H*I264KGv3-O}&i zAOC6T1bSo5?UGbcBriebY@)DH+YDMc2s%vh{J5MiRys&(;! zs`TkP|B@R?385l$+Y%=l-b(I@N)n>7qDVp@iS$k1*Cn(IbJhdF-|*vdv#B;|hW-+x z9Zf%t&Taav#01CUCW7M~6z0}zr!`}7&;1eDPe}DeGJbUL)v=IdSg~K{(41bKYc`qh zOU!T@wFy+3S8ldEOp5u543-U(;l%H%iEl6Q*tK4B$?3a?T;XQfxY;7f5QKM97*utudFGCGur1NLB8Q4F{Sg*xmCC zoVMIR1?h`jOp0lG=p$L!K;do^q;9u~e4uIy@h{KhCwb0&^!ScD5byZyAY>rN*AesK z-Zwe(5-MxHroE{QqH&V;T_c^YWcA!0lNn*l&nSIwb+iI)xCnu(3T^4XnlWS-;6kBJ zEjO17^hNcs80$sfC?{}@lFg;tAiA7owfjUkNr$269!t8tukcnYRd6wxz)Vd7h=;G3 zLVFOp@Ij~{RUeGQqbw&S$-i{`sJ%gyA4eXRXyR7-@-w!P)q*3vlbWK-fqG@_TP0dki(=d?*4&bEtVWfTePmt zOZ*VVCqOY;Ga`?gB}d+Xynhh*d#ZG%`eYg$x4^lPOn3-q=n#f2C7NpdrxLCQ@}4J5 z{QPf~e>EXxsz~JY9k_`pmLmTqnd)ph2XoSbD(CF3d^l4Hpvn^xg?w-ycgRLx=YU{c zYMEO6-mi}J=4pwo6eXADZKXNh$j2CEwq+kX7_Ld6fOX8rH z{tFpwBtB|+<-tXfmwx&`O^mG?sx--5j>i|$=bGl8Y-XB5(;MXLGOLCpcAV#pLcM2> zWV8mYzmFqlCNZ*JM8mt8gi@>Hr4u%Np*XtyAxj7rdR?hLv)>QfJyBFml7(9HH1ECY!^r>{P z-E&gj$fK29fC%TP@p)-w%{%@$S|fgPk}B7f|Jw$U^Tr|}7V0z*Zh66mGT!n*^o&)o zX8)+QF6#v@VNq6N{df*aY=aXg$+kOVgsuLKj$@bUen?21z%om(doLz@BD~hj>2#T z#Zf~8qcU;mdgPo`x!q}_SKfBLMRNCUZUM%fw$H|Q4tB(}hrcFMNLYDOZ+8eu1)0qcAUm}j2V;UH%1(oN#Crr;oNS7 zQ|ndKaN3MC-Yi}91TKCQ<1qT@zqAmp*r=9ZAO%Pa^6#`hxYD{} zweowq?2Gn{*e+PcbKb&vZ#seopzi+c@otQ|$TLfT-QM$q_aOr|P^V|A^oSZ^>o?Ug zRem{Lzuz4){8qvbRl5=Z`gSdXv9^nraCYM{H8-!)881)F=W&IfKk|I`#YemhNKE;D zVk|r7lUj6$d2Xrp@2qbn0+bAT6w()4=!^^8<{?tJ1)p;<97>s;V{vXCi zpFXjzqhy>SLDt`nRLY#)twI{K?8D~I*=17a=dFs!fD4ybjAzazPx?hbVcr>@@${2a zW<&8lhk83-k8&*Kgo>p`wBr4 z6*RFZM$XqE#jP62%w2RZrwDQ@qSQal2sU|LU|up@*D%%x>nFa~GMIKAvTaK(Q9nMP zN)xBaXEAcJW-LaE-o5h?da!d!!AR|KXk!JrpVh+c(X9Gu1EI6mwTL~Jn;|b!Su>*m zs09eGzivBz+_8tNJU@uuy)qY^_IsH!6D=lcE&g*gTi(lA#Qs2Vv z4bCg zXiQ5b#g+M%lUrXuPB+y04@T4Zb8}`^c%A!}Q`iR%?cV%44W#?p-Kb`8ntP*z8#wUI zNyx(YFrJ=Y%atvvLQgI|PF9KbLy9FBrMxDi7msFw%Z6K9S;OVB+rIU^TJvKuebcp{ zLsjz`{Q+aW-+xH_;eRFmxB!Xbe+%}(Or^UFpjC+*CQD7M0A|&^++Bg9y)4>2yGt(D zy>8T`UFK2h4vU}gm3J2nsH6gJTT;Wu1y957fO4;XydN|WD=i{ZC5tMdyxX6#m+t#! zR1{ymI6Ydmxn#%T-hy3%*Y#y)govz8ij zd|rtvK=p7Q1N(0!`-3c(+i!h0H0vMNsplmar^>j$<|yqPTEF4&(0l5j%~v-yhkSla zDJO_LiEQ`L!(;vz$^HGkWl{Ydth|M@W54og$aM!gWh(-`aL~Cf@%PR}5D_bIIWEPu z07qc<(XqrAHW6GqPco>TVb5uC=~7DBML{))ST*@IZnx4OGHN+FR|7k}gk5&M0%-BI zB32$kjCzU5EvXv8Y<-(I8UiAVBBD|rXr~j+x%Qir6XCW#Mzj+pB0JiQ9!CGIc{8*{ zyKL_h5vwS)f8D2WT~ZR*bDiCEgs=IQB@roF7QM=!4z95I!;Qsm%+tK}wk_B1EOK>> z)7v|HeBrvFV@)0oQCPzyg?i3fk|tG6mm@E0ko%+X-j|TE>^Y;uUsr+Ty5Rg*L+Lb} zA?o%0hnwH(cF6bDlsHM4rv6mz5t>Qc(@8=<#qyec)IQALFs=aD9pDKsTD_dtogWXS z5ukh4Rd3zCX5Lu0F463f{x55TA8Bm_o$>hE?rnu(c`-F_qyHgnjMj{@%fCp65%T>p z>7!0@?Fq)SbiTN2m2%PKrs&2^g?!J#u&|nt784{8i!+(nR&<#=8w@Xt`e;0IpEL^w z+e_TTi|9D59mZhtb;<8_su^E7lx^r&=CWyAt2m#cm&+%_RI{eX9cT39_^ok=a9`6J z)@VBNH$J^xK{~uhHWtULgXG&PorAsaA?KvCo>?9l+4bXtiWxtox7?)bVJ7)wTKyOS zTLnbj!{gASPa0WDog|3}HS=G6(Fb$g``7mMS(}^!W}D-8TA*lYhhXaFirnZ;x!a7B zWtmFR*anaMV}U!l2?BQ{sE~Hs*7DE1o zddVp{L%c{*EwHW<{tszy8B|BN^nH_%V8Md>Cb+vh1PSi$5Zv7%xJz(%*93QWcX!*k zyS_Wgb)Ea1bHC?2Pt{XJ?GLkeF*9rR>goQifA=&GE;CDC2%1xJ_kv|_q9dZ4cB=gd zO)H?bln^7k`>zO}b?Ep%NYQ=1S9E?Q+L!=b`1TOTvN~?ywtUM?1Us4uynhm0QAYMt z1NRp~V-Y4kUk_c=u~g*@X#XN`czd3*LOj2pXTK(bllI7Ero_{yO}vu%BR3%461U2W zjM1pp=I$DI+rH@lGO~uN=aH9~^F>w3@)6JLyK~$o1m_#OXcfdA5u*tj9=noo?!3UI zNK1PZ?YwHz@ArqTJx+udMdov7FcBo#HV9VkT45{H$87SJUffLoVRMD7_vGg|>E@T#+OJ3gQ~@G_%)e!pb99a`apTG2ap-XnTb)5#PG}?hPy&)BhlSyX zvr`y5q;e~EFY<~X-HQAdCLP+8lF5oTnoJ6l8T1K8xn}L8Rr}Ks@00926OBMIe(f>qbH1GvP4$1SzSedOb<_I?PV$! z;bA`}?E?I?Y6|!X)cu7|I2Y8XAs{*$PoW)t@4u?!Emwqio#9uK$Be9ALJr_k>RFkS z!r0<0#os5~cno{zxZths;nh9=hy4$aD(dB_(X*Y^vW$bS)1O_pvMl){M*FsD<-1rR zp^s^Y-y0i@egE6$N*C0TLwO0im9G)={@08;Wt+3(y1j*3|2WZs(nNi}y6f?US&4-j zh7d^A4;GcilT#jAX2TnIJN9^@H+j3xEX0IV6;)gb%|Y*WNvJ*ztbOR26}8i(Cym70 zk#U4BdrlFs+Sm-VnpCd~zs9^AsPE%T$V+8xx~aTXSUA(J{7(r?Yfd{x# z982SdCf$7(MReddQ223Tx7*k)i74sGGpdycYKlxNPbhyMEIePBf`X!(5Kn~I{h0De zM;*oG^qKHfD_#@uj{l+g4~C_S@9yrF(bD3%^0jRno|hS_fnzCRw5~L&zr^J!MTky4 zY}4zLDRE*`o6)C3wj`#1eBGUWb+mucX~R8Q`y9uuf&1{Nvu+h|5y=Rvd}CePuzA?w zPCs80cyal~diJHGoEeL<3$~!Bqk6+qQ-i!O?E$`4V@~J#Qg8`wr_S3E_U09GajR4- zEtodq;XC8;mXwAyigG|xJfS+S$>jHlwByH!&3nG4)bKZ5H5G*6Y&k7iiwmkP@T@1G zAz{Ig1>5)gizkEb2n^J}5YOoL%0^*S(1>XbDxq!&6vbUB{!|AQikN0mAX)!aN&<@a zI>_x^JXGt0IU7(0+CV^yUI5XLKA2S8Fn_<1M!e-$fb{2Y%6B8)H3bpjkWj^Nc)|*z zY1CT09L^Cm1P%`5jRURIDOJae%au;@Hbr$=M@gmPEpSFnltU&BC21WGYcg{gd*Uq( z$mpr(mtWNnMpQX*dJI($BoY0xWb(j&&+P9Lb#4o+!X(@z(RdDwj;7zd*v>*`bLti| zrfq>}pZj_-f&w(=KQ76KjytORNA>sVDLaQGV~1oap7?sA<4;hXdxXE#)_+~N4_$cT zs3^Cnamd>HiI87A6?{T(qOMneqx(M<8g~@()E_B>4L}Nnpjr@=xv(LoW{`wT6P8Ct zMMXvKq5w(P+g`C!a^UJ-b7%0@(Rr6d;#l&QBb606Qff;H*h#|p0C6X^hFE5UY+mcq zUzM+d1pYC`!bypV7=uGYq&HL9kkQ||EMBbkouo}Ha%&rGTdQ{96t#_pZew{;i^i;<9q26JN=pb+0w?pUTJ7`9 zrLTyMJXljJ0xr9(=bTWCG|xk;UI4{fzB2<0iFBzE8sYnubQa7edQr}=A@X^gRt8HghYXYdIS`kX5t>rWsK ztGqCcS%l=@b$J;XefQY>z+#LyG*@nDGKoX*R`RM=wXlMM0Ju$G8A>$|`{8bJ%`4P? zNXzr)f&bt^8U+je{OZ*`K6Y{C>53O&%K9?#fHe@*lC;WwLxbRLOJ<*#od>GHdn0yt zwuA?*_8wc0c%HE}D{a1K?~KdK=b5Xtlb-B?mw2No^VEltw#uq*p5P^m3lkAU;jm9( zVHIA1q;hYIctK6Zmehj}PYEzYJr4kPhK+MkgcV9oQQ9wS+zPN{8s{*i^!k|l1D8pR zjIgh@`pxH;MK=O|zYPb^146MIfMA2DppM)vct+$3RRz3eQ% zggHm(=PLHad0MsoU&K5Yr5#av{i2BNJO?o`l|Q>84b+Egq#}}u4zGdp401e?+V6G!$N9LAAHBdqnJQ0&o03Q)tpJ(D%t!)S_Kx6TG z^^DK;x8o{_*uS2v^vP)BrO=#KP>({d4LpyRCP3h6@ps9`l4`x==IL zL5erymekKC79ZGA)#u|I6Z=0u7CCap80g$21D(x&gnb;+&TID@l{m#(e`Li-(oIjAg`j+kb}raR~W>wBJ5Dw*U7&Ul4BlwOh0aPU^06^vGp*1o|zF z|NGW5jnNiw$tpYMy67_X7*&jPA&0UiXlmS)5i$9F1DNEpt4*OV<`m*5EQokvVD)+7s0MT4o z?#>jrZ`kpi6QR^PcZbPh52#wXmh9(pi=-!8sNklGR@)*&sVR6~UNBtCRGN+_LA$lT zR&zd7rTJ|CGceeW^s~piiPk+~P=rBe+Bk|K^@x~I3AT2_busu@X%p|`Zdzwai@+QNHICyJ_UvFCWVACBq|V@DNiJ|BG#BdH6ZVpGkZ89hYRw6h~Y()wL0|&G5jm zBqp`((8mWZk=<{?c{)|cYk?7e+a}f8SO_cQs-%isORZi`^Rpjplgb{&w+#qcl@m2s z+FOOYMLF4unXCl(U9zV1=?)>@HYr2p7-4m~UEWVf@$>inuPH6of%6@kv(WwtamUw=WSe505( z!TKp>yFm8lUcK3&bbw!ALGc-;b3ThXK~80^t29Ztv`0uGTp?ZzQ5@hAlW{;BCdfVK?(FD z2-k!rVl&Py;z%nmx0I1clmx>{!{y!!!KA&!h_H+}$p2>uop@#QQ6I-7)FQk>(An#Sd22iR=Nd;hkS|{}qDYERpt=MTB_`f}3lO z58Z1vksn-*f7y@g9}KfL<{0}~0v_L?@Ram%*H?gbcJXb*(UaBcV;7`*BX8i%nLXai z4Pz;+eBR2Ry+_+H10+?XSs(m!LA|iY+CgOzA37V%si$(?8v&#zx1!SOb#x>j0GQ@< zthy{Z>30n0uoz2^PkIDg4utA+w8XlGV1}snBf`oRKKySKaa;NsZ|H{y8jBc%pp>&p z!lK2N_GVahAar?P)I?F4!FQvtW=)Hi9P~aDLdj=M$OAk;-1+L;=1#cL?t-gvKj*NB zi^x3zL$KSdrQY*kpNoqpN}Jaf<3$;b>EwEN9VSRdJzvt_ves?avme3difo1Sxjzg55&3V(9}-h8WyD9!sLwy!N^bT$B~T%)nQp(=sQ zqE<8)g#_W3OkbGrYSiHPxyV`h2q+Pr)SlUjSMuPJ^|m+x!0+v;vQ&Ci&rO=U-lRi5 z@PftsI3~yQqlDbBxrOhPdUrfxY@o&C3CV?;=V=EyxKxcN^oVxIK$`lu+wl_}b@tF? z#zd-_@&G{cKYYXgqi5`c)Ca|aNG(R5$q(g)y?DMd20cN9H?Ayy|vJNWZqWM=HgiEwsHXJ`+=;0+7&2H_K+CVi^17 z3L3-HwPY0R*5>kSIc>_zs{J^qgZF~0o5>2~lO_J-W7gM>3P`J+OcN*evyE4F{E4j? zx?!z)vV^Kp7$I6N(Fj!#MA7xEwBY-YovD6rk$hp+qw z=s`1Q|4Q0hzL&of{Dop2jO z;u&C7=L$mmdf>zMXu$8M+dK-%HOVEU#SN}{tXdz7mS3llmmk|%=QZw;9pe@?D)|w6 zjTA18gbSg~eEq+h&*aTy>_nc%dhSquCVs-hTdPHM8wI*MmZu(cv_jd>LfGMmUJma$ zfQlV4wgp?_dV4Le*f)k@S=+-oZ8YiKbd~InTDbe+)&I_#VFi(1CV4>4*s9k&5KRH}qaY)$gr*CHhQFEZ{zV|suK7n`6w z$rPW#T`$Ml61Qyk{^|8-#mQcCCh6?;l)bJ{``UCNx^$Hq+sS;Hp4iV15mMm8r}reK zuw6v=BgsyNlB$<|DK1G80iVGA{G#ai$g)?v6zdHf#LpOrD(`5`xQ*UFf6^Ti zu5~aFjV}dO#iM^%u^U?fE<83EoL1eQC<>_Byc$NE>+grN?wuUGRaa(B#fK;U_X(UL>MDbuyLs|_$V=~c`JD$an|I%CrQ7x!>qy3 z;(uAgy`I*&De?NTPc=xb`Wt(()K$2)8F|^J~ZA_K1yyt`(;|+ZKy*lu%Z!-68Fqw!Em%1t}AXygoiu z%CLx$S+D{U%;K;q>G$Mgytl~dUSB8Rj-kv@A%G>k!3jd2sICGG--^N>)!9@w-- zlHcn+fF?EWpVnMk1{3Z%D2+0i)EE^P$s@_9OCFvEjzL0MJ5OhLQ#*H}k-|S$6nRfa z6Kh4I*5l+EE$N|%8h*@OuRy6)i}WpA&-FGN z%4}(L$g4SpCtfLv{7S_xD=nCT?>tvZ<~uQC$1yz4#`Dr=1qgc1 zrb7fuy!Tv~z`;UO+f284s3df0`#u(}I}1F`UN8g58`(5R1QTtqfKy^L+tKn3-0u=f zpm%Qp^l#5=H!wdNZnAKV#IVzt4we`j+tGc4eEANYOYE<26CdT)Y;rgMGh=Rh!y9$a zE_^n|3>INm^`{zYZykHT%7I1HLE32y_9a_M0(b8vIgq@}Ue+cmQD zCF|*G^nrx;QH<<*CvLjNemtkh`TZy%wHb}66+5w_hw}8f${>FCv>f>67nr(ivUTJP z!Px!o1W3btNlcU{;BZI&o&pn-wgFlWztw=Hqaw*gTq-r!v7OHo7UXP@z2y+B!PyhM zW9oshk}k@xiLLi4qLiymLW*2iKDoHK09zR2hoZmoq+7am`i}7hwinBn9P92JpT-8y zuqA0RU}83P(zvv&uZAn`uA6Q;x%Xq54pvRm+OB?un`&D6aJIFtmK(C7B6#7q0Pm{1 z&sxtOl!r=&47~d69 zR8R^gtttq;fRIO{)VijfB~z+bZ`w>Lfj6A-(d@jzsVX0Y+mPMl*+o8J(O7zAF#|Tk zl~YUC>^YOjhw8iJJ9f+qPP&bb7HpzI(nGPA#?^iVg3rPt=}*;D&tM}c=2Vo#H6kyu zRo{ZjSUytQlmcs1eo|;t`Lhhh?QxJPah0-;GxW+?wJ5rSDh{Vhn|%$Ept}u(w@haD zPiv>-)IV3KdcSNS)yCU2PsaGUU{Z-+cKZppbxFzZzqvVD8X|9^FK2+FkGrZBfJfc7 z)=p-X47@0u%(uf-cb0v&c*LO>DXx_Yyc3rTh<;TZkurDQ^)qyiU7^zc>GFO$IoNBwh}U+1!sA1Hw4Hw|lnh56cM7I4AVO;7kI2 z{<`kpAKlb?6cBJ<>7<}O<+Ebmef-Dq*q8|YUq1;N$ijl?FXjCEOadC=u#-@q8pv|X zpg$SHE6Va+sQmT6K);q?b#ZY)dPiT<|1Go`@CB9#0{J622s;1IFQDG^xBDUrEW->3 zys4aD8qv``Sv)=4OQz$9Z0)kDQyk|!F5&MWWC(;yQHnyt4I2^9YishY1);2y7e*Hc zaJjO-FOlRnp~znB!>8>QA*fH~1EpjT0rc-r&BgH95x9mQwh_%&l@!VVBI<;|!HWS- z_vizuIk?tuV*Sy9&gP#{;!a;60m{a#pHeMj`Qb>&86i>vq1T2{Ivo{cawJcCv+saE zc8VZHulF`JHbh~Lz!O`{-}%2^FEO2>Y@H(Rcmh^!M<`NBB#9)Bbn4WleSkwn!DIiT z<&T>{o@Dj(jJ!SXbT*W5GnpOfZp(r2yhZqx$!ZJzwJKwFqfa5jg-WX}p16qKZ-Gmv zU9`_1!gMgA%FF8`I>Z~+vBR1(o0pf4uQW%V-_f0z8SLvJ_tiZI2^VN0T5s%l$|ns) zEMe#uA2Wa&vs@4FunEPTx7Jn*6q2KU&uil7nzmII{E@*>yqG@>XyPmxd>NRvp->Qf zva_LX%=7ki=#NPNZ*w+9Rj-*VE!DeQ>paIs#ei@l+!s(#gxzC<4Jmi;jfM@z)!AxJ z$u8pqCtNl$uBTd&Wjo?)gNUrc7sotDDiEr(rGa-+zRoVgExvu}^)dIW;MK|rwvE-0 zG1_DkAl2!T_P{v|rzL`u+E)Fgn{*||GN`I4K>s~1teUysm^eP88NA3XT6j(=h36X< z6d__N>hN*yaHhj=4m>8Jt7IVoUf)pn(r_EdyA34ndT4e|Dy$6o6H#6NEWSj|<$c1c+#fE?wnQL!BLE zdEq#$$2CS9Y>=qIHxG+vqyZ;4T`BPJ3?Zt|XUf{z;Es;%1M|M)RVM7B;fiZ;h|a<< zHa(vq{K%T5yrwZkWhV1&YV$-8-vV#fl8zw^fm*->Eo48$s(Ysh*dwSQ^QB#FN^rkjQ(@R-PQGpKrgfTba#^KSfs#@i95hfR8igYqU-F@!56r1b zy6^y;O%$=%I}K(E|9BA@tE3;a-=ElBdAg-_nzWA7a_BLl37so5QWd7s<)QEZRTrf# zkCiW1RU>F|!DRT&EY}buv46~Z_u!(h=-|qURYcKm(3jqsMcm#yAz1EWAe5+EqZgknH=$6VTTk=KxgQ2!KGQRApBsvF;KuZh z15m&A3L~!T_hRhj^-T=;S9&zJ)kMMTry3wKCSVDUvf=?L_qCV+?tyEk#f@1lQ(*yjFXB08c?dV9-_naHoEWtHZ2qP#iZP*mV*@NJIYd)q{E-PNsQt{%VC( z1vzg@E_p0#3SOckn5uuZf6FGT`FXMl#S#0P)aCxM`=W6N@4ll_uX+)8ZD95+t?MIf zDsvh-C+PJKT72ik_p78X&O$`99qYBpi}XpHCe{+2Q+tuTJ203)NAw3HM4XH*-iD+*nuYuiMlzwF~F6AILD`B ziFseQG87}5-uzUuk`P~$5_Z>!T9t(o)b#9mBEh(4$|WMHikddc1MzbcdA;ksTgBrL z0>zu$ToL_AGd9oWj}~w3@=A)5@OF{fzG8mQYhZ$xXg5IxxV!V273J-Pr4jEJy~DM{ zCtQfJa|_w)Z^f0ivQn_VR3o8fMQt<3ds;A;W=$hfLl566!TpWA) z2i1=VlKznFGCXSNHJm`jvytXVNM*rnCY((tD|ca&xtYe66*AwA?WX~aQSih~Xf>BI zZvZ89%88L^VQ8_m_O4UI2<%%j&s^>^rbw#AVUJL8=i?v`!M>W&`{i5bHXUcRP#1XY z43_{06G~M?jec(>Cm?e@@>2WD12ZrGZ77lUT#5iObU=^&axKJ^eNJ@_DV^Va2hwytu3U+BLE+0B> z%wU)6mppqU@|_gqR~gz&ZZVax7u$|ldQZ~NBP0A60aY}!&~;-8pUAb6cZk4Ifl zc^Tq!H}tD*x3?_jFk%x0ciAeZz%wZ`T0{aM>A=D)#T)_I!gYu#G5q5-o9m|A5~7p= zSW;i-QLLo0)Xpx>JG0q}N{t2O&EMT2(Au!7o~H#RuAI?+1ij9l?%`oCV~<`jCv+1* zd$Y~6E&M40(Xt6>lm6J$wo_C=qgy`4Mk{vS+o#SyWnUdY5W<{6DKCiR)vbiy^h`(8S*C{&LFqg3}%oEPY?{lrPz?1IxIv4iw?CPD3;C0e!Sbv`NoONgu=@@TH=R@RxF?mr+8hS zf{fON=+lC7RSc0_j)6|!h-G4r(GB7Mu~cA5u}>1#HB}0h7^7t7oy1Lz3eQ%A8O$e3k}BQh zCsu+U(pWm}_buh&j<|HN_IxG0-EK`3dw?BwS1-!rlhqNB0kj1LcZ99IZiVJOk+h|w znlB(+JX;xTn$Q9-EjZcNR(%aG2#ECIQW!)QP@mC)P7^AM(pW&v2tJDD)^*;S(cBv9 z>}3{`NNB?pgcO4{M(`Yv+q))*vY%PLSG)n7bvcO7TQBJj-fHtXZ8e7klBRzvH^DHT zKDncPF{lVJ%LITAjfVjcDDeh!S>$eQSN94w_LiQqtpVf4be(zMRYZv!th;ja24BcgVwWo&!^ide~ z$lx<{uwf}ICpqivPRt0UkzGerhOa>C&$!#=rc$W$^iQ_+kL3zaebcgL<0}i{-jK2r zx;gN<^$uD&q1ng=R}@*L^u@_l)JlKGl{Z`gCb_X%|K0v}XvV zHGBes#)a2OHx#W}yjXr|1Ns?oQKC{8pVPoNxzq7;s33w;3r^bCJfxAbODy}eheU)e zf&1NTMRy?S!nCsD#QdtSc+IB4hmJM_$O;c7|6L_a;qfIhN()_id!$>QYYcit&BB-O zezlgsIBCiWj7-}(k?kJd&dMgw{>Ye+BJ-KElmr3WT!a=>_4{qRMnzql=D6(a_VYpd?-1jtriljUwt$mFMltuc?$d#RJ|ax`bb~ zxF&FyoHy!R>@mS(apy%G7P)gho-tb!RQlPQ0-OXHREsvoJ;PS|mI91mlY*Ddn51{> z3&|_8vqn0=@a{xNqT*2^dQ=5Y&ht0)LD5!BAf!^}81v#4l)f|FSjbFqd%H6M>qJA* zdfK(5=S`f@hs;}wXm)!1k3HMY3 zNp$l~z(SqCHYR>{_w>?{5+GW&gy!3!#-^V(H+MNx8PxZ;%c=`C8DZG%ju?4LynAB^ z8IIbM5P@r+Q<~{RV}~evi7Xlv-tF`wm@$xNW2LOXxMjYmXdSsJ(ID8f8ttSYQ?>2R zX{_OcY7!FPQWE$!Yj~ZTdIwrt7_ki+mK1L8Hif()1Z}LW#%U)bU25WeFi`=~M^;uJ zK05&V!I-R?LjS!KC{^IxO?;CW)ZgkG79}Nykd|BPmA%-+?F6#XJb^ob>eFEpl+F>wB2wE$&N1U4r8yxCNR#LSLhpN6|Tc(IkT{4+7xj-zch zMB&R58_=x}GXi=<@_oq+wzN9_N4u>r5@H0pFI=6^nJpLZIA5#dkkK`^D18$r!dfjM zJ|hJoFcflDhkKwpS{g5loD=Mvkk(tNB0)o6Lfy#7NU&sYB7gZ3MEZj;W2^*+;p`Wz z8Rlb232(bkX-k?lcmjIGyMiJI`l{zCUQt-Tdezv{Gpa7Sc1w$b@^UExg1_u&Gad~W zSJJ}b`0C{+&Co2!z7jV`T;0AmH#e)cwS{)`>Cw$%z?QWVYm@zs(Ec_*P$J6ZV7#q} zR{Reb^yjO@{Q$$K{@8yor@yQfQ+fb)jEN3qVN2vM%F|tn4{87mvgeqwD4~46dXwp_ z)97gbzy14PCt^&aAguVeV|5T!!vOSuJy_42XfSU?@`DZ}S9i9T#7Gla+o)Tj*h{-% ztU=)-u$%v3^4?^kW4>A8p^4MjtaxMlgf~W+6@P}puf9iB)Z?sxD}HL^1YP^9at_U> zf80|qIW28uo_K;7h*2T=(s#F;W3(%Tzc}xn&A%=PB)e2YI&dJg^^Wlt38eh|qztWk zff#8Klzp-Cy1oTtp%@j~v8&t3%INbD<(Z)93w*EFySK@&Pp8eUg0eJ- zMfRC2{TmbckNG8H>MrSKUuGg37$-Y|d7ns66Rxxd+3kKKsNB?h@YjbvJq_iNW1>oV zk8x}S*>SGH%(2|8)jXB*!^s(7ysjp~JHeUVZD z0L@&3B1S$@l0`1FY{eIbCe7k?Gi5ERSOZNXVyy~BcUB)WoorbKv^cIGVN7s$B&{ni z{s}h@TN(&)SwGRe?N3kF z4)z(G7e*Ve0v8JrOGjrM#3i0BbgT+EsluvIj|08F!Nsk9yw?9@ zsmtOW@s{VMf3z2{GT?J01AlDtodczcl@?NSZ-a8a`3|FveUj(qkqE^~t}^Bf)MSUu z6q`7ZXzhR2T=zDH+Clif%ZKJo#)O{3*(xf+csf8_YlQ2d)QOSuiRvPx2wu@9pf1XP z|Gc|L@Z-^GXhj`5n#R@bJo(}Sg%^dr))A=xBJhXtF-N>X_s5gd;Nt78BlDbw*5oZt zUP7c5_wSE>;&w7E?8wuKtQ*Mp5Cg?#Py4Is_bjD9}Ise=1d zztoTHnQi&6p!5Yf-RhTLOZ>5xHJIQ9z@DpDzfkLobRVYM9u)!k%1z*)-nL zXW2va3e)w{eH^`i2BTm;r8{DM6snzUkW}##h$Jt|NL~JzSSIh{=*cb4$t#Mv9 zEWw;M7)^&7DI3`hCfn?A8Z@NGGw)*^*f6_&+vg?FmK|xOgOURMwlakO-PbtCK_>Sn6C$?)aoBs+7Di$*i2zA$|xW$FtYsI%UsvupNBX(&Aq zo6K{8>#l|RtBM*qZU0tv3qseCKQ&vbwGd!p;ZzG`5%~~CKN&c2tdP4`TmA0cO4zm< zC%O;Ur$@Vpp3dM|sK!8=@hOa(EcqXK28?T)*&MIKg^xE9?ybK)HEA4gf~N+=GSUBE$8a++73?UAATO58o4BP+^1EXrEp)v zf@LB#Y^bJd0<3#}B3O$k@EY+rC)G(;BRJh0Z^-m?aXsp=947488XAFfa9HF84p1v5 zZ8b!po{uXyM}hC;I3P6Il>RHw$`A+gW<27ZqQgon(vRtGF^>J9u^|57^MQT5xCs-| zsUA7-FI=T{LrI=67?`0i{y<>6dy?~#3PE;fxZ3ASNg#^_f8NB(lT$68@{K`4i4&VN z6v4ZrLq#~t?#TZ56d=(oe5$F+`s`#>&WX#`@n>$|bW_kWw=zdW@j= z(i8TkHCmId1#pbWyW5+-TyRtXnrAQ6PijT!WA<@pV(Vb(NIS!-Dt!W=iw%{Zb#G9p zcd}5;zHmQ?gg}&Ez9aq?cBC@w8@G+_6gkO5O8DEs(_=25ar7j*xO(g;$u`VnwU`<#l*kCs|?gRQlDj6~Yw zhA@@b8ZlFMoPT%busZ6)Fc3jcFOw`CY*)R{!^-|=%*nqBNB)jz5^08YB<|68)#UL2 zCsa93-D_dqN;I%*o27UDh(~#u%FN^TLV&i3nJ+nA_$*{$I;e}w7~nGQpP@m9RBUE~ z(>(gqGt1AFqL8P=`M{_|m|OVvyhlXW72!!|e9K;stV5-YqB=Oiyg8J^P;|T_J0>O-#gh&QEE!5<2eUrHKAYB zoC1F|)PykJ7qHoIWgNg`zD=IdfLBu|*|00QCwm+%UC%GRVm5B^(@9cP(&_;t&i=mgbw7v@W;T7P} z*2P`f)!p^YJ$;vCJ>|fHpz3*2=;Me4rlQdM@#{m{9DR(vZ%ST4w~mVAyn~-yy$;7E z!c0ykd$YHKy0)LgI^&=5*It!K(r;{e)@oxekGYLWXayK%e~{b7?(D)^?zgDGihvu1 z!c?TA2Ot|odYe` zNA6czd`iZcVTU!H3EV^S)fco=++ytHd!lZ?nhCrRyGWZ)`s|bpDfI`54Omi2N+_mQ zpYHRxbGC<>`hO3d#G+Ms)|zI5r~VKgFUY?eR!wl^SIntWN7CXdYZ%G93uDWqS{&_HRFt?<#B6G%zPK?}%^W}r_b zb0{1kq~{fj+LC=xnutbja3zO@z=2-n;=(quFhT?#colQN6&togp!nX=X;$HKPkgEU z;xGjF%4gh>kOERX7~@6jjT-(3nt&0$Ir}pV4hZJd?Ogn@2g2qiUgmIf%6Wp~tSRSsR7saHT)pPgU88>M8}4=TYmF;Q#X!ed}4?k01VL(RWOns8T31 z-}~e03>mJ3e4#=YHzTy@64RUJFP27c;9WBOkz5t`Oy>PTr3T-+yN5DyB%d~JL%|!j zi#D+7RIJBKBCQ8vC2a-684(rNG3^bOQ^b2%NKJU~9$p{o3~ZcYJ5uebMSKP*$)U%6c8+sM|ktl65on{|p~ztBn4e77csu=eJd1Rg(`X*)jFEMSVd<2LjiTMAZ(Q74EJ* zKasHl2PUQOg9SL`(JL<|3ZTiT@_yQZb$#tY!*=Wm%Kg6(!&&w^MK3Nmd+|XKRl0{m zJ}Wn8ZkXopSwmYiN-2w=i#bBI0wd-0031KsHepeHKlI;Vue$@s+anMD2-8@0Ixz6; ztMqD$|4Gp2_|;xUc`p1TuC!ik@MQA21Om3WW_^qm%&O|zwvje;UTbr7V?4Yo6KX}f zORm9)&@pvE?!h3-5oi`MMd5-7$(KX2ze&3z$>t-^lR6I-co!48uhu7q+X**Vb#g@> zh2h7Z=%Xlvvsg$b`M4v4yh(SirxCz_7SKf}yfOqd_4ODpk&0j_aIaT75_%sZe(hbvIEIFxbn6Hvi%a8I{kNTWX zB>^WZ)ro%9ONj;b){EGMrF$a&LmUsw>}d8_x1e2-Rc!+g$G0C6Fs>Y!WL4Q0elJ0P1nk8&jwroO0J<`mD;yhTlkU4y7 z5#3b6VMD65=D!Ngf|4YyD7R(!;cxR?rtHZgiw6o7TKu;}DC@TlMYUh}!UqTl!8jsz z<+%??_~c{$q=VnIDU~sE@Ac?_gMAea&3_<_yd(&zG5kgJEaQbcdMzTk`@o@Vp7wzi zcBM;EY{R>3pk#81iirCRxwWdlCrep-eGK@OO!ilbIhvi5Q&d)#w#qy9^*uXiSu-Xs zKjL?f7^G{e7OuxRA|R~n`mU@>j(rO-y(VO0N!lj+fDV6L(60Lh$50Xn)>5|GT zB^GpB-GT>{t|?ykO?AY7hU0fCw3#m-_(B*8`O8iHKJe#b*q-8>cj+PVzZ`_3pCV7v zO@jEgV)~zv=m)!BW7PqhWQ5->nTLgc>5+e`?7`JJrPAt17`mI7+svv_i-K0s=sQg3 z&|3?c;m3K`ODO$=zJqH2U#?+Oe3%Z-=}z_^jO2{ZYIVfx)s__Q!Mqsnz51ZqNeg3i zbgf5f;hdq73u!Jl**k;Pfw@^o>&9zDe`@)OD5_!2M_fEjWMSZh)7^0`jB7Y{XvJ+R ztStipIk}9X3Ve~Em1l&}>^r%qS>8*-j?CuA5Y=|E17F^qpQ)CPZFdAsSPsy^|1&a) z_PZ$zdpZ9L6XGmRv^Ezp&Rp4&yxH(-B>gkj3efg2c0BDdQC9*H6N~9P(&cAm2&2nMQ8-~J zJ6xW5$bkXTXgNIT9+R4(YBix-`dk9AGs^Wv_PUc^rQL5~;+#z#{rq|dMQ-%c-uChn zV@`36HM(Ewn%{~`kiY8W#VG54ZUu46T7I^fL5P-!v^4UPxhzr7t{?g~MNj_>sw zz1gLtttW}6*l&=yTi?={?eiB!y!Wp@*t(_!c zFU{2%s<{@<_G)Ee2rK!5sIzGe3QA4Z&_Ca7B7uC{=Vs>gR9N0d7?>i(M5Ul$94ITqsFCA(n}WzT*+HDKap()oL<9;(E)QNtCvV^ z%d))LIWokC&j@!*6@G~87KY;!64(3S=1XbPLtvKLOFfoOW@MNpb07@zo!vWqe2(Aa zUi9X8Ub@I*`wHc~nKPOhYbib>iw_upv6qjQJ3@*k_IT^L%-Yo2|98 z(CxOPD6KWb3yI3UQ*pqdW}b$7kdnl9GV{WH{~vW|0yG-5@F9SrTdznf+VcXN)59l2 zAp1ivV=Y7cO=dvlZc>|}-B<98mrXA=I$JDXBeb=brobyb4AyPgO)6+IOS=Z}@!s_sR<75&xiAdIBzV=hbu*|N zZd$fwa8AKCV*P)FopoH4>(=*G6h!H6Bm|LW=o;w;1*E&XYiLA7B!=#iM!LHj1`v?$ zmKtK{A>MKC?b**h&w0*!|HCjJ=4S3I*0rwh^;>I=zEe??$gcv66kk5Rbm$PS1_!R; z%P8;aH1B~c@(WV>=hdp9>8gmdZv8?y(j$X$f|oS}R{Hk~!$QO^$x8Oy6OzyGWa_Fo zmShhqgz#!e2+MjjCqO++Oi!u`Gn{kj`R47ZEPVMHit4b)GhzCNcus|sJ~q?HnI1hA zJ55UEbh7!moEc*IeF}c9sRDO#*AfaF%WgXqo;CWu3C&E4*MTIG1JBEhl6AA>f-d<922)3uMVzcMJ+0<#lgJou6mwf_ ziCo=N;`GOTxlyfKhDKsbt37omtjj7Ew3Cv%Ez7H4Uveiq-M1h1^8EyCog?xvc-96f zI8)0gp3>BvDQk0$D!iDo`mXt|!=kX5E5YIPBPEx51JT9&Z1?v3#zv2alU`UbNovpF zzC*JDmKPjn>#$@E60TSS;ODJ@v7rK+1JQ?^8RjRt&(v*I{|E5Pz>a}wzWRHm>h3`( zwkJ0&s90!-?WIs()`+z@{u4-n`kEBiSKY6cqx_Ve3cWA+YI9hr&7s1(qq<}7^QS8h z!uV_$(~+H(9GFC*`NvZ z-`SuTc`So4KbIdUZ5p!{{Iw=5w^+}K3i0E&H_~1!mK2)RNpOOM zqdDxRl#+>a0{glzF>fRPQ}JcG}JGebaPDBARP1W znDJoE8|u}3F9Cr#&s;(P#d6vMA67bt%%{A^x|t0Z&Jl3lDlcx=wr#Zpsb-yw%rRf+ zCnq8PShE`vY+R+Be3%saLoG!9b5}5hV*F(I9J}32=*-+?g2-oF*~MOwElvS?0jPJ zsOWF!U~Q_#Wk>l>=ew7v09mEJ5BxGd%!JZ&P_BR&x;%wA?Vc;eN{Sa<5tkQKX7;%9 zFnpJ)s>Yec!2Re(fyYBRu(j3qEt3ZG1O65vBqD^9x~DJ`=2afGR&_v>=aALe=V%*$ z#WaZeY05i7&GPaZzJ7QJZfm1VWzC<;#UddMTt3RRBtLK=dHpVQs)}}G`S$Fg6k{1* z#Qy1npM&OyQL7@953*CD7lRANn7g-3R?hXd<9WwpeAxM6vwm5w-48zYzPVpP4_@N5 zM^d^!P`VsYlDvVZ*jKi@f0z#_iUPbWA+q9)GSpu>6FZhOSaGD$z3;|<`?l9zUEL^U6cOC41TF%JhW$mVI=9wzL&CP&y zvfiZ;E(u2XbP6w|;vEXfXPYAz**|Z93JY4jrJH4^LwaiEY&-dt@x{m6t|KN%B*80cj)cqS*a~3uu;@AHretmEje1R`sR?-pe>DP>1GC3v{Lk}v`JHyKtf~{v-8Yngi(4*W z)8Ut3bj)a+WxlC)($M-uK!`9&t3Sy;o7lT8sn%ckkn>;pSrfFCgGW`bE;*3Ho9Aw0U&oY}gjZYD z<0@Ssk7DgG>Ekp<7%R)ppoMbAJ)h)>@|LZ4D)Y$l@zOB?a^Jluv<3yO@ma*%diH=+ ziRU4L)iI?xcw5Py3@pV&_bjrw-$(4&R#egnjgZ+rUyTU$28C@F_uDjjwid3Mm`Z#- zCy3Uc0}O7@n)nd>Ex>uo-Yr=DeI5^D{H{wz@mXg9u(Qdl^r!0kY|X0`5~G;yb;qou zFA>H_i)?S+OX=$&G#vks*SY>Fuls=PtAju9v8hhM%lgxwpKALDCpr=?-NX;I#xb9O zDZM}qAY)71%h(7toskNx%bq>ohs(ulUkCh;bdbd`!rf~GsUpi26wzxB$#3Mu9~f9!8lB5 z;m%mi95T$jl){1nDuNtqHevbdODk^zQ5f_=(e{f3f}R46dXNPhOfgOp7>4rHw$ypr zvXNQeig`J8Hi`-$y1Y>jT~#>OzjZ~_3_yxR8dgn^loFI$|#SWcXk)}Lm` z{V0H$Du|n#<7Dx^8lm)=nyCjq{~sb8qHG4OU4;%F;V5a>$mqE()NA>@Nu5H=x7_Sp81l6aA6WJ`YHZ(IoT~U{MUMOkD)v6LeDqAta-Xanffjo{DSTf@ z9WeNBuq~x}nj*(@8@|yiII?RBKK3324HhN;+~+C3M#jb-8@@|e$}aaSfHqgP4veEGeb)Y9l&m{?5anFJr z0nWZ|Z-2#n>KwEx{?-EgEB^EGIqH&~W#;bF3?3G<_0)I5x)50Z$WzfBVM&q6_HN&Q z7z)WQBw$QSjQ{_DN5pymfJZcq+gw)eZNq(f7nS@%NfN8bE$4LKz9GMTh>m1_9Nc^j zSDPwhzCO)!wfP{&3bjG6>s~0Qy4UwoQ-MA`0kHU#t z%cAaN-QHBmeBA^ps|-&h)(b48hd5{-XFS?9X5xxHh2Pp^KUlX!^G5R+t9v2}etSdxe8!S0=gem$ouE z6z4C5(wI|Uf6FNbQO5uYTq$ig(U+SvGO$NGUvjsUoW&-9b;;+`dYUi#$UolyErP@-(2;P$oknktEsxVXvd(1?h< z#zs#oKTRH0C2DG?vr5~ZHzpjQ)cJKOp?Bhv?btnQ3Wbl)=PxDlB9q8O<<5upOW%%5 zl{zmSo6w>dWGqVA)kF*b{wf?G!Pryms3?v{G}1cdA87qhkPcj9_pg!s7PVy)SZJKm zU`ciUCcuIHxP*ClVt z$H(_2z$lX_j176KLCE*7d;IZZ!^%7z4mP{}*Iy%E=p4ugz3GhzaQApNG;L?{E>>)l z+;uiuqj}eCyc1GXD|Fej44J05As}5B`XTi9-RS%!jp@VbtEPnq#jHCmhJ3@9?OC(8 zzh!usVkK6`&)bJ&7Jyi#tkR~ZVSN@L`t3*q+b?xe@po`(EzL~ZbO6B!mh zlnCWnZr(vmwxos)Uy3CxnX8Pu7+cerC>MvXXl74QEuB$M-BvQ<#b;1VRTXvw2UI^F zzVC!)uC1^LKV@r2qXSJ+XVEpH2`35OC|yKp)P&!|ngXja6;^oH>fzhqiX3;=`?DhQ z9~vr|3W`CAx}B9w<+e;it%~q@*QM=YgyQdK-vZ9qKvaTXPl|+42J4qy_6+#_rbx76 zGo-CWuix}gPZ-sN7H&9sKwoBeuJyR0w=zSU!P-%P92b-<7+4Rh;^~Nr`gqCt?#PkKoZJ`kIgG|~QYdG+{&S1=ef!8s>AM5&4I!bhq=$N`oOG<2 zG%SIW{S_^<5KRin`6#g;dQXhMsZh15KWPdb6r)r|UHMGoFt9<-E@{FszkwH~>8B6m zzCAsgpSJZ=$v}a;Ay}wP4$KuOaNM~-MMj*3&?;6HET$+;uz@J0PDMGoJo(;FD!9ng z?R4;&a52JYe$RpIbw`#RKmd{g(j?iP0ZNbJ1Kj(1bivaVttsDi#oY|g@aB;{)9*uT zHcL&-k@=FZtYTEa3QF#nwTlYwVC1#3y?8dZ&-kq$hC?xrZ#t@I+O$bpX-#QY){E)N zGLu-h5aow;6Fb621Z!IsJA2!jf}Rk6-Cv&gOz;u+uSSa+J4*bXGfJr85`VaMrptb_ zajvSyijlk0MHQ&0_cf1h*_ITOT`N-4F!AT9dg z=J+D*6Mf*RYu(!;sPhe9nEm(sO~tgUNmO>BHFhp!rH-omzUP@6;ks1mjrTav!lM}aM+?A7(@%dXNd?+(+<()eWE%=sCoOX+tmQ}Du% z{6G0UBR2=8gw2QG!sm{2_D z;69PIc~y3|rL^Hb<1f*5Ox~=&E%UZhp*Redb^V>my) zC_M!BkG~DgtHdSaU#E4j;~*xbq@p_4^@Wc=BtagX{A#cII*H+(%X`ANZxwQTRXZJ8rKPWAiL-= z8X*JqOC!ClZQ)9Pj0SWwX?{jP=dtS>h=N@GYS%NxFgG}FQ=G8?Cf0pm%51q{XtdCo z4hUa7uss&d?uaahX*`fVz)FVd85 zLFs?Z9de@C|An_;^ghuiw+nr^!AS?{zFJ_mlKRp5sjr^*jy+zTzFqxj5XX#e zDt~eh!viU@4#qZ{$i>i01@|gim&h*{8LK_T$jA@E9w2mzu&0npAHsH? z?6;jxAF6SA>0b+>urw7lFrK;Dz2O=d&Dt$vJ?iYE(M-0a-E_@ok?aiK2(ODG`7Smv ze?Ls=lsuA=LhsymV%+K%v;31kA)gW;Dtbhw^-2m$IIqce{MOCP!NadM4Pt^gN~iK z@#1oCk$(Nec0O`ZP4sxLZ)A%1VML_|a$KY7w#sQe8DUDS9BXJuFXrFw+*p?B&>EXYUq}|64IuS1o3qod zduBwZ(x{O@X9${m{hcr2d|=fX6C#P)20{rJf_}}^#MgKdA)$-rWmf@FI_@l(#4Jo_tmcBh zE$V+5>Nz*y+H$<94(eNQQGPTEwD^QYNEkMzD?280u_n0d#;t|B$Xbew^nU+xxD6Jn zf2Z$zJZPxZyT3Ihu^Nn00FyC23kNie$NfN4q%kfHysOmt()cL_iYsQ7MY)(Op_*pz zJC%g~9x+@(JDC z24_69WkK5~e#k;LohYMGfZFn2^#_KcqQ)aL9FF1kZ@db(FG2K8EfI~1DTym=qVg84 zHhP13O-0Y=pLPrlJ(TZlm~nA+Ga>~X9dj>!4zxb#&}>O5IehGRZ~MGq+bhY&?%Rqu zls$rMB)8J_d&x1-c8jpQOIy7xn%npf-t%BrZj-8u?q^VaM_k8Xxz>$1I>5w42!|H~|* z6WapbPe3%EBb>r^&87?b8N`r^syZcX*R9vwcYc|gUg6{T<00nE!=-pEvYsv#&8 zZNg#uv5qyS8)bf#{$|3Jm&~BX8&53~%e~g#tdwb$dSgZe#%)+@<;Z?rCKtZU3-oFy zN_bqn2ufCZe!{xs+&8AMpiWnrruk#b_d{BJEFUT5YHKMWXx)JZ3F;S#XrPqy=D-d6 zFnZ@PQR?%<93iTZ*$9efu%U%z2}`uO*;h!ytG8>7X6`D9uAc#gLz+=)eplz#pJLJ} zLS|!>>>MxHE-+*IyB~j$w>Mk3y12O+kpuRneDu(-1iO6Q#rkc8-Q@!&edWz^OxdOl z$KGnmrl7m^5hr`v7(HtK$-tUb?`I!4%C#hwsh%{B4EMg&4;L_-$)gSRgS zEy4S#Vm^8vN`&FiytoQ@c%l528DFMNKlmiP{VDYgdU3L3GQ9=h>GX*0e*HW}aVh^Z z%pdPO3(8up~;LWvgT6ZCDRvzCoc0nP((W$@$Qo%N5h>ks`n>{-mSZLnSNUE9c zk-A&0L6+7)#<)Z7)7@L17CwIl89q@|%b;A;9nMJVNO$3?`3~rvmNY*Q5oXaI(H$Zf z_edHDH52FGSw&v#b7mkf1tqQ0(mghwrr1#OVv(6i8Y^C?{FK;DdL$gJ#QNLtQI`Vf zFV@k$&C0fx&MG`y@K46*!?(GsDT+5V^q#xDp{rX=mjC`4ncS9tj=%hvj)ULkQp6fz z`|4C2az0Yf#NxZ#(@}kA=QgeXxtUh&K1U={_4ESpiP;`e&h4>Txt+x0bV4iU$XIm7 zBx{Vfpyu|oBt#bya~%uyx1zsKI)phBv*}v!%GX4U2CTdpDZn+DVk3WWG9>83j)7QfNU9i{Y*d`uP+ zc#G4%n^RT91hH^Rzo8%Z>I;6F@FYq4poXr|P7X5&4HcT!5ID+f?J@nQJ4Rke{uzNV z4=vlYieKixcEDbAzP;dW8@pyxTxVPRM_ooTvY*?_%0Bs&wJGTJnP+bysY1PDiW|V? zp0iyyoI7~A_-EB;vmRF{0BbcA%G)jU6IPP?Uo|QL%)jqz4iZM08wHL;Y(dNIfYL4%IVRzoXe&FWC(u7$` zZD>pTRZYkX<9%b>!a{vb)p28bgUZstJ`Bp9-xrMq4KnoC*Lf5bK~o)ed@gZ|k8+h` z$4;94>1y#~9~p;oAUi)sl=>LZrs)`*BK48)%{$jF!gcdHWtE8la`L`rX_TJ#D$JdK z&5js)diw3g<>g;ySCRw?>^wg!-_D8D1dg9@O+`57ixh3L*r{93ZcDyU0G$>LA|@LJq6KzHkl+=ZerOtuk{_I5a4Dw(Kv^R zG-@fT=uHKq^6CnePDbN|6z76_N6&#Vr|9U8mcZ6~}j>CH-3z}Wh zyy```2Uydr@6M~MNk2KE+B|r@m1driZMTRVpPyU)YAUBJ_tQd}eT6{L=Pgt+LYISu z-peZ8!n!;hj089qkUq|oL73NJe0o;Y=UDiB|2EQ?8H(Q5q)w>#&An}~*0Qe3)0aB5 z)7DdKx3J*neRD*UoX26(eV*Gee|&ClbS*6^rdMS82!SI0d*vy?sDTW|x`B7orsnL2 zw~i>Qz{c=g?bgA7iM-klm?M=`$($Ajlqd3d}O7hraFCvf0(xL6GgKO z_o6fI?J6K^jDU)F;c|vpj|bj&s|^P?Vje%P)li-v4LdoC!BhJ>uY-qQd*TY%V^F9e zP3FUcTl9XspXR6+OsWSNCcbyYO}obby*an`X9qG(a{H^5saaWB;bCJpNP@6ypzN(} z9pJ7}V2{A&?X!?DDkU7KPqY*vdgXnC{?U@m@D$?nNrS%xb)}{0bNW;0lQ9Uk)w1uX zktGcf!b9pY*kC_mV=Je(s6dpJM&0~ubeyO92yS~rt4vjHHAU$m3 z!G0CIzeH{PZvqEK@%NRcrJkmyVf)bigi-p$o$b4x)IcflXu2iWg<+c67-GKkDEihW zS$H5@4Mh3p(?qemw~U^=MZ-fE)H03w!u-Rh4UMp*|~KKSJJ_nrnjis3aqy%b`s;{{^(uH1xC4qstkIU)NV^T29Q z+Io6DFoVQ?dv@aDd9;|Mc}w1u&IEh+P*iS7eilI!uKlfPrGt%XSLUGQb^+>`U+LU% z$VFE;V_GBBlJ|;u8{tAuR@alFi(3QxHQeU^X98eMl277P%WxjmiO|5k;E^H)b>6T4Gve=4Wv zJu@CLy2VB4^*T*5ZAkBry}510P&N-RUSmMl0v{kj45HPUsdq`xTCrmXe89F;vrTC+ zS5gDkJAKAlFFFh-j(O5>-(f>^oPe12pL1@M?gwf)wtt|-D$!xyPx#QP*{bVj~xX>f*ehP8SZ#4;wpHas6dnKT%$a>8IiT$ zsj*$i&yD_}wzc7`^wI5JPssM2A1E>hmlbATM#$kYYpwo>c)(Y~6+U2HuG2>N<@X{} z-+@HuTgdajxfmux;G)FlSIol44&B)G8(Q)=M33{Bs5_=*&X#?L>@T?3iQArBq*L@l z9w45w}yR+ICIABac5lseAmm#4uBK%d(fz&Ansxmm9HDO2yH0H%6V zE)+TUw}78>TuVIcf!&q_HC`~w%7yx0->ZMaTLsX1iIQzQPvblKeOeFdi0Br_#qnG@ ze59T?>_moW@(+wf&2Kz#n%Dw~(?I*)a4arK&gUGWqxc)w*Zcv9Iu>*-Kc;IkpZNDC z_sllCgH~s^uVAal$YpyPGp8;W2J?$97e9ycKFhV38(=YdKS?1(X>!Zw^p+WvZtv4n z&=Y~NO?xapmp}~5)8z-XK4WdHEeE8%5@okcv(62Di1)?Cd*`oocj+D2W*8$NKOW4% z5Vg82Xxhwh>+*7OTipqv_I@h{=exlTUY4{Sh>{Zm2AM@kyGqV8E$c7h(!?-raPXQU zgJA2Q(@15cBY}6V6GtYItx$qzOFj|6ZTF69-l-+8=g*BhQBT~)XWx#Dt)D?48uFrv z^tzLMGj~&PylM@WV8P8+zpbzGhtC5)%eBJVG@MpRB`N##uXywX*njpmJoLbcE{}~H z8c*U82qSJypFwJIspWdxc)`3RJQe1e%VF>rB|He~knOVP{v%VH6`G+hT}w$#EZOa6 zUCj)q^DJg#NrGiZYe$xYGUFA(wq$K}S{yFMSmKAR9!Ug3C9bL)rpF!W-Xl7e0%SD) z8%=FPJPD8AU93JAY=hCZKvPrIUlsmR^%+yV19)fF#m$Xp@87P_e9<0JQs)rUgk3II z@vU(l-k-G1^0+(;P~u;{>4PUNH<~9p*X->5G-yA`X@NNf0gj$2nIqDz<@7*|8Z%Jb z{4f{OY*QI#hf)r=CaeIpwmyk&+*!Q!s(L(wFVtB9iI6g(PI6fO*wL}|jUhr$Fzl*j z9ud8mG%{GTC&Pb7CqW~axtbv=*-SX{P3M``K5FCN6T`nx{Qhnkz#S*P>~``@k==ri zfvLb0wuKihcJX$41!|EnykbCT&Io&Dd0_Ow-mE*PVg)fI+;T8SZ>FJCay}p|uZhKl zXrl=|_vmlY&*l&X?Ao8V?f9lz^3{O@*_l6l+?c(bqA*etLBZxJHCt4Vwq)Rwp6Vbr zDb*Q>_aZ6uUBxB5Fe$g-Z4JEG6GWA*4~cWsQ>B~}6PdUQoC)Oop$$z-Syfs)Sl$Z2 z$M!(4R#wsMJg!PZ}6t!b^8szH$e`eaASM=>b)T#IX%k^|a59=%bjR%_Q+pLhr z$(qUH=}tbu!>gOHhGXHRblz}bVgX=W=}XC8$LXSCNddIWcdss3QFDa%O!Zsl!x8e9N;I!q##=ESam-b{fU50c{0OYb(F$8Y}%3MFN$_x{3nUz zN?{2K+M2{&t~7r$IHHHdHdj!e98d0d$q8M@@p?93%g3KS;@WB0VWc0YS*NGe>s(ru9spDiJq2l-!8E5F{~CAmj2a_r=Wo5cd`cef3S4hh$n= zS-xxQEQdC@ylyotrLD29K;Ve}&SOk}M>7_9gbPh+`wW@&Dii_@yiI#Qyp-TO8o)X{ zH{%k!c{J8Kad|dEwFyNeVze_?%9YVwx$o+-M1`E)d~Eie9-Pzh_AfSyd6f}V{5kOY z20W|2OSaiSe3`#E5RZ>dlz#zRlk>~2U*tnJJ)-uVSY$#a&sn=Q_h2syc=&+EKi12y zKQNTrd3%l8*S&mm&5bkbvT@G)CJ`Iw!}fPE{trjQjoi_TJ%!ntsgDpgz4>Ga2bj^f zt~y29oaFB736{bmrSwa6Wk95ci}pK)B#(Y;2ZWKfoj-NY1-)yy1=T`}+yH!QGLUPp z2EIx#uDwuKk<>^!rRq}GT_uW#ksR_~f~lj?wj~o2$+Kq`8chLwu$ZTi5k6q14GuPC zDCHsoaVL#)%Ntf^HEPOp zGfF?0FdGMlc!eY<1vR|j zu(;89%cj$NUC^>L1tG#mQ`_9wc%Z)!x>3~!Tpxrb2=h$!O~X9ztUT{z;Wr)+aO=9j z=4gc>zAgy_?_3f2efU*Gk7v<~6=jTirOb)WTBq{pC-OjSGZPXZP4bZ+M0qHD{$pVe z=1$Mg16D&4==~*>+<~>LL3NT6aihPr00|FoaZgch64Fwz-|R-?-R#qy+s@y;l%XX2 zjrEQYSWkxXFRVA%oR$bt{ZLg!bSN}H?#zAEF)1}V0pc;Y~A zQzhxcW1E{1f+=xVr~NbYOF6qLxYtwApM>!`asL_porp*V(EVHNZU-W+5c0B}S0M#m z&6uK3smvJm3)lfy4N}m}o;o^q5G{i6(#RZ&h(@NWs%Pn<5DLGXbEF8>T7~^qX_j8Y z@gYW)i8uHHzOX|w)bpI8!k~)z@o%A>n3!*Q{K$*!7Zg?l7l*xEV! zSZcVA=N%)C79dF1M`vGW%cbk1!XHjCS$-1w&qp%KUwQhI5KkoHFMlQPeYb zwp+F1nNf9gza`(hOXAd&MPn|^H zMndKfcRNXz&H+sMZ#*l#wngUi#Y?z!LTJdV!1gd^??Y0{%j(#Zf%CLf{`v3;_VA=a z>zP>YTdTY4mFtFCoho?TOj`a`^^5y8A$PLHZXZ)J;l0jEj09ohcPVgGw>9N08}E_B)x7jt_^jY-JPqLtFFh9J#s0Zbb;{QC5EQ=QZqoLemR^s{0sEg5svA&5*uA#n7Iy zq@jxFr7@}EqKHl;S3HWD2zL#Vx&?REA$vF-skL86Qyg?Or@=|USqP&v{zBF?(t5LW zYZNjX?@7A87hQG!f--@5yVUf#Wi!OKJxrQjXdx5s!IIlz3}QuWSffIW=DB+#_5F2| zH?H>Ex`cdpyjU*k5wo=3j&>-M0U06BaERc0Czn7B*owkJF4^qs7jpc7D|U}hwl(4T zJcAS`aSybkzo_ftI!hE#^)!Q99#Lv7-}E7c2Pk5Bc4kpQRejpYjXEE@-pS5Q;E9y% zPj*BxhYK^DM^YS(wi9Dh0pUDRV}@PyQpk)0!}dY#XozACE23wK0Xa4r13J$BgX>Sk z%yQ&&?QQR@9N+v9Ss_q7Auuf3GhdNqAVOn-V|6iv3pM+(eChJbbrHrp3z}kYA4EjE*cS$ z`jwJHs4cOv*4HMOFo4|H&sn}|7E5(#)? zGJ7#E7nfgu>R!%6NEHU}93{}HpL?|eCM_a98NkLJ3-R%7)_ z%%Drls?JKU6((i9H!vICUCCZ<7P)&#)Bhhp92s)!j{f$x`$uJMEky-m#zn;#OTboS zv@mH^er(p4rFTD$rRS0u9UbzUX&3@^4j?-fv>&|;iB<>`-sG%5Wj1c!RPpN(5iZn* z^cEOGSty+QrO|tT@`~$8+|Mli+SQp1zJ2ruK*{6Bd=Pk?ezC5w-^}Nsfv%cCVaEoM z(RF1G9Eu4^A^fEIKA3BxVRx~t(su5kI6b33%ONE_-t+bAYxalq+`2)2s|`TT3OiF0 zo*WkXf$8VSUOPLxS+&KV2e*n`k03qHRdfA*d()iWjUV2Js)U3p8m=Ax*q8x+%Gj+0-f{iP9efYiYl5eE}WB-lPd6`#;=|@*il8(9`cdH0|O1v3-@;j@D$bCzJ9aY)kqQ| z?;7!nz+U!c`EoBSM-XHKORG}f%smL9fQuRVKe$?7110uOzBsi?8a9#0+6R2vD*+;l zvTT!S%FDea<;K`L{3I7)7(wK|`NXLVMa>}mH&p4TJt?nvwTcwQw8@v}Te)Cyg zq~%H33Gn{-{S(pO)Qc|d{PLHnK-lHIFMqrw)~{77z)n)l6Gf!f{MY4V`*!VLybtl= z4U(_j;C`-wcGf$y*7KFR8KT3l4!{370xi-DRxhlX9GjfaNr5aBh-_!ej^PKUr}9^W zY)29OCS7^>IpV=syu&$V*>PLfuOpzo;M8Q__j|FHn8?4OnR`%A$8T-iPW@5jWO<4{ zuqI|=%A~vVf3dXw_k*Du%)s?k2!Dd?|f>{dW%{+M(dRsZCG-R;Jm=b@Zt zk)T7QVx?4>%re5fD)7h_zheAGwDZcVINQMNn+GvTa?tHn^r+bT9pJ3mR_e#drnks| zj~}ZW9(xKLDaldq2XcH%RcR6-7D-yTm?4O6ndeLLi*1hg70i2rL&i<+H^Eo4CXnRK z0lLh9(o|TH-fz33SW+gpJ9ax>j8YoQ9O~WesS6ZTiS#5EL^JE!K7&m_C}P(AN9=q%rDUay?fjn*9eF8q{OUtd(`q5q`ujjaX{@ zo0oK(BeqxFT|nBVZkQQl$jg%mfYi)uDX;fNN(Z?p%Gj$asY)=cmL|9$?PR?XIe;Nl z`p8xJwr=@k-bX=0g|AgTWxxj0jW8})I0vU4TWTeGK>tLNxu#8KoxV>HKS-I z9n3|18jXP@3BDNyD=CR0Yn-8TEmxfA&K)k|th9jQ1eN!T;(aF36sclrRUE+I1CfKD zf}0x|m$#Dl?eHq5+uQxeY{%gFb}`IS(*qu8&RyYj|6a2matqVQR?EygQJ1dAcJ zG>gjUwnW4c!#*dkBDIwKh^H_;M4^1Qu-5GGjN#%IfNAQfFRjmfHF9q>5IJfw10zkp z&YbF5_w9{|{P-({+(`4RA>`<+o8o6~RY|~ji~aF=g&C9j;7YIW>rcxz1ZCQzl|P6& zZ{$6-tr_^Pv70J|H}``Ml+bS0)SdUfh-aAvanQ6AvQA{>*F=12W)hx>8BKb4k=&n< zp0e0?tbP|ht>}HO;(=174umYq(V$|S_RK#-(j8XyOYVY_qZIB}_wux|^q{rVzH*~_ zzTJl{z!M$$!tcf>e|6x6&muEkGn~wCmEOjlvg6k2hVwpfC^C)b|Z| z)o3t^GF}c9B#Y6Z{K~K4H^~YM$?=MpOS%?}FaGS(DAvZM3s;2cMjT75{E}lPS)*!J zZ)_^NS~FE3vYXD$ONXNOR%>wkY-<;XR9i5OnBE^Nl2O4lA}gY#jKn}^Jbu(|UC2x% z5r-?c{7N5i>=3~fgpIR7YSYvWtwroeG<9bm=YA6s;{@uj$*j0;+uIQ051kO{rU;SAgQ9 zZMv9>V{9Cw<;^-)@=Qal_I94vagf+ojo+TXdS#bCeNIKo9du<)@xpA&TCj!dV(r#U zQUj>(X?Okt{Y*@X!4?^%iB~&GO2(QH$pb(`7yg82X{3(E$78F_&960V)}wnmH!*GR zQ3cQ9Ff#-9fh&FC>%z>EqJ)RdM=8+0r1h0w+y6q1^KW-kWnfP=Skj|xXUlL!~( zufyswHHY#1=KAvrp5kmjiJUwIk%J%+^u0rQCB}Ve;t!Xk zzM13Zg80bncY4kfB@Lu`S3hlT8Qfp$%1P?!O%J|E;5?3WQ8W9vzUQBq67SFzjGsz$ zaPH{F*yl#^;tqwU$`C~G(rdTjL^cdzoQM}z_@qstA%+(R$6*RD$Li9WKd7K-DL#8{ zHQUS=wDDc&2iL2=^|w%1BIHUqqoQf_`-~+npg7*gYf|p3NkH$G-rJegaQQ&9hwhy)qJ#p<*%f6~nM?gwK7^`ZCBuzgTTR>` zb!jw|^)`I%d_6PphZw6a{ z8yylU4bG0(Z2~hKIT*}}rY#*QpzVBL5AllQ<37!V%IGIlSA?UDMA+(UUeGgFl)G-q zU||!JcX#bd_4aqv9Oj3)=Q+5&jIDM(XyxB#;p2yVZ1Dm`Uf1k2w2w!>2D?07HAV#G zEtDB|{U^|-wQTe1Ri@zq@)ksinoVH)=0UxTxHprpi*t33*^G!wQ?5U`-&M47cV6^{ z`Ma}eLXXw;Dq|OP(lYB1#!c6nwgHJT>yn)6ii`qH3YWM9N6)ZM?tenG%=>5dY-@z|++jb111j>VTPL}YACMTUo(z?+fG8VgAZRgu)8Q9Zn zaOHY$cD|=~1*448vpv|y_~Le${~G3I#G!&ZGO|_)55Syq%qj?}!Cn>rnDm`9pey8m zleh=;MC*9V6`yB`93ivqnD>TV<)fO5#+M@M1;#Wl(!-Z$JCh3(BU@1KBL%O!p2AJFw+LU4HsavX9v(`{p;fgbGPrH(2jM#G_|t7!FPh`bX0;C?RKg-T;^gA|_`Jz&(& ze{PQ8#thPq>94n2)WkLsBmMN|QYTvVFISVL|DS%p&YZauF7T87E5kcvH3fhslrJ47=4#r(-`ncx0FllS{>X&4R;1r?xOOSfl;nh`If^P&5>T#UD6}bocLCm)R?NpGMZxGh8f|jXDN4#Sdv3Ia zMY@`q)5}L^TE8LYz;DYYYcu{~W~&uBXcog3|@d3=_Q^BACb+_G!5CFR)FUp!sehc3ui|y3zw69N2fPJ z+L(HFD|5djZwipH^RJ^z6WWkFrCrT(sAN1nMLs_>fs{E*pRA`8WySw3oNENen8}yD zw2Pmvu@3R}Rfm~xnaj0=I|ALOC^ptBHy3JbsKU2Qp%&OXIl-hZl%u&W^>lWhViK{! zbiE>h2Mx5A7Lrv?LnKBx_U&+K;g)X-zo)2U*Hus*-JW|7vT&8U^Wn9IVB@o^pE148 zq*|D2PE2J_1YX3<+bPglh$CfiliQNdc;FI~bKkT#F!t5VGw>>lg0Tm`H1Wh>{Ul1^ z&^bL(oD;AO%hdb`C+>>p;c3Hv1kk9Xel+^LhCq7oQyhc~r9e<`=N)FWNUCK$IU-ga<>0Ox zq~(wY9|DD>*ujorh?a|+?y(L@UFSSue*F2rE{9e zP~iPMB5j;ECSwRa0(68C!=#@EPMsKUr1N%!e7%2$0kdog8bwDOY^l2bAvDmjwNaQS zL*{9Fx*qGvTK0dvDV(Y1K=V7T zh>6_wxoXP!UVS66tLv=yg4ZU1!t+TPA!us$;GWJwa?&^vCKGuo2%BHEzr zb7a(8_W5k;?iVV+pKhpq{BlS}Qz16Krd*ghq|AFe1yZuxjZLI@l$3U3=M@y{W6^J3 zw_OQed5tqAiDNZcwf#01J~V8&l5*$j>nruDCU^4(XYKd_XA-wD2E$GjyO%7(x1Zz^ zqq#Nt4s>?z{ML6)Ykq#fq{)0p=N9r*0wx%octkDI0vVL%6J-VkXrL0RmKH*UI5Q(c2 z1y>E$-~NEsYyLJOL*~p`Z30r{urirUn{#(O`H5A?%cE`3_wT$i&*D$P8WK7th5os< zpG!IGA9^)RC|%)F&xm8&lZ}&exziD|8F!SFSZ;~>YY99Z=DsJ8PrD~sLMk{L?QeRu zzUiLYX;+b;D=4HCZoJR0_Cg66dvFw}f$@@`+amRhU{d-Cs*T!)j$lZhRwZD`-^4;!o0pIyNcw6k-gsy`uIVu$19DWUt|s2h7# zz_J|Qa2cn{_m?1!EYtg!o^+|;(N{S7NVjqPwg~NagoeEcdZN`FP0ughq{sJG{)M?k z9u$tnl(aP3iA_lHJn36mdN3eCK3ECfBvIcNlONY;1pO#)7L_Nx=BW)dI(CuW#wRJy z!v~oAzYUh@U2!Uvj>@HZXai7ZueCf6I^Jv1HH@$)Ur+mPE{3PNKckOEJI_F7N#i{g z+>4)L)QTw8?VD!;ReHz1IRdh=)g8_$Kavg;P>;p=M|~VgrzLt`?cI#8p?4d1Hsu-I z9wnI?%`LAFFjy;yKnxN$%O$@e%Sy5}&qa1UPFPQ3Gm zXFWXP-LAoh#r;6^g?aQF;^>%zV3oS8<{12M<$v-EJ zB%Ynk$mrLTu&u;npS0;UR+vZ2FS!@uF+#_0=H)+w#$p(}G6SMpwl~)Fj^eT$Evd zYG4e1012c&BKX1TO<0j1W$}nRUp5k&d|kEOZ9_n@lLs%zeYIl04@VRI_+D`&;~ z`SRP#3e_VspD)Wje(;b1?OPRakPtgARzjpm=GG)QJl>d#G%{)hAjMgkexi5B$uite z%R1CoHIuqJJq?w*aIf`+d&~91OJgV1Q24@DkXz4&3`;)LjLSPDZdhZzuGlp?aEsWy zk#jqA?KRJ&br)Ecye#TehQL6kFHh_mjaM3`UaW~h*}5-ubeqZYN;0bG63clKM=GV| zj3e;im|uI;F54yHq)i)&_HtMtKL4k+aD8l6)@Uk=<%^?1s6RFX{hl8qg`*Fumm=Fw z)(-x`3N`nws=+0UW0lh@Rs&bUokplxCNQOF3t^ zEw?#Y7#)R1|B&O1qWaSIcfOPmy-X21IRgC0`Hm?30|O0JjD}#%=yz-XQpqcW9$uC< zIf4Qb#>d|zg59jha&w06)^g6O>Dx1m0(T4=V6L+Z{>ca z*?Hzj9}}+2$}2s1Mi|N9s(bMj#0;wi-KL}63Usk&wblp~y${D=5-B1+cJ~86m^pgW zul<^_{B{#Jd!rPChD&7b`4rk)*-}0`wpZ{JIL+2wdOJq-@Nj-d01?Ppdt?L2jH1JH z_w#ZMEv7&5aKAr9i$6LGX&ESHD@UeAi?{YD7q)ZaM(hQ*g4_Wm{OF=?Idd7pK=;T~)XRkv8N4^upd z$(N0VYPZlEeWH>AwizD`aK=Jtb+w#;`ZX>iHahL=NmfBfg|Xnk?v;PobM8d71qD#7 zc+f{yqaoscMjTEBZP}IM>n%H4#1!c^fOqIX8s~_^3C<&L zGe{+&zNb4BFXJMFVZDc#I(TLKf(F~efuzk#qe}fjR>hGPxuP`N!kdDagq^^ud_RNm z@L4yK=nOo5HGQP%;SAL2!_CYHX~HNR{@OSHux}hvsVq+c7e+_e*u<600sEQi8i=d6 zB=%L}V2Lf0>9(8wv@bf4qMeieO06q7(8D7PW&Y5MA6}n0DetvDe>>$mkCQj9sLFrT zfCqOTr=D07K(^lL21;xd*ZOZ(VA21dMtGv*=@$qJcP^ zyF)ox6H0L9qH&&~+kDR1hvC@_^0~}x&b){<>n;r;9?D65Py^6`r0;@VGn4N; zdS7^YI7lK=NaZk?v83}Z_ldg`2?=vo@Q$fzN_0k(?eQeU&sq}qcA@MSj4hRVdfhse zo!Z zH?k27uIG_7NXiHIC}e5Q4-gRYm$IBTn0bx`aIdf;dsnvFY-n3!g|_N+jYcQXjCygt zJxxTf36>@j**+z1bb5OX3OZLWxf3BzC%|PXg zOqE+%jil?bOreq+*!O8M$4hWMV8D*NH$K^1A}wy#B|h>BnbwCde!8P<8#Fh0#Si`I za1C@b61L3!vp9ZMPJN855U#NlKMmer6zv_6{dG&<0!a>9q|Eb}B#BlXR z;r>)OrI44|(fq}BV@{*~S4d6edacolI>#QsvC!=Upln6j0_dy6y^!=V{?kO&Iz7Cy zqWr`m;SA~eWYX%QlBD_JXOjVkiiqvyMRBQ&(U@(j%B6p}Tp0{V5K8Y^HKy#}H@=wE zXLj+wBei`cfBb#3Q|$&&ccnOnG%#?Vx!UdffF#FPpNhf9RwfA%8Lw?7#wLu2X77AU zK53w8G#Whf=BzmV1_}}x14I1t=U3Xa1vB3eKcY+dy-Cgc5N`7e2gC1+e{zX)Zh>(X zDGe$bnqxF(_qeQ9!L|mbO?WXhJ|DhxSi(S>qxeWM!n@uP$sP5w;a`QbGo0$&3gGS9c0lpdqJU z1z{xSzx}*FDbc6?rTn`A{i;I`K!4mN^L|{a`C=lH@A>3V<*g3YkM+Ph^qt3m&^)Bh z&y3&6S265Z4uwp?zk=QXoNX&7!t@hCrrsaxs^v^c_i4WE>};{1B4TlPSh9a@gLy>C zbYozw9UCOhHWLk3Y4Bl=3WmI<*dFV^FH7VS%HD3Z24IEks(1K;5U}U)*k8 ze-$#hGxNGQ_U5-7y%?#E9-WmGJQFNYbA-Lj?ol z{pdTkDGGgD&oAVTTy80cNAdaIane|;r^6@^2oys4PACS9K{696CLwxV5VyC#{%oG- z-DMlPq8lVY+QC>`;W_9K`|<5+-j_0t9ejCu^6cVCOX5)tFg)_Y>C3sM1^rkVHF32> z1Hq0sY&*T4#*KpJYZbf9m-BY#2~8;gu`--~Fm45WQJv`hD^H695@+Y`^P4`Ac={A+emV#UCflb$=>ws-j&UK&!M7LB+uTvw7d!&QBcd@3WG{Cx$L@9-9+bni6BN6hmD@!ZswCtaC~#9JMgz z=}mb$uG>=DxurPBu8%+to^-MS2;X+o=2MWEA1!q2#-p#{`KUMrC1)5JnHc-#?wnPv z7DW47`A&3gGC-c?ZcbhZd)A!svvG`W9yV18Hr)$9aDyOm-LR+7qT6{8xc$jPM_N0a*iUBwQc5^R(xYMa0$L!>Dn4 z)BwE$XLvK}U(wxBN>N~&AHQo!*#1a1@bHcre8Fb322YY{F|0hYV`_vt1@T+jpPxW@ zbSij>YbFM@0f)ZTtr$IDMv|aDG&9cg!iVA)Oom3i?qn~=DA2&B-~fvEpSHLKoBp&M z?JQ}!UOXuDO_3|cMN!oS>{&-_WfUhzUM}@iHG8~N2jr|+gVp%#7nUZNlS~wPp*FUs zDJtUt)FANK-JNFe=&oc2N-v)(a$2{bCUMQhHN>;#$lAJ=gVgX#Bg40>57aSw!?wPq zV-aW^ST%NSJvH@(=}6~(i&#iAVWaSYCZo|caf96>++Z550S;min| zdy~qrQkxXyzgn*@h?k8b2kazq*( zK58&wX7P(goWvc1aLj4On_g5O;0k0oKUpHpZH}^l3FG{g-aT^}lU#P~#$>+8hWGF0;+bj#mn)^u=j7~7dK+`jGVqxuei);5N zzF9t0Z$$f{BE~@XsY5K~3okQ7ioyKt1K@ToobI&q7+e^$#o>Y$#$jX}1xYA=P$m{m z*wh%Y_(EQB)#GC#a=NesJGe+=-s*$<$jU>(4KsQw^EQnv=?pRc&R;bOyXG*+&gD-R zvo`vzpjft4n5!>8_on^o6P}1AqSuh>=UCo!p9p+ieBCA|dw^o4eb3G(-5~wqJR7=DVys?q)^E5Tr_EnbHtSea3^bAASY19ZovbUO)2ZHiYLoLIjg(O| zIDazd_!cc;e9l~q%}qZF7C-nPRo2!Rdiu%;nawxpI5DC z;biy$lJ8a$<8muus>W$-U-=YTS6I^o&O(nPPvy~-9$_fs%tO)Ekm6XmXDH4wt?+E2 zi2KC!45hVm!83E~I996A${G15c_2xQ&xMLtM=u!-3iqsB&W{{e5-QZ^LHBq~NPx)? zcDe3fjFoQ=w2zv3PIKOpRM=Fp)e<1=M45yEk|y%~Z8$o?ro~&kJXCWxn+OtZPBF## zc+9p;-@=hYj^+jj+lC9I@U!<;d($N!Sbwx#agWkae6Jjq;J4z$wD-SI^By20TO{)u z$;qJvpg0fC#hf9I@}&v)gE1k?5Xf(pOr2vW#9F{wAeg-CRrzr;oUn5!7;PFSuFDY-z5KT<+fo!8M7 zdq9Z|QHCNfwQg;Z+sB=ncFqwai$*ohF6sHhU?92G2|Uj0pTN(*A-lco^+StBUW()9 zG~8Vb(xp<2t@N5^?~88^)Y`I5I!R|th>^39hPiWs zN*4vCtUq{*23qFyMFnxDRvW*~7|glYD_b17Q`*#P4fllDD>|O(b+Va>MQ}eXRjsw@ z`)q&5sp!@6Yg{gCTGCsDV%pl3)vrKH_7u42v()B@7HUqVk<0#56RWV~=eIX_ZJzrg zvT7ql_6nSqliT{gLQ8uEmF5}XaXE%G!g<%WE^~oBiol|X6fqF1z}9rBvDd?oS+k|a z3};O9k`T2DjXmk7m{XFK|Ma)qc=V8?z<=Cx zPIa|1bl!7d%`KYa#3JXoK!?Yn*&Z+|vDvm-JxR0u+-6EcBU^ozq zQm3o|lzX+x<+bU^hn+;LFY;A3D=)N|@;>+STZ*V96(QK50BXX^d|2)5J?KGKKZMXVVn z#RbjoW&)?cu1X;df)XF}imCXM)X1Ejosp5iEjkQIWAS}Lk4x>M?-vFiwql27Uc5r` zt9EwGEG#VxuIcvGpbAU}_%E&So+!G%l*EsFRXg7|Gz}O#yM@9lM^_nB`~oI#~udQuxG1pc+^dA;0-O zF27$Ga4>(N3ErJLMQ3I4f%X*)J~7y_K^DK+sqFoy-w8oiHIW4ROLI31yB>g7$Uip? zT{xdYQ3<|kLj)pLWfbT9s@CFCYUd)1bk=hDY4A-SK1txuRSvPkk+GgCcNlDpvSf@i zbSqsq1o*;X410YXmRo)J-gGa+u^P@W54q)DBy$Bvx*z|E4@ip>ok-hNxNP!z(dXn1 z*LNFYkDBd(2hiyCWVVD`m%3ZbT_3=myD2T8?dBa6Rvy8N4JDKRx`CS2a^$$Yh=PqL zaQHY6Fd4FEwRq!IEG>$YS7u_n3{!*|uQSKeX_9_T!CtR2qO{LzrJkr75| zT%iG?2R=FKoLjo*0m}wlAyr4_=!+WP&3-iNhs!Ose)Cy!(_cj+q8;W?3 zSt|rv568ElXW9nfj4cygN{KRGb&obonhvq|)H^HBwRbMU#c;}AU2Tt~0NLB14Dk77 zxWtDQ69>Y9G$%mYo13efk4V+Ss zjUhi&K>IXf;K1srGZ*W9DZuPcAUrJk8wk%r|NjTV931}!gaNOVnFd{~H-&F`_i!?s z<=b5)K1z8p?*UN9_Xv*-Lv&?b-1w3#Jwl@fNtuYV(pmd|8-Y)Ta`mUCWic_|5_LHd z1k{7C#I7aAP^SNigB?|W<6z0ah)FTdJCFOZOI?rqP4p;^`8NkH2XJ6uR8P~um5f+v zh+lt+)RL2qA|^Y=B3Py1729w;on71@U9xpyHO2e7rU;KfGRYw{XDx3?9fcdadxXPKrPEpvYqL>+R$Wm z@O(>!W7FVmHXMEOiO(GZ*CoVtQIDs;ff6PbvU z+XL4K#sHT^i@PSUqQ{C^?OJAGQ|4*^IT%2hG3$%h@c2%5?qgR&-BX~e6s}=-`J%mD z+;WtTn!L`)&FkrGze(O8qaOngDq0$NC6jI^En0EBucB-?J<6UIxkAx2+Q$+**O;u? zG7GdQ_}t>dwh-d#Eil(^gUx2R>4H7I`zAfk$Lj0!?8T-KE8Cvl>S^o=ouh-DuOU>H z%#XC1&Pd#OQmp1GBjX*9mG-u=DWA-ZNIcd`D6;3)*I9I-jS8T~RMdr?9mzzTxf;lb z;zEd^qD%c=R+=JLYxg=Xi6`x}N5}K$UP3-T{A3@?dC=BYmCIo&Ly~9ls3mulFBxd3 z|FlgUvI)Q^m#Kj_+7ladELSI478dzL|UJ`g7wAFhVp z&;#AKbix{)8#$ZC516%f+Xv9KIJtaq(}oO^drKu%g#W+gIV@Q)^~d`yoOsIDg9TdAbW=aMH1uyZUq9ZU-^~@?A?C zz()?^+uN8*W~>0!&fUq#h_duONqEA-zohd+!>c~*Jc`RpsU@K59uRkPKw4WqxVHX{RCF|nGI_F6 z-O52;#}2sF%9DTNlz8K!pzehkyq%j{pSj!w_KM~bHmox8`8`co@jTBXX7TtYogp^H z2b>E4a?ZD8oRFC~z9q&PB^Yubnc8KFMQPh`6qTn_kCo7D|{yR8?FmSrkxwNx3`Y1-VKsp;EjdH$H~k`04-j8_?g;WY-%fm=XCjYoNU1; zrnD0iY)hY#;s!>2dwtP#WxA5j=58O(tuz`lOR^0dXgEI;+AMZjg;m-=1*o}$r0=H% z8iY1gy~5G)`VAHra7K=8e=Usn`yoei@V`sPFg)7E)*>vNyC#!m-3PyWdFx5LoGbv2))J+=J|hk!@>CtZcTBb zcB~sf%kx)N>yLj(2FC>G5#ws2E~>3&as$7AH-Kl%VP7!cpW>$Kv{qnQ+W-YfR48hU zhbS?ipqeGCq8%TY6)35NYF0!}pZdo&%*XX!veFE2DV$!?!`nDsOdh`tuy`c|C#Ce} z=jAT35p}zo0t1E}$42i@Gp^Cc9THuS-JUGpn=8sMWw?5$9gDCRPwib3;t`}oVQ->d zt0~bsL4u2r5|K{AJq+t7)~#S#W`oO}J;W#ZUX?dLT$xjExL8&xI^3{Fo=?ozGom_I zV_S+tYE(cTpuLON)RDOkCGrl%Z`sP5(tecnciAE|K7@%er+7PfH}$e#h*uQF+`_%P z8J22{JZ|M@0txxU@k(*$MSV?vU?o44f6suN(_!T6-7agns{o`MUMokUC|Rn`ps{Ql zUdo#WwnD81=;pH`54w>&(_*RZ(tgPG6w0d=RkTHl^h zIPmQ^tOp6Hle5J3KeYfK1hL0L#B~Hu#^c^XLHXq+Tp_iQ_;_MMro11V>p7wsl+Z-< zOM+?K&i3VR&-N>pEk`&U0Vg@HZSdo@xN_({`mi=>{b1L#OJpj5Ej+T5zB%P7X7k<~ zd^ris@JGIHb_&W7;6x#Ul2H{OE!iK;$*_-yKXuo^1PBNmAGTPBGL+t;`tsVvw5F{L zEVvm;2zkG1!bLrHcZ;0J#f5-(@}_^ixtF9K*Z=l{k)HmXw`l0IK7p6sqYZUG=xRUJooyP4CDkYWMcU>RnmL3t!3kjMeM zA0akYBMm4&CXDY`)2_`mp($%*uFaSJm~TB}-x3qkT^F5%#8)XJQFOxnU^fFg1Ny^Q zmFXH<=IKBksG05hZLWUuG9Z*-nsvN5SDiV~l(Y~h0TNI~Q4Lo|B1bI__o`8EV}=m@{AB6;K-6rBt7Wl^59CHI=BAv~U);hbQM1y`9=pbSn#Z$8{B* ziOio+Y*=+g@6=7%Qs58UE#maSmAfT_H9V;DQ>?gN;2;t8c)qjqSl*B100;&1#u_~; zaF#Nrz<$?6o?Mnk+Aw&<(a*S6jCBm7+TB;r8t?jLH>yO`HxwawNcBCtWVV~pmQq0~ z7FxLl+Gq9nwjV+Wup#5{ozC5~q>?!MJdro30`cLxVZ_SWeK{B zQXr||=grA!w+0f)1v>=g>(}Q+s_tRH*w_BG?uAOCBI^VY)`M!8MmGKyRy{F8mfsq_ zK(5xH_1>Pb5_uQSe`bAq4eBB&=O((E`h#yvijZwv|I|wMRXkgjqAGuLv)ar%};vV#COQtCl)HThX`y2m_H7o4@oi$JV z8*A1J>Q%JO&e`QGEFLs&AtXj6B^Z%}9jmF^VP+ zJl=ywqLzRcDCcW$3JxOvFm1-lU71o(5`N07B-}QY|1#b*GP6b_!U*I8etFR@gy8WW z!chw@BL$U}{D#a~!T$=GzyBXXW)R;lmaGg!gquvC4+$sOXL`pC1r2w^ZIb~tj*hoS z3!raFL3pjrl#0bK9uV5kf*KUt{_Pp94S8$+||hi_1T z3Zo0vVv8}tTAkRfs+QjQDm1!xDEd&MUdkEf{u+sQ0JU0=fiz#;h4&1DALffgd8}Wl%tAvPuw8eCnc{`SQ)JI zk7Ov8v3oC=r)w%DY$;JX>UU@mgHIGSIsMWoqRZAdimVEEDqd}TY$gEL_6-q=gjCco zBN`Hr(CDrhfqNh{-EpMrOD;1)y)&+Z}lY zQe=Sr(~A%LiEW-}R}koOTE#lK$iq%*y_@gMNn`;)xpua5?1xP%{i!51#n}mga;0uE zHze~EhC=VHc-6}lfhurvd*;+jL;%PDA*O;ywwG8zv_+8V%NiOBuG|RM`jreaXUV|{ z9CVk!;r=#0Jsuc~7WTZwEm?l#VEg|FCqJBR__QqJw5kqJQCo#eueBDm%2>%DKsvr9 zP`f(60~Sk|wHZ)PWxK@^HOr%(NQsjU*g+1m%jH(8Wvm))P`Xe%*&DOb5>oNJ&AUep zRB=g~)qVa-OgQ~o(lX7q4RZJ2z%fMvCHM+@Z-3sKXHK6cY*H=l{g9^<)}VSk(PPs$ zI+}HU-}DlQKkE5>!ZjG@a60zC;N-{u1t$~D|6jq$UwS3rH0c}~9q>ZKCp6Mn5g=r( zcs`~MMA`53>5ph$K+~0zU9u*gMR^XTf57oM|8Q`9U}PKqwv>_$uL?>G z+qfoshFW`mImwETP~ zEbh(AX=bRBzVge4;}4sklQmIl%G`5oNK6MyS5Q=DLd6kf3s@N!Zu^}z-@nd&p|h`+ zb#qlcYQw*Q zJP$cC@kWnoFuPi}Ho3?RX@)I!JfojIA_#_`LPS(D91im!G__I99Bb5%;`e_(33S>Ie1{7pXJ z)+|VC)F2=M&uGzScJor_Bu+pZ0+I*~5?i=*8{eua?-XY{&zIp&amV;Bt=R!jZn&v)L}Aw?)lq1y9YdUzU6w!bcBmI=AKkWhIdr}-OaC9qG_xna=KU_aq!C^k*j%u+SZa&tpXg~K$ zE9nRFl03G-`u;a_H8qb48KO@-EkMdaADA= zgsR7ji*5^^!K1I-d6foMiJhre)25Fw6%=L}yNB+|+cM=JzPBg)SA?vy;r*AUcmd<+ z4_8VhaY$Z}%}~!iw-IF2Mb2rp$uL$C9RtPTOVlBmhJjx832j*T;f(r=CpeR9^rOqe zXY|3!jy|5LjwQ{vV(p_V_z6C#STuca_=$Q4$ebZ8iQuYnJQLJ-n}#AqPL!KlBIj(S z4$P|2eLAoMk$DKZaJ^3O|4Dzhg`4j6;^e&~`Xx;=s}eibS`+pFZ)}MB-k7lz z7bDRX0}@Cic>zBREv=w!d|ES#cLY_N2p-t=+ zLEJgaEog|P8)ZRCtqI$-Lz!8q0@vj%N7Z5m2xZoSvfQW_@9*At{>ZvRSJi8qSYW@t z;ydp>k77v2_6xo3x19UQ8kd`F_r+Ug2jcOHedhmsjHY4~Jfc^akca4y94&T2iX+o0`boF*0HS z!mr5`5pj=b2>+8R)V(A}=Rc@#fz?w-#bFe_J+$rHu9+5h1iPi#>!nW3-9c16ewdg|tylMg$*knEG$pS>r8@wNC#)Uth z=~#)Me7~9^2-7NW4L!jR?eti?zCvi0T-cyQcy_26lPn71kPaNnWctuS=F zsq6~}O?Wpc)bu-$4v>g+TlWu(ZEc_2$zBkLk_PYZg-Z@@5ZUQv^a z9m}*qUG)6OIyY|wBz~U2FoFz@EMe(aX+ua z!Dq0{nbe6H9XI@Nb4f>d_>Eo?aIhs`BbjsSd*UX_Sdkxxy1+wasWor!FrfT#L~G>k ztr_Lr7sIU)E^fAW&k;~=M&87dLbPq3=S%~Q=^OHpbjYr}U3>IUD!$$cD_hJ=ud?4p zU!6F5nReUYsjCd^lTp{fUp1lWUC$3*pRe_ccsX9Sa6cQs6gWDv+iw%ncnfJp*le98 zacD!*6C+mY=XL=?>#Y$gXthCSPkN_mLYHc$C`H0HzW(U7@0JBTF@(}^W@`=qPK4X{ z{zioP4eb!Yf%%;6NjA5Q@R-D^v+73}2KVYHivg_zYVFTmni>L~>?~4ZkM{6rX+UP!XK$8r|0dt>P01HT}8>z zFw9H4G$Btu*yNxB6qW+Ey1Iee|#2%y!j*qXs_kXTAEH zvX8U#qCOGW(UB@j;7B8gSJ^cj5ci;niL#f={@edR@#`H zdyz^X`ae<4__ciZQ~bfp^2a@Eh_gz63>;|^K!!3XyTUZTN2UVDQ4PQLW9u_^<;HIE z@q4$tYg_&N@M@=^XeKN*MX>S~RyM*sC?xb}g!KWiGClX*Yqz3oOZYn|R5+Nzy_<}U zO+ashyNw0;nm*;lth~xGM%(#^_kYSck2$<= zq`3Z8{-Kq|y-KD;#O8Imk95j(XGXw7=lgRNJJs0~rEDcAuwBX1iTx)4uqnOVhc9ipR3)8`eK2M6ow6(YrX+<4ycj|$&Bk-> z$bZnj?!|#CBfe}}lYM$N(k{-dy%^9JAEkM039R+XW(B1Y0`v~D;$f>Kr(%uXsMvnN zzwz`r`!z-tz}6qyx|vbop^o#;afZn2ISq5DD&EoI*oU_6dY$&X_VYSe2d+YJCv;X>mVJNx%p@KAv*qj7>L6w#5Fhi@cv3w!vC)l|pbGsgk_BUfm{Q$5c zwdpr#1~U%d{XBG;SzEXX@S6N@crT6f54@KSIgg9xc{@$lQlUGZT#a_d&B0b0Im7y4 z{UZ{-`Km#N=cH}AEI5V**IB}y?^-vp04_Dq8vPEku-^PE*dU5{LQmj_qC_ibRw7Qh!HsTCAlJ56kjDF_k0SNYbGCh)SVu=( zuHgl+q*YWh>bRSWJ3z-1&t$n}#YF6J&`a^~q!3O}dKheXGlqyVqYCT2;icp7uW)Y( za_TR*$Cvq!75=*a)%HPA!0ylBb}Mr^#|pin{CRYxd34gIL+JvKG@D10vg7?1@u(Xz zgmdLx`Ts0^WWIng?6#Oz7=jHsvA3U|{6iqhD6^!ZaBThCpt?W(YPG*%R|hq#K|Bk& z=PuYK&dSAmz z?c+6^Y#Z+XCsve2$1dFGak|_g_lFI!t3ep!XF;d5CT}0C_tZF%*~NaBGfsbXMZab} z(c;0SWhQ{ow+-}E#I%+o=-vzmoX!}|X@>Rj%tquxA|e}LRhDF6zigQPqZBmq=f6ln z^Ouv4|JaQ?_F3U%CmE$z8xk!Aq%>7uyeo$P~4CaBNf5RYc391qflMI@9i~? z=b(s(G0LktPBK;hPiToUeU6+@N!S!DdgH#r5fCwEc3BwzpqsqWL1t+)^7eFd$*FO~ zrz`kW-^;Lj+3PrudhbWEnbmRkH;*+#c#@x6j=Ik!d-*r}7pjT!)^eow=dQOtZkU%m zSU>@VuXTqT({fby24EwWtbVy0c*|q=#5O6~ZG($&76Vq_KiK~fEpOmSio6WDWuP6!381G+tzS!teb^Zn^iagT@ z(0i;wE&vLxJ$067Hm6mWKhp52d-$iyo*)2778L>`>Vj$tf_$ir%?lyh^|+7vQ>jJPb}Sg%xfQi|y^YGqu^kGQ zShiSQu8N)~xV&c#S&>pnKM4iFDq~@l1Y9(`?}jwD(X&7c=G@USp$FBi?Zze*rDR$Vq`tEpxOlJcTT_eK6#(!4gFN+}mD*_eC1C*- zD5jn~qsIK4ezj}H@LSOVMsO6)c8LhS66V)r>Aw-Q@%J?!WkD)GcP;ztR^$ztBoMwt zHNPo_>bd{N4mE$X?o5N-k0PLwsp+U|XjiRlZ*cjE>{0o>eL?)x2{W!v!D3TdVPCc9Nt*BW zo_BEgvmJO^W}H3Z40g_NY85y|&7GHz;|oJ}#@D%e0GABA>DKe}bB!jK z;gDXZI$V!CEIDx6jI~3x3)9lMP1Iz~zCRae`{>fH+J$4{(xf^|PWU_Hzv=yn8l&JW z!y6>p$qsq(basQgCuGW(L-)}5)t8VHg;VNdJ>xs@c5wyYv$>JQCSdsieImYSO5FWM zTpro8V1w>bm4I_wf*FJeS=ww|DJ#}3#Je6cUI&}x4$N<8jZ=X zQ(J%DuKw0v@?(C9Hg_17peLM?;P=OWyfDSU#lsSKi@&$$Qn{;5)rY32V<6GZc#suD%+$+KWjcWe_RDNHw$wjZCn6hy83+WbG8s-a*Bc3C&M^Fx?|Yvj1AbcZ zXJM*+>d6_|@^~SfS$Xf({?r2eMzHo>)c|lG>6(82 z`MdvJcY2h8A_zTXGCB!}-dpa@`%XtuJ;!jD3=NIYq31l(T+5WdK0?Mp^s%b$^>YMj z2VZ%%i6*)`_{N;yWrd|Hg?daMt5!nDMH3?eyS=gU_^$j(5Lw~(cpBWr3D||cNKpxT zl8}O)<3IlwS!ONQvobhWLe|U=J&Dw_IL0RLZc4xSH5_!Zn$)_f!Qa4N#O&O8d`(8h zm?pa?F+gO$W0%`8%mZ{mcNX9K(j845Ddjh@wdcdORt6PqqOL+{2_k6Kb$W@ICciu6 zIOZh%R@?!cEHG|rvVP_lM(9iqBKe8|yKyorhjKbt_5O%rGlx%W?leG$dJu-_S|0Z7 zodW~oJ3e1uY=r(@8h~R(6*?O;nB%5+Ir^_^}z*rZQ+Q68cz?~1?k0A11y@q zFYF;`CU<%DJ#(8LeO4SH@ir8}A-Ep>W9a{0+-KHotvufKu*qVjo+hCv&EDQhdg1Tm z!I?(EclO$scQGjFMHk8E>57Lt?M!y}u5wQa^kPim~bYjpMRc4yWsRj z1?O%=8M;0ouQ<5^8?P_%A3cnh7k86JB)Md*dP9Ry*l=}pY{&y^pQLOvg>rmG zsU94}Xs{?l)AZH@S$sCzPHnw3XRd2}6Y4+Eof+t|n*whs@IP{R_}YA)*(-2&)8LNz z=6{2k-3yey?Dlf;b&rQxoP!Ubd`(f}xvBe+tQ&b7)TOG|Q^cf}64Uav8Uy8OZ_?^{ z1C(BMB^At(IyAknk&+=P_?6G8R#D3#%$w^<$?C9esC~Mb;_a~3a3b0+@lXUQAu(cA z@%Xr=n0vc`%K=4hg(<2#Txxghr91VgG$E;YUR6z^RKZo%{;G(kO{VKt#+fGe^P{%2 zcK6_>>8Z%Z&f!KzvSW^?HGj;nP*}Sa(@OT+uNGai^7L0X0<~#j(Hkxw&|L>)2*{0T zv}V=CLqdtU*YA1jK)KUK(iIx9*F(Y1DS4@1-?b4ni{`87AiL3jr>- zJ8NM_CS9GL)(UDmb94A>YO8;{!_kc%N2F6{)=`Ts~e>!`Sztlg84KyW8GA-Dv04UpjO?i!?Vm*DR1(zv_31`qBu z?(WX*B=5|8GvA%L_q+F>UaUp0)8|yxsoM3cXFt2~*?@vj`w*$m)#mH{7ckiPthXu! zA4-2K?;$aelmo2=T-Crp92xMl1=p4~*Y&t0*x!FZprz`}0X(UvtDpol=Eo%mi>I1a zj_aS2lTg7LCzLu?r~sdb6Wp|nKhhi#DCH#<^0o!oO1huWa$XOza=Vs~TeBb5D4<&v zPD>$qd?7Kc+$}48v}oZge|EWpZSA8AtMs_FZI`!}17t43HT_ z>x*`1xrf{K&hAb<1&P&F=p3PujNE=t0C5emAiXYmlY8;gR=SEt4On=|-H)5*JDMbY z-DfN!zS0K(@d~td`!UYoPibEn=q$uE0d<(|tQ&99-#1Hq8P)vUx8E-UKYKfd1Y3DU zaHyr)poYIl$x)M*uJbmQf^n9P)OvTfN!Ak9D+m)ak5s3ed#KR%=(3=5SfaMVV92o| z$9&_;F??bbFXFaI#ZjQj`SOH-cyj8CC_k@pN!o57gaA-4NU=seh5&5z8QY;y$9uy} zt!Gz)@in#SXZR$#fcc=?_NUP7r{M%Pa*rjm_xg(o1+s9eN%-QKucD7t2bWs68hDTv z+7AXAQhH@M?VBBJ@+3(=uww~E;JYTE-DM~InuvQY8J3}^x73g1$bF{_gJOCgK zglx}H5HX8MZt0A^!fJqXuDnnI!#_->@b4n|E?=T-BCE)?)+^sOZVoR9A8l27s02#6 zn({s%X%H3Ivc?AhDHrO~crd8!vtHPwjdL0LFEQROlSQ8s=t{c1-+8&EI>|6!6B@j> zYPf{aa$`KZ2q_QW zCSlNzkg}1(CXd>bEQwmFVCm}W`uh2OR)m>G^xMth@TJfiOaX>pe3jh&Mq|xT^f1pr z7Ss9xuPn{*WPAl&h^RF!dpV$R3jFv6sCx&1B_4Z?hB9p^# z`CfY4FD@LVb?`?5IYSlGF7!x$Ft`MRHIiB}q2% ze9K~jG4^aQomoEV?F}QBDS0EbVpq0!v@3>gRQ<}TJT*2F`^#GjlP%>2P8}`jb|v97 zNpea?e+rD`v^I@t`$JaTCRDHXjD20zP=L!aC0lE)zgkKk4Iwq0@s;JugE&?Ms6MgW zoi1QRax0b3H93ZSRBn7b+>ywl32v zo5-cbL72;~&XcaL`+IE?nv*VU6oR-&*+mV?mQ5ZTd`*iMCNxary>a>{7a?8l z1_pF`x=NU;2klbF$=tMVcLap^Wm%KUw?$O@VXyJ0ef!eR(#+k1e2xiZ6fVN1{leAp zZCt-{AgDo|F^u2JN(Q(I{n;6mdE_Mu%qGEZMP-~co64h8ih~DFmoheh`?-aXCH}HT zvmiK*ojGx`N5oQ*%NamDHcF2Tp8tO)?cAVo3I#@=tIisVr zb|2rtFmzjW$BRJ}hS0n@xH@#cv2a*%Gw~OQbSA>}$19m0w|koTQ1zZeto~x5{HcQN z8~y5`iz~4tKBp*=5$9kq1%YJ-Rm8=1Z%X4eSu&^Hb`J^tBt-5LrYS|1HMmHt2@3*q z#ANhq<^AvjXImf*cix)aekKm~5CU{uriq?6Mh&$jTRoC(BSM(08z98HH5^WOzro6Y z%Y#96>0yp|$sJTbr}AK1r^vn(oMdUXkt`^jhB5??VZNfa%&g@e#E^&`MRq8u#3{sL zYah0~O?x>%J{-#WdAjs7g%RIyaCmh-ZiZGM`S0yZ--thozG*NY`DI2OTG3< zu{FwsLryvjQC<@lE3Mo|InfZWnX1WD9?$fPr>2>E%hgoer3j`i%h9Gb&X zIb-G^PH6qc%h_Z#HN}T?#If-(QfVu)12(Nd@pteKKaiy_wk5-1M=|RJOjr+;dvu#r zZ3Qa9wSw?!1A>`$`b-r=sqOn)TN*Vm3CQRBSW?1KS!3otoWy0#gHC3AOHoAz7ve~8 znfHTfC$byo{rjlezU#q~bT~b*G~vK5s$Y6OX_3d7lAQDUrFsKq73N9R+S1K6I46f`||*m|$PCYuZ6 zX!0UqY%&^qn+to=ceXanpdXsOj?WA!3+FcbYGoTTBX4|1Ka}V~1Kea+PBb`YhiGNS z)B0L!LEEkjy;BR!k6jxYop&MbUuNeFm0(Uumtpj%$Ejm z7l-;!)z5hp4j&VJY}0kG&hziAg)m6BluZvN7@&n2ZH>4dwC@7D%49c3ikm1GuVC&d zrK{YAZtip!-VP?G`VNnN;Gqo+pRjn`qNd)kmEKib#!jg^jhq?IU58>N&8xhc&rg!~ zKwzN>-_4_QKDuB;I!KC|3eZ{?h8rrhJnrG+O$+ToPPKoyI~3_2IU3Ud2_gR$g9ffL{TOF~ zjK>t;KaoWsKn z8R7oKU$(2MmvgR+u1awY*_)$#OqvCm>OBq8Y#Xge3T0yBrP<9LO~qr%GVI12rzxCx zWJp8SRk`qUHdb=t&lJZdID*8wRa$i&V=sEm=;Rx15QeI^qf+An+hu{p%VL7|r1(N_ zn=ZkfJhWH){sJu3%(r}kIv%ZxOevW#EL}Ss<*RzoK^fU-NQf1;HsHHC$x91~F+qKG3Pnj=gr%s@q^ z7mP0-i6(`C`;_IqO~Z!(=uci6JgL%mCX3@NGB#P~OKG>p zi#N51e-I9`o}9IDw4f3hjCNs2Te1f@-p)1nGB*3l+~a6!YD(mb@2M))xLNv+u=+ZM z%ZavA{b$y*rdBq%t+IUW^(g1*$30_!O^fES)$i-|tfHc!feU_LA1$hX>sS&t^?9(tCF2&c_^t+AWVysX|31Of-X5_Q<{MSw7Trx!-AEXj*Fe0Ou~CN?CQ z309=NB#&wT))+JcnPtC1*JcG6FYuYq8QXUPPPidWYH;E<0=4aAkb{EF=2-c~!j2(u zF-`h6H+i>)2F6|Fm-lV-l?>wy$P<`)hJh{1NFU;wn^UN(7(L75)nFl$>7Jr7jhexcr z7&qIj9>DGVWO8sMQi)Zjg`^a*RH&RjwOsilBHxff!6SeQO?m%9#?x_!9Z>t;QF}*< zle-XvX4=3>FV}i{=?>OgdMKFs#6)>(n?s2!l@d`4#aV??g<~FT)kiJ8@$vn&T7X;M zdLu^QBqt=Bf|hXcrax{LysFS*AI7tbtG*+0^Ewk+OeOoIkS4lcQ52 zza>>>60@)WE=u+0ytc(^lo>y-fIv#XQ;h-D_eN>wtH%cy_62T#IV{8e!3d2;9@1x?bEd!=VqAgw;uDsORhh-LhvPy z)g6uFo&kR0+N?a8GagI%j!R{I*W#sv{UdCpZak(y}^7eOSn1 z24JvOWb4wS9QN^(8Df?Ply@~_;JmC@t~B{P^g5TS-Zu49`1;sziK|LAcSxgk)Eiv< zIkj(;9F-CH!eWiA?#;hPM_^_1TU-6D$nt1_4O}5ue%eP}w}D~|4jX&ybXypXn4HRu zMKmO&B*+!xW<@0ib#)DRp;LrGg7<#?^u#^GTW4)I(?<$;An~`~iTr-%qH&xtd0C&9 zMhN(-*@(i~$vyP~?vA|3YWA?SOT8u^!WkZpu@ zP;kVr>%lj1K)!v`AHFsD61k?$r(hnx%x!r%(Qe*Th0E!_5}^&stZObm5eMd%JCeHx zGoBv^2cMwEetx^+GBnsnxD=v$L+5NL-Aw_#t%%C{6xpu*{znk#h45K{ zksny=k52GBP)&0*$HcEr8%BmmWsR$~*$W=LEf?~~w8Y5XQEK=Fkq?%`Lstvg>*1L1| zjBm?dEm9$)dDI(=EmWmaZW<25hG`58xwgWW} z58j~!x(fP*BndE3x+8lt2qp+Q8(42h?sQo4h+i#buDTBT)jSD?+mWB0^0GGuxERG;JNhe4QR`@)bp&kvgD=nrMC|| z;dU3avKG7iq@@P)@4)Y9X(%#uYY5ZHGc{qVqodr=)2;VlYRk@T0JIS@fk{rkl5}qp zq&dhv-rw?O;{dZh{UsZj8Ni~hloLbGlpGlOdALYO*bIN`E%bb4eq>*|M}J<4;Q+sLgy3nWWCaCgtdUGd@jy&&P~XxX_ePq&B}7zwSt;;ROi)p>x} z8_4p#qyG8HY~{BVR?9tQB}goDoR|8CxqJ+z!or50Burc$C{KaxY%7O(7wGRS z`(thcJN9H<6UVxS!AbiYuI#f@j_&xbhPdgi%6sg14r)}e4O8Fpq4_>WSE<;|Dm}BV zWGH*Kx(?TS$^Bc<=>b`H+{+*IW36(Bkd!GWq)+^<+jJ2!L59Tsp^gG4Kw9uKV@lhD z#Y~?W*hXOM6dTvSKmpSbu$i=Jvf{ZV2)k%sQ~XuKT(!Gs9yJT9VcMSPmYU$m0NhzfyLXSMd1R+24v`E{wGCgs8OCm zV^|@<_X#1=)|EqFHkaNSlz4>pScSbjW+JB?Yq>2KHyy>|El5dMycR=GI!K6Sx3hzh z_(9Si{k`=bZzs5Xyzl`n&Rn;1fm|f{>=j+RW1ZtiX(IaZuCAIlhjGRn_GM`VEQv{l znDOR!i1D!&EzhH}IH?;bzlKD;9+a34m3oG2G6n2d@Kq2Z&XRyty z`ld1XfvPMdzBPhDUgZf9*&=wpHM&G@NwU!BP}ehL(M*#tH5lL$P5L?GE`^ErBhD(@ z!j@PbkMFBLzAeKfSpTkE7dTPC zbx!2jaAf)T!BD!TM<32+AgMNDVMw3rLSJl@gjfW4Ud`rwAu~h|2|DiS%(%lnA!f?) z5zlz^cRWwAx{e=9eenEYd-G;l$w<^WqJpd~$5l_6;}~9$vhp7YE|UdOlMD@JsTc zKf`pM|G3~zYEFVqKtJn~rM^#`hL#>Z$T9C%f6M|DvrRIvww}H|z%2Q|^@tZx+T?m> ze~|X`pV+UEHbF6>M^C@|9t&B;ncsUAfa*YYfdC@2X+5FqzeB<11MhyW0_%P&GD#vuF}?vm_9Y>85wt$jLLn%z*~hry0Hsw1ELH`LZTty0Ct- zxTO?2bJ~_lW6Wv=eOFi4J2*J6BGe*$*l|(Yce0i(ZTIFxpPG`KllI#`!ggRzFo6AqH&G5mb!=7JwiX?mB=;vNJ$Xy-dz9 zcA9g2{lYlof56`pLVd9D>WQ6Z`(6LE?Jvw8v%>@S&+0MIe{-yIqMyi;F||tY&8+mz z*DqH3nxf>&#YY8jOd@bRJ>#tSQ`kLUihrt#Iv;)U&|Larr$mr4`-#ln=$#RU-3Y&N zgg5^yMf`_xi~q=O&0|+ZK0bj-owD#!v^Y!<*@8Adf?97ipDN2PgPIIIKWxn&7?XC- z`zw}YBzzTG#g>}4hd&GXkzT0BW$z6ZT!o+bBmYecaDmC_QvmU{^buAWI!F1R0rL`# z-QNMTtXn@<>+F$(9Vu+}JOsQp=yC?Ujug2^8JzhLr^m(nA6ji+pL zKhe0H7`uD&%*a$Va{nD-YP563j??`fvTGZmj);;)J^A@4dG{!1s}Z*YK9DCiPa-Mr ze^kaiDf#ZMUa4z8^^w^XaZY%_X3a;Ow*rjT0H4;1kGKlIHHJ?jcZ3etnh(Mf<~P64 zmf^W(Xrmt!6T70oRagB`d$G5f-LzgCy1Cu8LP$G?5|!OebNFmcr1dW-IlhhAj$nNlaK zFDf1KrJQFlz!eJKsyL{`&F+)vp6wZzs!0BfgnTuWXtiiKlT~3~Z7$@WJa%0Nf&Ifn z0dnt1WTu}CmtOyZijn_@iogFx#T^w1CfA&_c;L4q>gcxD!1_c#!s^Byq^Ey0Hm|g1 zMUCjx9Ov^!L!Z-ZdO|Y0Emn^*_U-f*DvrVhl*N7QU z3ol%J=UraJqpq1%&o(}l#Y9f#l>|j`T9h>vVfz3hW@aufKp4Ga*uwj;ZPB@Ycgtlpd}k@798PP zA%f^`uIH9y(&eumx-T;CFaOkqlMOlsWcMqGoc}VTmGx&j9-hrGz9Rh?SA%8piECv3 zVuu6tGS-Nu(NeU=#}>vx_PM>UF(zSGCR_FF)M!FL6Z_SSDZos)KjOA0kqD}RMXh|w z8lPBH7499bC5BJg+7xp~;QVIaj93$Xv!*ainy7ilZoPq=gx4D^z?iYJAW^{B6tIx! zi%>FD$$~WzBF|PTRYf+makaHOqgOZSq-^KjYibt}#2bsG2u8#?1t^MDO)xIZ@tMsz3PUV0+5?}a@c4US8Vi=A;m-{Fs2`9gFKlpk*%goP@vehYDYkp-8I2Wg#t zwR_?l^skK@5p=nx1$Ir{?_Ao$deFV)<$~m0DT>N=!s+@CN~fl3faH0RIDpKCiGkY5 zjPspMleVbl;FCvv*4nMDsalQxtYnyXY5XePh%2|*EucobvINb{Y_2e8v-Xi2z2L%H z(_6oOw8=-(at|ecG^<#`4U>_NtVZ0!a3JX|0YzLy!4C`MFgRiA~wG4v{y+Tp%VjKT}DS=?6qKa=Ujcq@B(8FR67{kbwshj#mVM`Jo?}Ru8aY)6-um10bk0yzX#_L< zl_!o_PVE5poyOL!?Y^IH{OX8_C9b#^dafEkmtX3L8AxsYvs`<vJn;V32VKf`NF=>P|o44?PP=LjKD=Yj!^+=Ge`O|6OTE!Uj(2W(c3@qSAN zakOR##*WWX%g`Yv4&nOx*1748w!BE|2LxeFPbX)xtAd+`WBO-uX`^6h9_Jjt(gxN< z#7&~GBpe!eULJ(S5-yL7YHG_adqxj#U9&ozUF9G&qB03Dzglrw?(37hiHxfX%!Puk z^Z!O=1}P#vwR?P>Gu+n(8c&Af(1`5ziT_+iFq-eCU?EIOLiHM$y~=iDd7S2I?9n8} zW+OrN%OmX9%q#C(@)=Ez%@27pDViWH3v%ws{12v1L{-S1yf=&X+O2}Iy|s< z9eY2hDc#;fd{J~aIkvLt)VyT>Tbm$3{)d7*Tz@)v2ijFYpM^qtAl%tETjIz+>9x4L zv){3IZ!Uv(Y#}#fAvil@4kO;0UA)6Px!(@s4mX|;o2`XDg zvF~4Q;$83n(`MNh==QPw2WL>-x2K4`_Gz^j40iVy0;kc=@Ea0MpxPN^aBLm29+kt! z83=j-a$M_DTG-%{z>8k`>Ey~)VHzF z^(Yk0uCNP%NosTXr10aN47HO+mc%K7cQgTyHne7)3)=6W14jv;ekcKek}2j_+oNYy z(~EO`jx>7A3%?%!ZvV=#m<>d(-Ws%Lo>RIabPv9ao4?u_Q?i|N({u_|@t-*BSD&q! zf$2CY6fYJe_HEp6E$FYnf06?#y=3$3dY@2PFLQ7){~r%}`n5lN;6pxg+h;QO-pjHV zHl;K8+I6GVv3tUkeX6v!fvo44FHfG^$5bDI=zkTZ0N-)mYwX0|z9>I#;F{F=2ydI) z+L2h-HU=9tTI+a&adB18Aiw{EI}5C*Z0WBZ+v5&M(u=VFHMV|ThCZnW18hJk`(Lmg zlVo=$YW><*tzo#GVJ^O{?vDWhI}8kF%Z^UpEZ{Brc~@^1#rLqT!^Ar2Xaf*ZlypQx zKQe#LEe3nm7ssV8JSm@>HMy5INyxY;{?icUAA8f+vCN1WLuLeq#~!C2aW?>xwBN3p z!6`+KHeX}p{v>FL{q0Bv>44aLhan0{B!dR&_L?~j=p5Ku9v4?Ui#5i4@A8Db?{yPX z%PT!~^+3os1Ol2eL*_>&fUOZ}*>sU9w)sD!UY41$tYz~vD%58ugt4l{Tz(m*9EF%Ivk za)3Lq*a`68qwe0@O& z9k)L=kr6F5S{%pC#6ft_*rG~YB_Q$iRw_Pm&w(oZB=>bkq`>Y3O!BR4m&)y~t(&bb z{j6CCyL(|sV5~$u?=4Lb5#V$ooT}+h{HOOCkhV1>^7~EU9dUZdLHaJBqC%mfZW2*h zq0^_ekIO7E04Ks!KQTcdpyEV9h5zGN7}B%`-F#!@wQ{)PJ6J@a+?Znf8Bye+fp{%# z3UGdqZHBWJ!Hu!sg!P&9<9&PhWVYA3W9lc6XS`zZvGIK2Ec+ZuYx$oSh4?HEhAN37 z#qCN+mIM)e8)R(6@TvCgt z?$7^9~<>_&n8Z_L3Lo~@g?$CbFztSi1H+$TH_M5vW$lFm$v%4xAOJj7%f2Mjvrlyh@ z|Go8`CV#Yc5(ve_G~E^b3Dg-~6*ddv5c9F+UO&)Vh8fr%Z+8uqkVhkZdzV`2kc|uZ zE-aW-Y1~rMr2&IU=C%C%{nBJf;CQ7Hy7j&Qmz4awO3I6*divmNChe8fTkCR9t6I=m zC{Ar;+rq;foiUY|^YgJ-!gTRNFRbLf`>>tWF@cl|IHUYoFxu$!E^j zNrHKTbOYk|g!JblkRJ=1{j&HCDqg{=orApV@#|7*%*Z%=QI`(GYxLSIgZ%<8uUqP$ zz!Z@|S6`Mh&D58T;ug;;KirLcS9Xp2H*~zok}KyvsUYXvo5ejGdtu&9qjX|g-uC7swp z5I*L>p-2ip2NpaDZw{`JdnAWMSXHQyc6u^U%dLJ}BSMU27j`b;`oE#2xt%c=oRo`a zn4Y`ENO}6^E^BXRKB@3K+;SkQ+jlH;?tQEuoQt_H{{Irkx@PFxnz6*}oY~idtgFfD zm1HJR8u>>nZCs zJ-8;K_}jUaCZ=Rgj+v#x_E94#ck4i$kwaU;2f>30RjM+(W0s#{aW^HGW0b>4&?HQ7 z2A|RAe}ayE;3$i2%^=So0JPhsTw(8UR_|xg@GzBn6F@2{a zw5`T!=+`{scWv|o=%E0Hn*^Vm)(ZJ2Ee{=YFA-Ln70Jn0F*`=?ix1eIfuL*1w~A>U znFpF09M`<<6idQF*B>#B45MnF4>rpNHo6i{&c@epIG4l9i&jihlKr=*Z(Z_1*zI$5 zlMa%?FbKp`5VcR6YFl>{{f_XjQu zjW_I{xFTlr-85qyNPMvtdHZT%GI$-O9&aBu^1n~cb5-pgW=%R5$IPVS+%B^V0RTCL zg5;Dv62ht|z1>G+Id3AHeh5@(jioz+jCMw#bt&E?y|2>6gVMSBrEj%28j~PdiRE*1 z;rSzEWpFwx`3*{;d=l1w{+&(MyM2ZUBc@g1FE-6|PK8QnO<`l(&xwdT!mO0~J~J&Gr+8aOHp5GX1q=FqAsqhGx8?qX)OlE_<2}fGmfDg+7s? z_&d;h@~zTkB;N5NV}>qaT$UL-3j)0!tK?6Ylyn;@43%-8>iGuVq>f4vf6I+za5trh znn%{tW=^imgohKJ1u+0K%&iox>MAen#HT0A(l7F_MOB-l4Sa+&$G@sELxjyx+iUcT$j!X&iiHWJ%S?O?L%-q?R^~5& zm{BM!FBllgyxf>=nUi>>U{zTHN2-TXjQRC4#axyiM>y)6^aK8K_;MN0ca(%x$9Fbq zyJFAJbG@JLiI~rWF(FV^G01XoEOiG*cC&1RD4PvA7-X&liU}T&73^#zGwA$_HFXse z+8RcAgBxqD`(*OCUG@eMwBnMrz7v4GYX{F-Q*eWroy?Gev3s1Qx6_Z8dI4XYz&8@X zR7649E~cIk&cPm?#I!j7GANAh@XAisrYf@TE=2Wi>caOuru^(om?b@0GJ5yzp~kf2 z-KaD>=MAM&iF5o*l$wOKBK0y@f=(iw?WE7HXtph94Vi*EId^|JIZWB^kAo>}H<{3K z?TnrN$>3+BmV;ODG4pom6Duf$GH)ht?LC3C#6?2OeNywzQJ(oM`DQ-%!1*W8PJroq z3Nss2MlPSrh7X)#^=Ap?C81;P8TA+2QfZgDjI7c3KgAzSbUDCTuW*=#av^v zT!@OyfIHNsT7XZA9_P4{6dk3Pw@5M9m_TaFrhk{xz5@+MD>o0-$zYq9zzrEEg>(Q6 zcnY8SB3c;N(g1(_a$KJ%Z`zHFBW|!EwKAvWp+5ZISRvBd9@YHF`yHlRq3v0xwL3f7 zDF?KuXwiN6v?lkA7!bwepIkFN7qDNZ@qCrxZ=;+Ke1zabNS?nPM9%8}^~LIFlHYt^=laztvC3Xo?2NdeP$ltkk|` zDsP|cxsOvF9%)Gl{mjJ9xmU4R_~}!&9$vauxpsSxw)PW3t=VifH&aqcE;g1uG(Ib} z;#Z8=a2HRe{~chn&w8D{EmKdh19bG6YchqopmAhSx7MlG$|{+vzSzIkdp=({m?{Nz zEURML#3(kEu%s^E2|Ezd=-~zH9iD@uL~t+8{9D241*|K`Bj)&1ib}e!?z}l<6EG$G zT8WBINsd+I>B_;)w5cbE(Q|ub)S$7K5K^kiT&WC`P-m>IHMMS^pm$i-@q4{ieWmpz zk3lYtULiQ4A}e`t0b&A;rKy>Rk_r6Ikxw^+b|$}4`2&p02i!*2~^B5V_q?#7(i8YRA=g-o0I77keK4A+md`^V%2{!0)nw3@Vs zXwFDWPR0Re^>2ugx{O>rnuz0lJ$ZsV!Td3)Zh4X=(0H(y;AEi1;(0%xf(J-=g8n_h z_3V<8k;!Rl9xc{)wYoOCR^>k&?Ig7JGg-$qt>pE&aQnpUR?LimLI z%7PR9Wl*?q20I4mJ=9P!^;3_6D zEz=4QJ;qwU@ji3L>AUeh@NFZqp|D~cbQ+vI^c4|E+__Syo)PzaiN@e-)kHy2y}39| zhF=GE!!Q<_EIX83#c6Ome|IM@su%)V{8=6nB=Ru$1fLeKE+kek_>TKJruoeQNDdK( zp~5kJolq_TT7K605F-iD56h*{-A`?vTIAgjI-qZ*Z3f|W1Wpr}WG=m9CI_7zEmD0L zeCZOt(%V68m7!i-?tKOkod(ChZ!7PnL$+7+@0?daf}HV;iNgs8QkmRC$R&-gXKs-J zi>9=#t;(Dk?R!TcBxurf-MB%;*>$~t@u*iFjSpyX()JT1wG)&velr^bp5$Zfq-WXy zB@0~!E=YI?^ZSy&)h53wveJv__cl)?<~S%f|HT=&y#5)lV?;}-nH`M=w172_9WmUb z!y_#b^Sp_ihJuxb_4Ovside!ziv8Z%e_3`VZUC+~y_qjmL<0v? zWsB)E&YJ#+k05runHzD?uXSGJu0zj zRBQc9uqfjPwB!F(N4qvp9zs-im`odv&&6sEFT@qeh`qjV3BME;RCd7ja{1(1)ThI^ zY2SbauME)qbThD&5NfZUD0YJVbnvLdkTO__T|yvHe>2v(-)V64(1PJp>4s!ys5hQA zKnSRlCiLu!2vR+0>y|guH{rT|)eh1U>yIr>f&C{5Zj3aCR$!sF1|lwNX-72HSCj8z z%C6KS%G4aS59OP6n#9#PEO}=Tl)>dE_`kMiw>kg3mBv3I~8H5K| z64z~j8irFLt$+p8$w^xTd+GHN3;`eM$J?FL%a;qRcz(}f+4_TDEH%JbKZJ@Yo_BN- zcb)R#l<&62E|K5*Us37?um7=-iyvSa`9BDKr=T-T1Y>C0Vn~f#xVD5HD~Z3nVu`*h zwh>Lt%)y!-l#2 zW<_fgg-?gva)T_+2fu^G{CamFUSJZet&k6RPVAI$9AlUUCp@*?^KBT@>@OGucFMG8 z(AewNFj&=xNz`NAHtF|=SDMdP=`Pf-+oY3U4AMF3(PQklfF~^QyWfHW=?Hr7&vjzb z_L(7lOaa%SH)6)k>xsN*x9Mnsvu7E`wD~ zNaj+&)0oiJ=kZChT}rVy0N~5N$9=gZPZPGA+4Ld9TZxzfd!A`of* zYAORGy4=CmUg_W1iF2epNJ&kTo143TJ*_E*1xM%}4xokKcCkRor?W?iiXNDN&LCyj zM9^B4{R(R0?+!ITpP}mj*J`>$W5x488J3dXDtm|)g?+-O^Hkzz`yGRK;R_<{UlRKM z62$&JgWv-LRs@!l8R@kSwaXIEi3r1Y6f%#?8PxD&uEAQEVmh2pZx@}aKU+HaElLJv zu7Y)ljcUe*_s4Fe79x7A*A^p(Cjmu^4Q_gT4^%A-@o3fX(YuHN=SQ>?T+RwZ9;{Z26Y|7R2w*C(3$HoS9#<(cjydM^1F?%E^sI#iv(`d?{~~PT znV}hReE)M&zRlzAP}d(qJO=!W3S*9h87ou#-xxBq{_H53mcBTxa{4F;dB*fPq7__f z^X~8&oOsK2gJeV8>dwa~9MkB+LtQN|8h9Eos`O1dXU}2;%YUI%ZTOWFh6xz-4yLE%n_bO}td>>t^1}e@C#DUzQ8FXsr+K=#FDk{)Y(LdCC91GXq^J z)5&8jQV1SF-|UckEcDp0>}#|in)T^hNdrCpcR3BP0wKpX1vGmj*f8=&Pc=|z24c5`UeF00GI-P32Att zJ-T(3=haN4&z|_g;jz_vPj+&0-t&t;?HYMPo8a@XstCtEE_sAUtlTF))}?HjlIf1p zJesU^q`RrrW~qyiJ|M+c?Ba^%4qK@er_-ca6qCx+7xhp)r;D{@IGDtYpjs|nW>Gmz3w|H1F3tQ^f0)sr&+$73R|m~ z!VY-WwiYi1Z7#|8uos23RF>8Z(8_~c_rvHdc{$NhjBnMiut(7ye-^u< z;w5yIU`V6lp1*2ea9b$FHh>)B<>~E`3EQ5i#xt{7f6o+i$ubs=UhfBLwGD*or`VTt z{3&xH)!%4#q+2nCh2TJoxnsLx`H{i{b6|)S6+iRrg_j~n+_Cj2^f@LLZZ=Z%$P2Ys9Gl$#Pp-RWYvo0*fG7-Zch+!%{Zp%ujaIKe~%GYO{Y zQJ!UJ`2z{3zDW`p_!2vXM+wj#8qKsquC0y22%Rfvtd7XRd?R&Ulv#*Bcvt z+4W(d4y1GyZj9Z7teql$hO~5lmxU`5Z$UvBY#cjmcWj!0kR;p^`Fb<*`~^iCUS6zw zi@C$m;>83UflG9_xsXPc{I#?SZ|L`LWs)x5_7~GmWRjxslER`%&XwPn?)znwzh8NU zLPD$2?bc39Yd(-GVD#If{?EX2BSjz#ZFG<^zGV>PYrk$Fn&mbAn6Qm&UC1V}@&*c8 zALsf0iM0g3HKE4yhE&2^Y1 zkm?0O5yJnCca_lb_qS=I6WrHF?Y@pD%yI;9xh5y9HdG4xkI!+&6VZVT__>*YOg#Gl z-c4!c>7`eL>26_R)rmE^;SJ=#;PC$-EnoVn(bCof_RW2t|K9B@b-N^Ie za?T)2Y@^Xtddxs_H?2PEXiC_%0h#t)W5tt_0!KVTdv(Dk7ob%nj#{6GdX1!!O^>!R zEdXuZW*w{;&O;)qZjX}EU@n8Oc?Vs``(CUreZD(sf_<=kbeZ?XT_Ya1YKXc%zYABX z1y0XbWb6VPU8lwB8@*YK*TZ?b+GC`##;Ip49+y*i+~}WA za$R0r-C}10L;nn(23k5gfP&eaI25hh)C{Rl`8O_zfzJzG1|P6Rpz5i8%%DyDk&YYA zxg9e$q@aiqAF=XEx3@gi+^6+N2kCC_@*ryv+uEv2;~X?eshCpU)^f4Sj)!m5DK<+1 z%JI?BjL^OdNjnlY>GgG&d;I>*VrR~@lZKtg3 z3XGIPoQ&Zb?;QBny~5`g zeCg1C+c|$fK*{&up zt@Y%x#q)TTzsK2VVue@dXIe&|+j84aGG8l0a@T;_n|jAqDXX@Qa!$1U;`>I zEttId&EsUj(ucp$r>n=W(Ji*%r%SeH-!f85 zM9Ck1-?U$|Hpu8T7J%PyNV%usgJUvJH3FcVb;?o`xC-6Yl{lAHm9x5gB+Qc{;{cBZ zpT*7cEO#6+ig!r4*p1tE@?$Fd<@7l_4F<|q_Hq`-_cIXBesgofx36`s>_ygN1#U&B zyD8GFSKFPpi91v@nJ(FmY1~Pshm#2y$kNeN*6Rj6y4iS|)MZHtVH7P@37Z5d@#R#) zSm_R`_6qmJLFe)#W;mt^*#w`a=Z;E1NpOxUkCQuNZ0q!0JkgAVkOvAZQ|(C-U~`!A z-otaqW^$puuWx$MeWHYUylHO7W;>r~#V>z^O}i>-p%vu7s@2B)&T)XJ4Tw)c}U!HR<@+~%xSlevVSjs`LhrDB8M+DVSLcj zN9)427B;?(KUC35~zUp0n z+i}+PV*(*xjQFx@l3#n^%A7rxZ=WhBDuY`=iCLppY{-Bi<1%iOUl>q8D6$~pgZDg; zERV;~#;zjYkAN)jT%=F4KpiP}NSZ`yXH8#xV_8>*a3gPcOpq~wh8YI0_;Z&5&cLB$ z=X!p|@?eabSYe;X1Dd)bCtMuqT2NSjNEq|{bH}AW7&WQjcCSL*t46AqLA2T{J`ahA zj*Fu|5Oa>{xHoRObwn>1WR}vv2{prFB)#;Z%gXm z25-4A701ufBLKco{#386+6k#Fs-v4$ua{fso!cfQcpPTwjCM}H6+@Y8PT{DHZJ3EL z%3BvEI$+s~yf`0tjRvNdKmk^aYnZrBQP%x{+~$X8MH2`nV5P+<%ROa7aOA1m+yS>y z+B;%m?%AtbF|@gtx0Fja*a2&4Mt!G8#~q#e!9{c1EUGX;a6$>urGhH`doo6AC4fq; zw1~K4v=D-8`XyOzF|{hxCDXpa!1LTZ2RLsYGef&p*(3cs{OLxUak^5XyrjDDPBEP| z=qj+b$xauG8C2hBE9c(jNmm99{zCXE30`SJN8);q%SKaBa*!X+>T=vU!!Y_=}>gEdSAHIW(H=f zh?F5FRGZD$M5og`%MBI7T&T_nG%Hd0A3Q`slpSx1t*m=;mt!7D1vC#nOm=Y>*LtDJ zdK0fj1tKtyD_(MOiL^}fnX?+od7!E`QwHfi=@RF4G0{!HO)7W!2v{1;e{$TEz;`1Ik#X4siSLwI_&-lt)LKiD#4)mCdYDXR>)mI6T-+L!skl-8Fepeg|_>-OmPphbQ z7>*@NQ3M&ijmGFbf@$|NQ(gtu@@nNX$nZE0nM5CvYQB6Lvk(Me3f=J}LzTZkK5G53mEtXEGJ{Q}!5+q%P9vb5pG`Rkr2 zf~_FXqVUbi;{JkT^zMqU(y-*d>z3s$f$Bi!IvR!yOFGZ(_Kro?sRx-MhsoYrN*T{p z{^;k;{CObZ(!T!C+}%gX_>Nb;zNOvZRCKz*z^Uy$`@G?W7EtoDJWQK9fzfO+_GkaS zbJaa6hNC8WmXe(B3t!<|V^>8ytq3*@nw_F+?S?1wP*Bsl9du+v)for|f=ymu@=NO#1Egqdcg5CIPhWA%)Jh4z9a=stEcLE{rTk+9N z@2!@vUP0@HJcWd3sjguc<3%^;#@6=5ikFVRAi8=~5iv3FUf^l$4VJ=mcmO@}Cd9=# z1IyMJzyU^Ny9xz_h)+F_}f;HJDH5mW9~%QWO`5`7xiJc`;kgu4K2(a5wAT zY-Uk(_Lm#HN+S~I^#a^%sx!aWf{>^)-<0*hJ>{w8DD{ampyt>fM1QZD_^0W8Ho~jn znWW!_M_x7>{zn1&>PyA`$yz^%C)jQyB)0T$n#BEg9u|x7Qpoa1*buftFQl4BTIqsOt0>~94MAooI$ zqH41pLV_YZ${$PEnNkJX^Yi!LiXjX1qV-Y6_wn(Kr>?2m$f9=U^$ zs~ve$@qZL-YQo~OQ5})C5dwPQmCLk*BpevMFwotNap^8%){h>On-g2#xNEho$M81O zM`p&hB-Wc7&PmTa|NQ(27pHwX*%wq&23FbTduCIaeyY3`71dn1HLDhC$EITOV^_5 z*gLTHp7!lcSm{9#zc)Gf77OOhXC);jCi;l+vAAqL&3_C&5tSXypTD5-swqOex`q2B zgu&a+Qj|q`cZ_*oz9$H}zS&ZeacirG+rVGj6E5|NQK^F9yf~D-Detun zXser-2fevp8}_D`eOiMua&xe$IEKe8@x-F@dj0Lj&h(CFztm1fu9Z4tKxY#gNm!x! zX34cI{ps?XjhLpj^J8XytB6X(cvfk!(i-S>49%g@xf&7jJs_?-hJ|j=EInq*Xg}SbJ@Z8XyWYE zyw0)VMNHPGG){~XwZ5+jOnxp!V8wg|+e;WOuAYLO*2c5$n6pN^;^#Tit>fUpIypIc z=$UP6`?hCMkWfuMyolS445IHn^RE^3>&17}_*tuvJfy{xZfnN58TRf|8k=Jyy;G=Z z?02#ESVXNx^dPe^u9Ao-cL1ZME!F`=xNQ^phtS4m9YNU#xd@l!j6hmE7_ z#YdxRccvwtb+Vw{Vu;p@Z;;;wIoGw?p0 zq`-G)?W(yqk3KrqCAx$5dlN6lro5BN@}SbGIa(vptDwnm3-~Gme&*`+Y%eO+Ak2T6 zjqD|1;2X$%j~kN*_&&b>gTsj3zN&Tjy#57fp*kwjYZ|z>Tk&h9z&_;=`Tk})R>7_G z#_iXTGTk)Z1Y8m1uGM(?nwXG}~96($_844H^xW-^&Fc^uiYV-3>AFaA-@hLxB z4;`>HPbv0##2*&Rwh8Nk>F7917cp(9e^T;eNZ7j{^MRo056&uJ0QK_pBvuHjwb_Ey zaINjc!M|tYMg&g#nhK6SO)QJZ*hZWH^D;}0_D!*7TX;jo%C$S^ju|D%lM)}%&Y3tY zi(V0bU#)DdT{ri+Foa?pUxxu)7R>3{&knG1B}O4|tHS+GkGj!6+&-iE15&~Vajn|m z;&b8L*KR`AxHV)q`->F-{k=(i_wFB`V@ou|jTF#c8ikd1OPJky9yT|E8|r5D3Z_(s z6W({gz8Vl%dwL`~+HDtMOa8QUCpP7$xt#Un7Uz+KJ3#CrYxr1bfsxaVvRN`VuRQSW z-gBSZCUt6HX{1dAu`xyQ=mDBA+0hZ3hhq+rnrW8dL>A!pcG)nyt;i=>@ou*Ejy24) zbZZYK?$TTSIJGqtI(AT3LYUI0RXhGuSZXbIKOAB?N#6I|N4*~M;^mbMDycVc#6Nnz zBJ-q3v!SIe08>AZsp6}Eyw4xXPWtVTPQ9LV?rR2JZ%+2&&>Sehz_0(p42#%FqR?jl zFRx-@33bx6X9^_r!4k5^*{g5IXsF9Wt0ApH9D#TZ7kJuB3x@zLu)L_XVK4`lBcaok zJ!Au@g-{lH`eEC8UAt3{I7OrONGZFS_5%p;51c8o^tfO4Kl|7_%6bRL(Il|7##n1;=JJElkrKWReGH&8)N z;l;!vu5(5!ZmZ$tPYLs9F2MC7Pk@O{C^1;?fi(A=+3@6KGg;C}s}g%2yM)R(yPJfRdW$bAL zc)g0p!7_SIV`vsJd3^%o;%&Phg!N(12whU6{pgx+4)t(Sq9Tqsbw1D=LItZ3Bek8w zOa6S8v|dl!>oh$jwg&JGds4Z9P2n?e!uSt7r3N2JbMBf z9>9`tDG#2S6duQd5=46fS3g|9bKX$!^N#u1&%s#E^uUQ&H+7|lh?*<1$dLJ~+2>Y1 zDUdn6=!&}TG=U#>qb_s<_kA2qot`v!R?D%?!!jKaoxa$E0=p2uW6TBmZXZLC74x;h zDLEr2*7z~7=nt~s!Q!7}K}yO0Bnu?1MraD=^ZNzfqkkdtNiUAz`6QTE#R~AeV^~?_ z35)I#qMB<8ONNc%Zu8zqs3z5y5~JG2r4(DtK)M+}&ZB{*bU$TdAMPhL*wr>;;MSsH zAlI(~XSeka&&sl&JO(L4h4&NHor`NPewVq-gh*a=eS;utROg_H%gW#5Y#;oBJG|6$FdpUK263ILCb^ zU41?%1uyxIcOZ_xN3!*9*7=@TeHDiw#XQqvJ`c}gWP!7+sOLGCceO|e%I%jI+?nz- zKa_E;htZOa;c0xgh`?Uis~yOJpYC|fQu05s{}%idkTwq``5^g=u+&3-hpy0o8z@Pb z{{j8KpueWG;xFaGVf`wL6&<=)knAi05Srp!I+kJ`UxjCwQH*w=aoU|qx#19@8-Q&1Ie?3lv)(MT%4@iEH7`uryuqU zomBfSr@gy_-l5hS?ZwBsHl-%y7h9iLT%zr7@o%hskhVH3%UO=PeRl=irg-wMm3JEu zGMm6#7<@u=(?3BVrKOI=rrIf9U`(1lIXdg6Fvd<~&AU?mezv2%s-xL4F8LXF(?(5!$P3cF$I!~*BanL2gwN?MeUZX@J9NSnRLdlpG+FEt`w&$ z933-gd|ce}tu}aOHx6oNM`CmbjUX2E>xHe0GHN9acJY-lQSA}Fq3q`T()spoKEr>y zn{~v~V&w?GLYVUfQy!ZQjwjnW8m@cb-mA9GJj9Cd1JgMxYE>Zy7e@E@Lof0{1o>Zf zSHjxTIBI3)muK3dE_e0kiprAp=ci0R3tYXLwQm!>EP(S+=9ZK9ANj_6vtahs-05`l z?yle}zJG8qr?}CYK-Oa#X&~3Rw}}^q6csH*+K)3eNuILbpGaqgQM9Lcu~z= z>7&NZ82Q4n2eYO1H;3i(E1RQx%UB;&pd!x zYt(*!cWqXy#rx^9!QCTz@7G>*!E&ysnbKsE%gZBn(kcY zZ2MNnPMGTjZ-D3Di>B~ZNs7qabwg)b+xz`g-OWj+-Q#7|lI=D*Nv7NX!5)mFF(^!f zfbalj{<|{*>PCm{!gt<1BEjZueOGNU!-d7F;ZHU9x%P!tE+AXZUw+WS~NUFG@Bg!GKN5l^WJVum zA?fW(N|tt88WPJiN_ukkhO~m6DfRea=W>jSee2S|){@)j`ZjT;(A7UGs;p^xZL3`Qjdwhl%SZ$ssvN_IHYS~Yxb5?_ju zIS>E@7*UN^Fz>-~0FJd0-axJcC%i9acv2#7$f?I5T3TY~ir8_-D`K?MMF-wdQNBg` zhJ3Z&aM&CQ{JU*g2!%}t=p6>>pZ?UxdkhS3srbI2h+tC4ASjq?K3qCJ3knK{mLJut zJJg(N+TI?MzbApY0{d+jhem}(=B6#9)2DxkmgkPPZplYa%eVJ|VSj5VBz{KJrwEXe zH`fiMvO}7~RB>>JIbPm_)W_cw8H-xbm`Dtkhe?>>^Wt=D#OkEv$;v%)T_AP@xRT_X z<#OC`Az4H`eVv1Vg0eAk)}^BD?jY$?cc)Q;u(w%ibJg%p(|hD~FKVwHLlg0p2YhC4&F&5EF|aK?B{%%|mEt$u{T z22r9l=TR_=OqSQESM1UM>9#%NE#PR4S;xkKVfoRx&U19&iM}dRjTR2UOL@N< z3*&K2LluUktQwn)`iPoQao+nB<3OsT_ZI-tYF8d>3p)D>`$3t$AfY+qVKQ(+{2NNz z+|m}LMcr-&_I>gtFG6Y8yMmb;CTRUs!`V#ZYk51cuK7jvyyGChps=t*<Q@IlJMj=nhi&?03y$5y#6e!LoR0c?GMlYVDZE|tmf zj%AUV^Y_uXQ!_4Gd&6w3|95)8UI3!nNJ66Ivl#i=2;35JZY7+r4yT|r&&@+^Q5>Bj z#Og;_jx5UMl<&gPE1fYf(KuYl4I_8q_|S0_F=#1v6K@?@lUL;A2R=E+oY47xRk@A2 z2lp2Jgt=EfcPr2P5ELp)%-$;{JG-@xc7ceI=lj){LhW{fcgph$J@X8xu$ZCuCS^F8 z>*RWN;O2g$tG!v1vrO`r+a|Oye|T|m_fJGyY+|95!Cd z`HaQ0Y`U$l)}|PE|IbTiSh_}!Q5#T;W>2ZFHsKA!xs;&^n~XWfLiZOPIX{H+Xx*us zC{^vsoZtjYU>i)}pF5}(P#308EIRg*=hJIamCxTpn?I?PTDR8es9-P3=jk#KON!8+;>_a{U2Q^hTSYCkSoM$T=s z;@rxqpP?pUt^CfrgDrR1;Ht<6e(xII!AdojUij&qiYY~Hkh7MNx+GBpB(?`#SIF%G zZ-0-&LH;!qw7wD=?aF< zT*E$}l2nnsYO6?E#ZC#7a#_6W>3z%~GZklJ$wbOhPwk>RrO6oBoj3nIFP@<&FhovG zM#U-)y?wczo0}_&f-Dq@8Z)xNaOMk5Of`3Z)T}bX5TWUKbzuNvDXZ{uV@rG7w+wgO zjSPCWKAogN;o-TBjkm*(_4$TngxT&; zaCm&N<;fH6uH;9^yhq^vuwu_&)*V2N4F1Z_Q`Rqs95Kn|xuJ&wuxT`RlE=9CDFDQ4U|M09IyZW~9h}j@P+nd)uV2 zsOV^4U4@#jqjEgAKAYTMtp`LEA0kx*W3Yp5It4(eXa zk!1@*uNli%IME;5g;Ubem7D0bMy;2p*9!Eglrz@OLsjr@VIgH z;UMS4t4H8nvZIv4iPAry^9e31W9566nd=mU!Sn59eLa52DgIClfv-Pb9m_9z;IqYN zS7Y7t!e3{Tq1I+a_nXV+I4gL$VDfmN%lXDPutrfiYgOF_PtNnbKS}Nn&Py|p{)~Kd ze{K+*GL8RUc+QhnCtB3w^ILvVXswc(XuPF?@DDi-oQu2+x*yenvZ-l+s~Uqrb(TA? zJGj>3R%Wb%+s+D;AqkAZP@+zaoVKip;3~1+J}w#QxVK!9G>GCw8zMjwvRr7+QVB%H(d0wu3zSaOd4a^>- zxbXr6K5rsm>n)b}83v=L3gp(UCg0KflmtFLxeI!Ff~6i1?3OeDZg9}Z>!Uzd+M~ZS zpayB8tTK%S(A*Cff>}js%RrbK74dgM&JQaHxmz!e(4MkjKsh2NwKw{`?6zfAEooW{ z&!xNtK4`S)zv18HFR;XCudR7gR%{zA{sVt+IX;WGbPYdgB&*cf@3uTG`wl>8LgmuC z`}bgoBCl_K3wU{JNvD(sG`PC#P;x-H_%3_g%9k~a8S2wVt5Fv@m`(X=5JxL4X5#!V zwBkk9;7WJ_2l`We!(d9xdrc{{_DB9}7d6I}A0W$(!B~!)>JfI%X-kJA=?cKO`60ApF=VVB zLOsQJ;?Kse0%7V;D%8ziy4#hx4yp^wACL?No^>pNdp9g@oV`+|#XxJpoez|(DR}Mw zT5n{&pyZ%=jNgF=>>k+C%XIh5hYAT)F8@ca3cUUolI5}2$^rU81_yA!3Sx<@ifh(} zyhg^?6wDN!2*B=dr;mGt3Nu_IpNg(?t5%LUBF)Tlv)=&}r?efiAlsI0exh5dQq+ld z6dYKTu&ksx5URZ~Dga~TOltE?rlmt^r1pWp%s@?h<#mi`6lWj@3;M0A#F!47IV zVw%d?c9_u0J{96RsMWq@TEkzKj;b+M#TLB*(MFICB?qeYC8TTFV61nUs6T8wnpoKd^nxMXZwf-8$gO)Sm23pyFihm|gM3OfjKhyoVIC|n&saL4Ty$_=DWec zH8zZ7a%8B%OiBM6w0eSbZA+%}@8D-o^nAWuy}_>Kw&~=)=N27e&EDEE=!FBfC%t^GSi~;>6Mdjh*ymF0Y@C=XhxT*qMA3?E`FydR8{ zVVL#IYr{MEE}V=m}Yhf=>jEaZ83rVO?|M3D}v-K&FsZj@fB}bbPBlsI9_VI-x7CPcYN<~oqo_?lX zz2yZvl_Na3FA zRD7h&%#Qd8rq@~>1*Tt+tNOlqoYQkRI-otl{A{s4;a&6}%FVhKd21!#9c%q}tVgmT zg=?YPEh&^6>ikcv2#pQ1EM!26sn~Nv=X%uqX%LXwPiljrGNSl*l!a)w+kB))x6|g} zju9*aZ$qwquAsqI@BJMlsL|w)@>Wc!_c+P#>lK*X&c~@$rg6glLv8sFClVRkhlv(p zO15hl!1eZwb^wE~0}xq6NmZ7&SZZ+jhL|`r%CpQ{IKy-KQ?rqG6rli$grzt(TbLzy z8>aOc|CqpsUX$mSc?vS$B-n8P(~+4BK|3_5YhC5~W=*WTuQFlGXNPkc`pIo(DR{^z zU`^Aw;)?Th$kV~fzL)$CzF-}ia$Imq(R=e1AzKpjtSFaj9^hL=kk2lmxXGClXvR(2 zwdUU-2D@bXjd`(~VIU{o6RTvbcK{(dhN9-AXc~C6XugG=Bi*#&*|S91bifqW~<0z$}lMwh(L&~lkHW;abA2yyizQqGFB2i|#Yc09nO-|J+YH>3TFPGnRhIFhG|iX z6Fk=__-J^%ePel>6^Bh_Z&SQucM%aJw;eVIgL;74!&?FL{mj2rc78tw7+bjRiq!W< zR9gcaULuB5b{IL*6!dgBvRVEu;}QmrWPGCE26V=)TYsD|%jU{T8p;P#Kqb#K6;EIu zQ5YW)$f%b+aku?jR-%-ySb6xtf)2RY%ShQU2RW@V{xbs$r`t}&Y(7{{BXdKvtn`1$ zTHF`ia8ziy^L#XOjW?_^`i@;XZcvif+_bE%|BNO|Cld-5@v zwN!I_vfCffyd|3AmqUtog=uaWKi9tJI#(i5TG7c`)M~z~hI;yu{9E4(M?4^4)>dubW#>!OfkxySvMCS0*PSIBn>O z_$%^X;a;mj%3mqE1__js_1m0L?0Dw69z8V!)p}ZxBUjVfyN@h%bH$)B;m)YaFZHUg zknhzB$NfLH0u_-%p3!q&U8n{p%h2zYB2*@8_f#0tlfeWZN@;umpk zYtDB`quGlK1nMLdR|I-#^s}*IrzU=k+jomFoD1$NbZ89BKq;OMr}>uzrlPw6QYw%lIPEG)q@cpjwdlNd(vHZRun93a zuja{)HQVBzBX#&#cYEOGS8VC;RXopi0rEcf3GvknCi98en`Yu*$MZ&_&_Xa=Pb;J# z_2d`VBe$5On7!;%9#&=Juw!I&oMqvyWek2Nz`zSXVr`yr>p{>|N0^&wzMTvU8jm~q z5s57o1Vc754Odk-I<73{+WyjM9c^qvz+V(Sez4M!rcWxE_($>Rq$)W42ZrIieYCYt z;GyxUkEi_l;CXyfsr%EXWxhXw&id3e13~L|5~k72t*?5=VY`##Vo{TvbsZ;0n1Ay0 z%|`fK5zqPLJLc9CTEJlCh|MtsXz`O*2%oNKb6{ZW6Pvc$p&;n!DWolyi$TEa!HX@c z#a}6x|M-J;D{y!iT;7%1y%#_N{|0c%z%ZD1nf0{37}Y{wjgPrIwDCOGp~C-InZyhX zfNyY^68``vK0?tO>EewmN2tSfZQ-i%kVRq#wc?prwT;d4IC57QrCg4UwHvOWHD@Zu zr?5h5Y?z(`9mdLT-$um$yoXMuAk%}hZgr3EZuheOzm*%0UyRX!SX|C?@>H=3M>XAI z4Wwo6^^GE1H`O9nYmb|p5l5F_jF@oNq?9<4-$xyi(6mckRNxJ>BDLm%gI7?PmAWLU zI7{B@C-=}~mK5P(jqbt#BmEYec!&UqzTSTQj(mg~`sN?ammz9U^vZjL+Dk8(!;OVo=z%_^{Z=pOn6Mnl5FiyF^b zp7`>h!g59<$<%7e24W4>Drw<(SFv#|V7|Y7hx&or0mh*|#X;HGtt9WLYRYqJL!?o~ zikn87dwq;(>pXqNE);%I=rwrcD-0$yv?=XSNyp-rS*Se@kIx47UrmuE7x-p`D-8 zQv#h8EPm6Ly=#JNQo?^8pR+~T*Pugg*Ln(cTsahtjNevp5T+sMMso7SfMt3e8WVpQ zUKK1{&>!LB)-Ue|k{u-hkB|2qc{!iZ7>-W#*N6=-I%s8gH#&LRR>FMgAS^A6RQl>% z9wYFS85Y`uq-#FhBe-&mPxE))a|##|KKL&k<>wLpIR1WfT;)M=q)kv?Ws{DCF(lG7 zEB~39%7q|geA%L1rWO;>?Z3}{Kz3s>uPvzxL}Mll&a&BqVvkFj5VX?2x!f3h0D>?C(vLU=Z_&ud3vowF&mJT|T0qtWd7SYsojKV%QAptgTwZvaQ1 z(#}TNKB!)mN-N8ew{+*MJz$NqT^3Ss^*{$)Kz9n$Q|g*h@$Ru&ViV0=6yM0eS9--c z7N})h=#q`liO`gx}KI1JSYecAFzI=s5oUi>>t>-bOoO zvb5%bR=1?%k4U)(Srzy!*n!{zG^>)(IL2J)8>WE6LmegMmJ? zkVdqorc78`U1+Hd?TLCmMu?uxQDy_u5>^;YP|Jy;+E%oz_=eVMUyge}5|fYwg`U4R zWcuXgTOVEE;@>FP$P$x0D?j2CP3I03%>TlP=UduA=1)6MP=Kx8`1m-SKU^K$kIbeb zqEBOSnQ6_k z;F)odZ)bR~WBpWOKXtBh+!yjR2=qQ-xW7k&KK2?_WGl5pR0A0`*ZKy2M1n#j-=Za^ zVTprGKxJeK3Jm^nTsN{`C2G7My5&-@)twOd=h4f^DYo!+vNPhru=vr8x`C@=-P-zR zc)Xz7SMjSL)aXl4{hOwm#6-l9KBkk-#F5n?68f1R@EZN&0$Oet0SIsugD;le(l_F! zzUlPGQZ=keZrP7JIH={`<+f0Ox*g#iZVR>6tZ4(!77@)$vqLQ|0QMV#1@f8Lv{WyM zfS0+hS;4W=D#jGG$RYCwFZ}DhKeI;Pb3;5Lgx2k`sduJKUzl=_3`W{`c6F z5QgdS(LT&rR!}4i_qyXw7D$lhxlu_RfKII>6G@0~O8OtZx4^9B2;U6FM#Q#Kwvu^qw6-BK_4jK*LqLQ=lP4)HRKp3oHRl#v+1DG~6S z8NBgSl%9=M>USR>_zg!Wh;h7cM#E_zJi}P4h1?v_h@w#YLi6?JyU8&YSd!G3a$a}E zU*qnX){0v1ht9iH%Tsd6PZYDHq7KV&|7f{hRm`HMFAhf@mror#S3q) z0Dx-+Uqi7DM@a8z#-a2R!dRsZb9HUitvd~;6{dElw{Xm#M}~Ji&MNWReJs1eB%n2FyV!95|I-D zjhzse{WWJviyhN>7ufV35eSf~$ArYr3Id&hxE64e38|RJ&xY2XP)*VYHDbGkl zxU^*o>=?ATl&)#>HADarQAUa-L#v43k(~Ri*iPP2MA{`jM(N#4?-3 z@L5gk5Rc8kfuX9e3vzbbIoG-`Th-1~Pp_+l(b43$_Bx#EgFXiJ;Ke;&%Gd7jT}rtp zcMYU%9vPv@E6qxzk@&qSV8ROhsYG3rFfM{nEG@J3n3tw&riN?unb=l3?RZQq2i|%B zGpTeeD*7si#j{J%L!dPfY*5nkNmr8uRyYW?=Ss0-ByNQ{{9o#s?vQdJu3jKLQQZt& zR_3|Un==!vHV_Ujf6hT_BZ;pv5UN-*Fr!DSpC&mZ>%{u-{xpRtNX) z8>Y`{y!6QHG20KFbgAe2ZR&atz)J2N74m=aP^zjIbO-haMRc3O1~!qKHa9FsD53sidXUThTOdeVwBtU-6j>t|~7oF-59; zJhN_5^1~;{MHvXU0FZrCRiHrIxyG*Y;!x(k)Tx5BTgxQg;yGg40cG|LdDAKPHJ$~x z>|@YU>r`hU*{sxny0B**%fhhED8q{|_$P=%B zy>mXLpl)Z_q-_7PDSYGfy%D9c^M)e(m?}h#h3f_S?No`Oo+vq7E@%0Jr$b$xf^Ff~ zF&bvv1+Mk7lFeeaxO@_Ks(o(f(${8}Q97=edwgsY)oB9W-B!QuF8<#)5*w`XHKQ4* z5&Q{hN5>18L^~GK$#GtLXK=RKTHO6jup>xnHCA8%Fh!ot+WUPQ59N97 zVX!j$Y=%!JnQQsU6vQ)aggk1D8XGNs zSghLY{uBl5zkQ30y^i~aC_>(k+u9?0aX!2*3rQp6KWj@f2K5KQrlArEaYTYWW)$*a zdRs~Ocv@?BfJVs9#3wamY+9D^E?ItHB54l-V)YKst=MB5NBEkG+4EMyJPg0quanda z3QcauD^uf}c5ZrNFZ*j~;Ju~YhK13nbEsU8HP#Ik8GD#x``zle5hK&O=oyk_@sxy& za*b&>;CZQs_L|UMuuo(TO@_B=<5I&ukFnQ=3*9HsBV%71M99`6D>QYf#M#};>+#!~)%1xczi&jXz}%BJHt@tXt7qyi%c?EKs%?~C0K)x# z#sT`m1VH%PCO2$&M!4T=dI%hx*n48?Y=8Ruekup$3)IyG5SGw+SkjZ1-O~fg0(u1{iua<|Ra zdayri20IoHCdqv55ww;hqqwyAyatls7PEOwNHwKxFh+ngk|w6^%`Iw({OOrATb-AT zXny^GFVpmE;5xg&3l7Q=O|QF}aKb^RUwr@kTJFmBBk7gvS|s5><5 z&vfyCzEVW37x%5?p;~JDX7@r22l>qU@+UB^xUFOLM^xpP3!SF8h7+sp#wm`@kDI)w z@JsQiGAhzU0kT&pDY0GPsE~a2jG4i*INO?2N2naGHIjk`ZrJeprsyrY9{W=lT!NZj6hTXDEk)WE>=^-%HXbnj_FHUv_1 z#B1td*)*2E1ppbKtuHn%mp958?=bDTfW4P@?i=S~=#2XE%g~+L!(i1yiwS-S2HAuXKT8rl@u-}f+$SL8Lzq0+o}=@ z6>mH)`w03O)UNt|@Yy2L9BE5ANxYKRli6>zYUK7{O$GJO6QYfnrR^zi8azey*!$8) zXK#8RL2l}p^kjOSh1}a2AbeUIeBoQZGoV`MLLP;(8hGiq%1+m)u}8^M>l>B?XR=Rd)tUuNc0dxiO+purYw2mb z7kkVZcuYW5yXbgoPkfW-x@TNwn?FvF^_WPybZ3yNK_L7Ht`K_|`|&M}0`$NOEDK-l zHD@?B%6K|!s$c6>uMH;SVu?q?hvzGqKqJ)O>$XI5Evt1>gKyCBjw~AlH>lt8KAFoi zBuT8%zv6;HFx@;BJF2kM!L?7jA$lXP!ZRj4w=gR_G8j%5V1gakb6BE#H>{80#g~%2 zuj*uJiZ`dqVGz$xf|1qs{UHDt2 z{MocD&?ZB5!^F8&o!s%5QVDeLOv&87A?7AaYH(fv>X1R6CFyuO>AA9YM0JpOKVYeq zk_Q7e>^tXu58#Q2orqBp_A=oPFfPRSSF*SSKsbi`RMPtAXV+e7LDuA(!$D-N-`g}1K%jPjVWa^}(I)>ZW_)~FQ?mqV>zzM_KE4U{>}65FatU*f~^wykRA3DJg?r(^z!u3&)9F3RyU+F9)46mn4*zz z&I2VAIa?&wSaZ<0TV*mi%A$*QF>^rpw2uiXfTXmK;*0wOs5;}@emDj{N!vEQPhT0o zrN)ZN4HQ`j)*na^?n|P;Oxmq?xxW{*S!7D&TvIY=7u8^RzxAhUAef3}7~xxo(mBSm zLgsQ!J(x@^B_m3HQU`{K}f0HL2$tL5~@v z7}L#_QH!jD_t=^MmR|CPuzHgKY5&AGt)ptQ%s`~@Oc|i|?O<=C{#fB}5CH!Z{3z=_ zWxec<2b7r5$fBqp89=aTfbqf+;QX%PPYdDWg-^T|B@ELOC34x^K z=q7;Q)Fpce5-{M)UX7Yv(leS7SJS_Enx*>&D0rhAoK@KdTs|S-49i#Tqg>EtIna;y z0N%^em7mxp?X)rb_qif%bO#C`VRMHaTw5C8?9u}kd}Wj>?Xa!BFg-VYXj;aozTCH; z;Q%4NO4WHy$ZZRXOq7A;7DZOMvC|4VCssLp7-1b(eAt2-SE{{}-p z_B`}yUQ(N1u3Do7QjHoJ=7wWr1ZNCtd9f*QON2F{v$&}egCKT2B&_W7n|_A*i}Kan z%VpIDnetgWMTK1lH**eAVJd9Q>>A^Hpd=JN-;lBWGJ7=Z9=&zew)&C? z|Ds@kM|Qt(Wpy6|vBSs~tdCV@d|joc2(=Y>(PU@w?%Ct!PEY+P6%=Ag@@9(1#VvL= z6&91E0@GI<>t6z-nZE0n!~6&VjXL^Mu#JZ~;aMWkCAUBo_e4TxTaZ<~&$(@Cajqah z`x{W>VrFC{NQR9pjCivVAh!n-jjJ_R;IpWeLVHQ{qt1ZLu@8cgC`YeF{`Awk zX?)+}^5pW{KZrjC-8a6ad;3A9NOS2uT8oL0m;)A#?_V?&K9z2nztEWoccB}3C*8Le z-#YUbJ5L(QzD94r`aJhm-7f?i)ZAX2#|OT#k^KhK69yY@&29z>v0L$wu0%sNPIuDF zMmqh)b@aM7=?VZ<_{CKzq+&-8_MLSILErgt_qc^4*~zXej0+0V&}d&yl?BvmjojE^ zl0)@eZPc19@Vw_0y4k-~fUgk*&kq-%k&snv^WX`SX|btroN{cb`9O_SWTY@`HXlRB z{^qr!^~uA$z7#?mAgPlA9(2;NNvJl@a}GE!yO)jo;x9{fcO3{rJ^4KfJ;o;e<62Um zzCG5eq>J7w+Bn-6iYw3x#KK#QXAh$e6O>YVi*4U1VCEO^A9dE7D~a^omTWCcJ0LBy zI%?Zjx%L6g^C89V1XjYby4cpzq+S?t>DDWL31@Ad5f#3U)0Lp?tzwiwNs7jE91p1O z%Xf91dglv%Tah*aYf2Cn4m~1fBN_!?DO5I^-ba*md-KH-tZfrCYWGQboMPvm~dbNc!M}YJtBO`K^%imEL zM@56mfRTc79Fa01$_haPwNI_lOSm_4rSCpw61=pYOOW8o3JxJ(+{uR|R|gte(+hvu zUcFAl_}T*U@CBzeyQG%miG%bKV_lw-@DeIn2}4PZ7XTw_-kUQX;zEKAZwO@Y_prTN zfezVl5gw2i6PJxpo^$$^Sc}9}Yr&$Eb&%hNbi0 zd;!U)E!tIy3%8Zt?4}S3UULR0sRs{HZgw`RE}&FId%=pq4~uyL?SYaz3<=^l3oe~v z?TI%Y+2fZ|Q(HJ-;Z1Ixa&t)d*qR1{XZr3hOW$(AIN$e1t7w0>oco9eFeudtM3`9+ zb981E33oIQ^DYx5v{IYucOOY@_e!{aRzOblFwVs{c}DD?&LcnOOokFz7! z=Am-Qt#^poth)7ydmz$~HYJ@8Z!{xK?Ti?7YGikSak2Tk5K-+O_KBnTUf|zrVRto4 zW|vIWeHSm6?7~82inKTjL`S|ueX=C2j=I~cN0&49x*B&xdNn9IAwl}Xhq3-^`(dWy zy_rj112|7MZwhVtH^XPK+NQkCcB7)Df(kS`ixFs9@@l%@m#*@wjso>b+YD8k5_j<^ z9pBC2Uz_j}_V;JZQSB%Xd7DFHr2!vtbs2E-if}C5AJ*NLCl(;TDw?E~xI2np8-sET zTo0vh1cbzvE!s{Qi;RIne|*}=G`%AB>$Sz}-%l+J*K2@VZRvlXINX~MGxugm>~H75 z-6w8SzugbNzt>GK#OfiON*X}&mlojH@2+M>CMOsDNe|&xINVc_oVw{AJZlzSmx8%$ z+1&$nL^jQ~B-t6r>f85pM-{}Gh#2NQA1x`nJJsFU@XhYi>_4uTSsQ7QXEs4B6d-6f ztDBKM%}`xL~hVI7GJ-10mw@o_0O-ft%$ASttBe zjOMVC09(VCs#crS4s2?VB>%oPt9Yq!KK&V+1H`LR0MJ!_bf`gPIeJxD4xUiyKq2h@_jsk3R4 zk$Lu5ozo(%o49&&o+dm88q3KWGMXdNF6xUzM&yMC@A07(3OrDsr{6SidhJ)^FQeTY z;bR-i%$>CP9^V0oMcU{RSk>6(>K9+aB++=<#aG4We-#7lyv*=KyOylKbWYMH?FgUH zTI?6PJ#V*?OKAI1haZ_3@kS{Yr>-cz5R*J4tLg}b{IGm_V_$I6A>=EYvVa>FRDtFR zA#O@qW7Ipb0hZ?*vcoHycFLrHHePb;S=TaLh1vA}L>a{X-ANn&Xitl&hNor=YJIIm zS&@;Xy@m84*~gT3JcBdsAsXIak&$0sHg8>nlvc3J07`t1H`vYZp*5ZiHSOdA!85&W zI-7Am372i;s|6KDMM#wiv_h9y{)-Qhig_1025l6BoB8#|G=_xX-f5DaNQB6{A$bSV zt!8Xq?;37XCl>ZlPA#`cFNe!kCW(ff=leb7CV9N?I<{Ec68Vo;Xy{%Ai&~x@1PX|9 zu|jTNH&$?AI|5&itz~f!55H}qB#<+s^PCUWeM*fkhZ%NtqHjZ|aukqk{aKrlY6D$=QoMR|@B4YI|*JBcH+A3@D`G=`L`HRWgdVvpE@ zZ-{KR(>@f{ZpC!3RWRx%4o5r*_d$b5LQWZqlzPjBkGzuE%~ynPM%h&?v0N`v@k5Tc z+5QO57-k>XD%!HT@4f2_gDS#?EYGe(T`umUV}Y;)dmWGV*F1UAoSnmB29(LKMOm=P za8MQ#>Z8O|WYbq89j8<*amcn>%H7K^%$h}hZ2PGtjrImOdbANEt8;Nq7_!z$Hg-V6 zR*PMhFlEhh8_Ey#K9rn{EtJd{g|*tUqJTX7I{d^tLrE!*k%C2u>taj zORwuo%O1LpYGK90BHSv?i>ULB9)YkriGI~qaf7H`GEtU8J!RvWr7S~_|}`(9Mk6B>Hgw;G{>KQ z+_^IEY)LnL8!Cs+i-7o}F$roT2i)?tGDGm2A>?K_c`4IWTAi2s89jA%Ts+}esUQ^= zc40bT<~G7s1BJIMn{T{vXT_GsCb)SO=Z;qm_!>iuCc`_Wj`xg@aF#Z@G zTn+x{1|#6-YV?Cz{8^dOF|6Y+$9e{&UJ=ntn2p(tIT}Y_9Q# zNazuIsZ69x1_Obu+f}h#rZht{Fl^Gj`<6KL_nA_c{n0p>+MN(zdtTG2ZT z5AZpnO$R)%p# zR($N-ys%g!ukVTynyBxU=yH_TZ97rysI%^uj=mK`YVEjBmOP(%y7 zbr`U7V;;1-nzgZZaHWJtKVOn@&Sm)Ep19wa8~Bu&GvyWaGM$EpOVj;2W8THZr6izp z#TsGG+tvU7%%e`R>NM{Gdyup)>>nqF;4yjShEpaMT^Xap&Pw943-^4_Y|rtOlfV8B|BE3gHi5!78_G90*`SzMw9_x zw&N3QYyhgPuNF=AWfMD={q{4iDlifn*98Re3M%aF!lfl)W)xWD)%#EEd|yZD)CKLM z`LM*#`@&IJP0+*02>$?U-KfhFzsY^-ImoBfTvJ>df;@hY&9vQa)amtk2{?IyT`k?y zLJLlLNmplz!~kUP3g!HcDtNbY+-<7x`p?cE5X!TvmQ(o8_cCnH+_;277}BS<(~d_@ zyX7u1(I&1xH^~S}m?+)@!+mfxzC)Tv_kr^pq%Y>w*pw%RcM`-@Z<#R@jJrD5`&uZ= z=~Uk)Xo}kJolA-fuEoy-x<+Z$Di2USBIG5kr_|gUIQ9<+o;;bJf-S4#9*3@#RhjT! z2>>NSR)*>`+)g33*)LzG6=t9{ZP8HaJqX7jc0ONWdGNW(jL|iBqm*XldD3MIx~%fW z0k2R%GFgbV#NqHWyMeT;#r2B;Xv(kImWhh!iJQ=vj}jB!*e ze@5U`%Hi{ow&{pr-1Sqo$!+~t-T#TWRg}_2$Sw{cqeVJ7qNBA>hXiqR@4%+gm^Z%4VyXBvb%Q<1p~=jQ zTx{Mg;KuhZk}^+<=~Dk;_g06J_*8i?Px1Xf*eqHF5U1TkfHWlV7l693Pm67c(VR3@h1Iscy5 zKabuE)mP#1AMeyW2nb>Tef#jhIF(Y*T9w;q2BaqP}rXlA@|Czgp` zju_HKlmm3E$d%BPd{xnQicf7`tLloZ(Lr_WlQ8{E%J2HnrrxEBjgkOap@wc!&7^W297uCL%meWT5Tbepb=tg{_gMQf~` zl0<1OC^`_@KV~3mFE3x5?A|pnNGK3ee;TwG(a$93Pw*rGL9h+SN}>F*>O=c*X33I;$YmWk}}|nX_U+L zSp0cETKv||rQ4?v?4-6Tk1LE)8(UEA_k`u=;EO{=TOG7`US6)^tYC*7wusvQ*uI)g(s2cXKo%iRPHi#?vM|ZAk11D(5rVuBoImmV)`a2e}d-**spK| z*5hlhaRx{ycGXXrq|3@saIhpC3_jL4+uA#_x$<5(vUt0}Bo-btdHj%0jmwWPawP!M zUib8La49d#X@|Gov6>Jqa@7^sXWQ%D4Lmoh*CwhSENZVy-Z&qVCvo0;I8S%1-QD^> zV_S8%Iy3A-!>Z>8{C!d&afA1tLoXCCNx6H!B=AavIS#4W$6`R-+N~k|Wm>Uw8_(F% zL2cv>U6tUS=^5T0VoXVsst+1S(KjOM zmwJ}Mn>>Q)RB$@Fj<}ciS{!^IWAlaw_==ob@eoIdU*z|E8Q(R69y&aMsCMRF0+#q2 z{779>do)YGh&4{X8GC(sfRW+e7D7Aied&^=lR~U*ihuLmVQQc2M|=~H%RVEZ_1OZp zP{6^LCwSkQgCCk!v!;5Fkng7QF~vc6tfhn5OL&M(c1yb&nnYJM#_1&5vuFCckUzek z`c2w@+B0fdkpn{=`I;TgdERm0eo?6EQR6u}7Fesx8!C5rLajlSPImWbHE zO%B9zlwT)@-0+BNl?NX$GRT_E$!NZTF#IwHdH;=SE+VRH4wZl$1gFg-- zKO3C(0&__GQ18Er3n8I9T_PVFm^nT^_F8J)dr-W&zum?$i&!J5U2A5QSfJBI3|x(M zP88cQsfO+FPQT039>SPK8v_&L)2SEMd&VL+`Og_F zAr>TuX7SHYIbS6DI9m^vMkdnop3Kw!T2tWLssvAGq>tNsy`2^XnVD^RHg^O883||> zL>pSIgTQL`QtsAn>jUI2F2dyCLvH)v(3<90>Af;*ts&^mm{I-BhInI*2buP@2g51H zH|yn1T}(1AN#~tSfpLE@NnOYfoQIs?>h0`|;uO5kSDLOhE9&4wt9|c$e))D_@+Rrq z_iv@OU|e!@tQd8xlpd!G$i|hObxla$SvSH7Ev#W92ukNCzl0@shYfFqTO&1b(QtaG zudl8Xi%Al*U=SONq@$+l?Id9a7rG%qw>53@&Gqkl#%b1{n4qfEC0N2Wk$PcLB;LgC zu$sB-|0_zsRi!jlfmnM`X~(i}ANU4M4ED5yfi3DO}w?^_}Gk+D;jFo zc$5}z6qfwDGqkN8G2iq9MdFgQzxB}6YQ|;mHLHItlqqZ>(M$6PUyCp=6|8fyBTKCx zM_l*)tD?-SUne!Ydjy4AUfN&%I}#GY@hi?0k+>jo|p=w@2TUY%m{SU+I+Q@`!sppM{ z^Q-d~D`zbuvxz)G9awWx=cdG5?)~l_bRSK3HYq?+yHmns0#o9HSpS{(4_@H4w7 zk2!FQce*v{VxxqmgVEAv!}!}B7`HrBa6V|JeQlE|?F!qn(TAOC^5k{1hd&HrMahg@ zF(N8Vc)kK}VrhMKSqeU+ec**IYIC0x?G7-)elGDPm zC-%em{oEf$Q(jhtY5sz%!Tt3b=rsJiV&iOw@L|Fs5{gW0Pl6iGcSCpsZR5t>)QU(# zteaT!{+DUFHGYffAOk8_lu`4QwmFP8uFB*i8Ot*L?MOQHGep6j?DXngx<)NxM<;Yt z)IBrTL;6Q9T`b7)m2D7c)+iTQzxofyTLHhgQkLzHwFmJQLKHNQr;5X41Q{sro&BGr zi7`|@A}zt4Q;(DllDQJWHq>v{1}4n;^y3F6 z>rZHVcS}V2Gto(Y+NtP^|9k$-mLfe8jDxZ!JvgazI?0e#E@}wc4fdhK;y7@ueD8js z&tW+$Au+L5!%xCu= zXB+nB6%AHd(4(=ks4;bT?m^P(8sPm~o$;435TW5b*4ilhy~}S2Cq;o6F~rHI_%8fpF<9 z!Hva7V#%p8ePnfLuW_9u`oE=-4jo_UapcU{WZRw@PgCrJ9M1PR8vKZ-TpJHqGq2eL z0s}fzg77TE<`4g7DXY$>G(=C08@`o>X0_d6YARw@%#R1G&ZpCA)t4 zlV%$uA|rEhbBU&7j8=X$Sews~9lL|cc_$qh8t*)6-S4?D4B`Dkem-p8rOEr()Q99f z^}5@aXzSl9K>ZaLAJYEqpY$V~`5ZkCkFy_%{^U34uku@BI04MSe1ryc9&z9=7-jd? zY$K(eUW1*Z=PngVQzcJx2W|)+1&J{b#@E zQ20!n72rza(C`AuC!Y9efUnK%%vcA$%fIYdRLdeO(|tDQUm+M_13N-rYh9$F4%Psr z(YwpTeKTEQpgsv}MHB;%n1U_#H`Z<<^dyQ1+ zPhf_NdPhGXM`wXfZmzdM3+6Ar&oqK&NKqsI4YGIE@b7ja&pw+m&%m&+q0wD44rXk; zK3cI zdAoWzn_@bETTWDYumimQ@@eNvQ?Fa2B=no}h{OTcrg_e4d(zLKmqeDk1nqz2f7Xtu z=APKc@Vaus!Unh+d5`sHVD@P2F}E5IN$-wdN|qi9qt;=!a@x_#qzmkFv=U_ZWXzmP z$#$Y~noSr=Irri|NT<`ep4d0Es3)!!-I;ugK|~~Hp&vBiycREUWro)u+I4g;z_>{e z-sikZ*vL$qP#7nKnY>TULmvbW-pG`07-~(cN-Wg4vO4#(x&aLzM4zIIJj}4;Nd?6* zN7kRbls>#dzJy9e27oJI9}`N zkDGhzhBU<&e&8~i9_uAB8AeWd*QqDUqT)oa$s7HgU*ZIyKN^(R{_&mC2=vvK zcI%LVCl9l1DKU&|zruHPe=K?|?zRCx_V%1VXW@#XX;!t(N_osi)Tnqj>Dy`sE%sXF zrg3&kt>9H|7m;pcjqTVcJV3@{a=`G&$F{9^GiP>PFF#(~m!>JY~EGv>kBJ|3OwU5?FP zdTn^zFxGRV`Ayx`Z2Esn{KiY32c(1Jq>cMMILIw&4?_*%)nxJJM_eaMXyaz7rJPpt zFq9ffu@>G>cck8Q)4C~bP_SGxM5ou}OgDj6WH!2jWq!&BDZBj#)=G@XpZAVPt!(M< znzH*#N*Z=XSxLJv@N<~aUWd+=8M|Z##;#1YK76V+)=1?jlGN>Q5L4 zLy9WUZr}R}cgfFRjSYFyMlyZs3jKo39m6j5gn63-dgvJqM*F;u7(wgv#uD3To33?O zx!6M&_i4P~>YFvf?E-WfS;=j0LFz5f?^dL|R8HO8F0fzmV&!TQ!j3G|aau;p+IHr&2^_MM(1 zJKKu};6}w2%|OMb-nKiim(|fn(=I=L%amNtBO$po%%ctBI68u*&Y^Z*#`BGEz(9DuZkFbR~68UC-#z5QX zxyWCRtD9k!7bH}SA4OfP@M$aeGxwKub)Ec!nTluJ&+<`hl#8BQ#z_Ex*nabtX>%On zf&T6KLXZ#euDkWST1TlDIcHY*hBvyuOyb>|xyrG^$2lYBldK*jBPYj5z%a{jFKE9| zz^qN?>!nMtVF;zlt1=^B{YzN!-r{*G)|=0b^S$FLwwV#EypN`jrb>-cHW75H6wjs@ zUfDossX2pU8+Z>~;t!`WDJb{}&SDeF{PX+7_3|ohQyM}3*(m71r~LwG)t$baH$1Yq z93?E)6aj}c=oJSz*>|jS(jGQa;!0%P_>^Y)VMZAfBj!hkQmDa325S>KJ_GIK_4V1F z?5n_6#&UtF`PHFso)I>gd-vLhgmlhQ(Vug`I~55-dK{fy9ak!h4mFCfey-}j9#tSu z)52OMm%LgvDHqY-NpxyN7EJHj4y2!Pv^T%XTiZ44nl^{`mYhs)Z^tneDyt&2Y<~8V z=FteY?E3j`Y3E;BfczKv9zg+RfF}*+Pb2k->AxvuiRrGQMM52toHUdiFk;-$T| zTjyhGqaW~a`JCIUUwXN9>b+#M)GpUwxp354={e)2U`>Q{e5ws9gws01Fz6`%NU@Z_ zvg57$XMkz!Uk0S$zqrj85fRjV$O$cdnVA*LyODDsOKsA+p}v zJP^JxAXsyf({nQX-t*^Q-Vj$Rt6%C(g~mAW4y;p?%8}G1_6$evOUs-FzZHM>yqyNoU!?izr2~W;DkLt%A~cI8{@Ek>m5SOa z8CepP7i{|(+O)w|a{@;VCDU*ZRAnq#jIbAL% zBrH)S5;Qyj_QwjpHe_Pdx=Ym34RAX36CyNZI($yN-7UAJI-D~?!O+KqDFtVW*o|ntZ1sKDn5#PYk2RZ1qS_f`&!!baPkqjgcM^rJ`8hM_6M?$)#1cF0a;7@|xUCY#J{}_(MeyPf0fp0yyaC21t6c zoO?c{7TDy1Lk=I9>R$wt(^^mUcKerlVhc(7-yh&wFZd`^Z!+Yu&LlQqcWkuOUx`0O zp&$`<(#G_Ri#`$Y5?jN&)9`Uptaz-hf=l5|?MhLW0Wx`F_hOJ57Ie0(j9YD_H>#Wt zAXAY&ck;YuqsYzhjSHsQ_rVXk5!FslQC0i`>l(khi^w1}P8?kP0%fgG9UtVWjL-4?etsz@>Oplm?*t(eh#t={2$rBZyO#o}4J ziaIWJrMFw3@8yT;-5ebiWoy>K%RGZt)2BDBKiHbh@a|433XgoY+!s)hNv!$oe}#a1 zvLL#e!!5i&Raebf?i*K$>gE@}BsNS+Tw?@l&WRTu=u8jlvbi)lVt8s>KLr~$Hh!f8 zIrQQCN+>)xukoYE^}V^Uuxv|8BtYf#1VUK;u^YH!ctONbMq@<7?KrvR@BuE&C@|xH zF9H4x6H3cmWJ13(qSGG<2D1x;hoB_Yxd*I$e zNlK=|^J3j@ODqUf$M>!eY1~s){!Er^u0l6Uq5Ui2?9M1jBXtIEDxsyQIR1VcuC(~| zwA%on_*cf--RczS{perOxX3U6$JZ?TtLy8p{uJ`RKpP}h_k3z0%QiHmxcC@*^<}VZ{YXEDjIVq zSN2JaJAPg?fR$1p;;~;mY@J9F6QZ}%sPK{hPb2Ri?2kZKy>F;Sh~I}4y3f;mYzRL! zZsCxP@$wyV?6%SOf&<3Y=#hzoQPi`SoTtUlIid3lqkKl#?}u?ldg z!*ZQxzZWxYXEfRA(9zGBqvb%bech73f6j5CE22JTYQ*?~#V1T)>p-XjCWJAozrGwx z%IRq4XXsB4U{SPaP;~kWL;PgC*x}(L3YIG%`cQi?FdhRH*2@Sw;XUgBS6c7KWt0Rr zvyJnW28g^Y`Eu!MT*OGp*c6%rg;4Q#N{Efg3wUh2d!(7EvWHozF|llU<=>&w7;%xv zcu-cr?o{gkewq9ku=E~*j!VK_8#j$_JZmaPH;u70+_IBV7Q9Mn2AiD%TYB)Wk!H zbXr1pC4*UiNPdc?ld}8Si4dQ>>%$gzYpmi>rM66a10FIK+l+W`f{z+1|@P>|1xX z)#sd2u#=&^6^A93(fwT$;X;DkHwZdI%5lB>a$xLP{=`1N)R)sI%)GD7Mt!fp!sT!h z4rHrNMVxzaY)>KjawQ?{pGD~8ylcI{XXWj-Xb+gV>rUnBUF#vsf_w6-Zs&w#pgIsT ze)96SYX(SXsXGUj+iji!mi0pX)B!5vjUCz;PNR@6t;v++Fai&Ei79yn0#-7%q*JWt z*tk#-Vds@SaW_bpvaBe!{`8|s8TymfR@92O;1uq&@bV)v8;XnUD;>r)3-aHKo=wQ? z?CcD@G~vJE>Dnw-pTB2aN%P>%&GGAS9ojyKwX=um5qg|mVpO0{Ag-8DK+?dfEE`%1 zaD?ZqgC#S+8bIfU}6UM(BKtea^h}v?Hd4>HBa;QPMf*? zdo>LSbs@wx>Ix@5iE4VZgn^xWv@NmLz@nqoT45L2n*hOmUf^||lkfIFpbnmY#J^$` z5x*V%Hj>jZT(uy9U*1YR*ehi!s2iO*XT~Eo*A&uSaB2k3nB=q|e5VUo!V`*X6(55Y?!8bQ|Z zis_o00mME4y5389vojpLr@pse!Dn0T@aE!Q3Ka=F)4@`-&G~65I$wEh@;N?!qz{G* z@OIy`>L92a6MXmenHm?0ceZyJ8RzSm;G|j+I1y;_&=<6K|F>~|NG*B&3+ z3cCnlNti}!7+IzvLE9i>Gr4zT5al=uh55-Ng*}=Ikt}0aWfD_(^5Kd!V5Mw9N2cC8 zG}X~*$x*CO{j8L>?-_SYzVzK5f%H)8!zP`0n({5!%v-1Yso@F}mUk=+zPxjlu|itRRGL)yZr*_Gwur2*&Ei zZIhV>WNes%QK$>Q+A8rNKtjyQh}04EG95hGL~q5xL1mSe1dnNRrX@v?y4g{9GXnVg zY{3KT1~QEBiA2WGS{#4X?%|yXI9}%X8;#o_&!zpn+>G89jb+EyZ9$f!tANB1-#~WKin!I+- zvxB79-oHv4YyBp~k%bkCnMrKHqp|Vg_4QR{+cI|-ZIk=A`F>)xxbU8cEeASBMon}4 zY`zZ?YLVwPjY*8JvtEBff+`{u^MDl_fygtJ)oo?#zGUhG4 z^%=QH$DG)e{>qq${{XhcjUoQsFA401cefjF%&PwX;@WP1Le^A8I;PDNNLp>}$AE4w z14@^%GB-zCJ`u|+OD)0qEb%+A+ioNwApx&65dsl}SDNUpZ4l)679a0AQ?&B0tcOJ@ zBo2D$KQbzKi309PI=b@Neuq(}mV^j0(bOF_GJpJ>JuU?-&JpGvN z;%d(2SLFwPe`%NBPo)7IBLDcE?|%H)?RUk6Ur45>1<*q8@gvL=XoloC-w?P^LC9ZqLK`uV2_+sdFoS?Xp&33~gqj(5FBt zId}O!|8ErT@|xi+%uhfXfU`?5^PjMNQ+0N=45J04z1Y)l3nC&D`aFV^q{YKHYMZ&q zl)Nv{H|3yd-gG_SURB(rOuTkkRmMJgPo2tkf8e=1!mr@~KY?K@4UJ9n1ND1-nUT8! zZqZ43^OeSeBRnn1=mw9YLGN6?`sIe*c;B9tTaN~+-e5CJW1Ot?(bs?b#CNRA692wy z(rj_F5J6fS?_F>ByHO`QI*XnF4!-F2&G#C#r^UA#fWx&7kcHtNsa-Fwd%Vlt9&%--Gz$e9!LJ+XIxZ>#B-x# zwSz``hDR(W0yhFhWGYWqmQ>krcMWESl5T)AQx&@}Z*DvvnrYelM?zFmE}?&q4}g$? z^ah@ni6=a{H;147vPXYnd=9scPsMN-pErzsCnhrSiI{LPLS9wS01R&+dA@^ufpO7m zO`lwpUmMcpjn7Y@g;{B=EO@H9A0XJ}cY7lxU`|q8bsu`ReS5`X%ecD>jP~KYKB3Vj z9?DBvtBc3k$`=%q8~ho^JFb{e48MIz4&f4Qs|fo_H12eeiY36`)+V8J@kE&}u`Az% zSsK+w@5Fv&UO}#>(9!ACI8sjE=*)J0p!}QM!C(X;MVr?_)jMr5oDW$xQzeFiPh(=< zK^^k3s^*w^`=2!Kn%o?=7zEz#XglxOEFm9gH?Q1Y5fGlJpKS%z!4bqHikxP9YK=)c z4ejHnWJ2QapUKW1+tt2syH&Z$Nm-HX@fZbD&s*$d=$<&{uV+?)oSo@9H#a)qF?E5` ztiwS;{{H2{#COT$zKK%@>+$r~I1AU8W702yF}Kj<8kO55-5|p~=xri~q8t<^r$t%R z_KPiWMn^>n!&BeRZuIAvis|N_-s!dGZJAOyP{`d`RPA4Sq|R^8u)+glamy z@0>RFf#+dhffuypzkc`)dLh_6_>k zeayJmp|%%7$nIyX)YS10;RQ4ns1Xl_gLp4ua-lF)^r|`a<`KUcL^BRE1liskNB;Iq z>7emxR;46{tcN(_r{OFy9$-B5;6LO0;l^1aWrh^?7KaUtaP0;wRSs zFmrr-{;%B)jw}nCX*3GJ8@&_4Y zn=Yladd+vW$Gatt+!vNWbzbhX4+Q}hZvGuZ7C!{t0v2|2vap&_sG;FT=N||7`K*kv zi*_A#b%&Me!}vQmo*>|r@L_B}5?C3D2-i9}$<(BMxkIM=K?sX>-Z_9XjO}!zIIQSQS!t>38P(-|GEK5DYYWDv^F1-#s!&nt_8D$Vg*phm2k^rL z>^%%_L?>rS@MLF1`U%6Zy7a2|=G_KNSjBCGglbt73yvXeQnRsp@ub|O zZ>y{_SsWculzW*S$W2JBmge4Bf>FkEt=Kzl4s}Gubrn(&3MMq6FAWFnO+(5c#^cRs1Is zN~21tE0LhGGp(enVFikQ9-GtTOh=MLsm|4URw8}(bX!}#zN!Ei)SL>0!M(tzMEW{q z>PR0jZuWrDy@5W?8M<6zk8itbaLeL?vse9B;_0m3J1sEl4%Xp5Y{U-3see1WpHnp_qI0C(B(Od ziIBtYF$tvwU@{dyT<9OUwL4v`LH2uW_9p0IQZ8xzVT@Iy8-#-FW?g9Cgl?m~B#ngI zEjSQuKYnmwsQVPU(xR@lro#~d%ucY!$||+;z^zH<(DUi1;2#j3fLG)^aT4?p^Aizs z<&9?cxd)7wThW!C%zT1l?!7Ph!&KB#+F5WTQP`+xC5b&K_9->`DOhrCwouIz6Wrl!WY>Aoy}n)@Yl*YF5q}E8 z05&>*I^rI;;xsh^L}EwDY5Do^>)wa1n3Zpku8(FI&eKdnR5|s5yQtxuP)QI|Otc`WnhuYA1cNCc<-LvN z4`I{x&=A7fz^w0S!r!IPzj?53XcXB1v+Pl;2#r*qU)*aLvs1^>ttukK(&Ai{!Ne=* zI#n#zr9rdB!)|gUF4!WJE_1XlO|eszizKoJ7PYZ4G6)-J)WUW8P6Q*~?VAkvYhwwV zDDk&17OoUH?iW76^r#Oh>rZsr^_1@a*x$K}qRq=Jx_8m~?quF^QgbM%Ywn$2UedI$ zvP*%r69Zuobl^qE33h+~A=?7Y8kml8BVG+WRR2lYJgK8K|9$AXLwH2l=Nz`O)Av)~ z>K5((p0f4J_lgNF^Qe{8DMRM)Mph!kt=1K0c?0(x)Tp|so*4NJ-zUGv*}5En#mtmP zY+NgWcI(PVMz=e;H?ae8CaR-T5W3!c^_s{56Cg%Udpc%gv(RRZV~Q+STIvL1o%rx3 zNziL+riAq)QD6Ry{4b`q>2)3T%I5-TCc)*!{le z!+U=3IluFs_q^|i^E}W0|9>9tIMKOn0$VGv1od~2I7=@WFcG4FAZI#NhVF>FS2(u8 zsCXL!)j^90-sXx0h;jOStWv=U_*z3R+=3Q9ywv!S^U%W&mi@l}I4qI%=6JMU3O%@M z^3rX`@Ts)?!( ziuN7JMfHWBd%`fKezn#wRpX$ zJt#R88Sr)yvsSX1n|CJeP)X_Y_k0xP{Or;x1>foW02IVRU^kd2BO`yo$=>!-pR4;| zaX)>;ZH-aje|7R3p|Tg?XR^q;bomD%TwIWow;sMlZE~g2dePd&pXLK7wii z1<>}WPRLxFC*HJvJHX~lUcmdqm~I?C(XbfiJN-*{#SKof;7>Vy|7c91smwf0$+w1d z;T)C+xA>7)O^|eQalHs-b%wO3qfm?T_*P{DqBr*W^-4cjymLe;{Q9#zl;e(GP`C%E3;Jp|o~u}s8|kbfm@o0)^(9?@*gj(Tt+SfdD^rsrrUMR;VY1Ak9aJ~y_r<1On=ds+WA#m@F za>HV)h2~Bkn)i~lV0v1zg)S$$|AJ;*L8M|~$jFt}RKMxfWlS__N3i>EK6HD~ocg;* zpw^#UM#FlA!c(M~SQE{^t;fXz{|h+z2){gX`S=SVi-o*M#lriVj9)sn3@+3xj<-gS zH&%zxL2>X9q)%GR&Ic4{Hs&j1V=juqtm=x&YI+3D^|th#q8rfOB(jPEm>d z&8~`ShJ&4_j_(m%-$-lskS0_SwYUi(1j(alc5c)=lzF!a^0G=61ws@UGR5w_LWEeX z1!hHCyYx=@92qMzTTzc6DK%SoUTsw{%t^wLaG<~$VIc$&CUzCGnwmbFDl$-Q+faPx zX0XJuY(D4Q8#oC0Duxn*uC07X$Iav?YVhup*s$&3qz?#f^tXY=+GrrqHffGi^>aC{ z=#|zcH|8o+SQFVX^LiWfO+77QUDyNOD+|~oI(6!L^e=;t2R4&b~t#0_!2RcAC z*tVDPx3-$EbHc9s8&G_r^76L?cMI_wkD>YSYOmE7E($E-3d?1domrA@gm^ai~4wvg4BF^e6F4;3J zRxPo4KeP8mi=@&Fa|x1aG^&|lqpP9~DV#n?jM)J)yNj=Q{e zxcH*(D}LMH*68*{?yM_!mThkBc=bk;+;2-<=JpbCOOQVg-djx*^x5nip}Lvb;$)`N zodXvJ_-j>C+NlyIk&^|+{Mp=kZw-I1>?48g*ri&@+_KYusrsbvbPQ_HnU@apy&U{g zUX#FsP(Y&mYo$Q%(Xs(PkUv=|8uPW6etFTQj|5{SVCpg;1PX|)OH6K9@q8m4xG_j} zCTm}9q-CUhk}Y{}PmG`J?)8&W1bV+Q0* Date: Mon, 11 Mar 2024 17:15:40 +0100 Subject: [PATCH 090/164] Fix doxygen warnings --- .../core/include/visp3/core/vpStatisticalTestShewhart.h | 8 ++++---- tutorial/mean-drift/tutorial-meandrift.cpp | 5 ++++- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h index 584658b0ec..32c543086a 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h +++ b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h @@ -98,10 +98,10 @@ class VISP_EXPORT vpStatisticalTestShewhart : public vpStatisticalTestSigma alarm frequency is.*/ int m_idCurrentData; /*!< The index of the current data in m_signal.*/ vpWecoRulesAlarm m_alarm; /*!< The type of alarm raised due to WECO's rules.*/ - float m_oneSigmaNegLim; /*!< The \f$ \mu - \sigma \* threshold.*/ - float m_oneSigmaPosLim; /*!< The \f$ \mu + \sigma \* threshold.*/ - float m_twoSigmaNegLim; /*!< The \f$ \mu - 2 \sigma \* threshold.*/ - float m_twoSigmaPosLim; /*!< The \f$ \mu + 2 \sigma \* threshold.*/ + float m_oneSigmaNegLim; /*!< The \f$ \mu - \sigma \f$ threshold.*/ + float m_oneSigmaPosLim; /*!< The \f$ \mu + \sigma \f$ threshold.*/ + float m_twoSigmaNegLim; /*!< The \f$ \mu - 2 \sigma \f$ threshold.*/ + float m_twoSigmaPosLim; /*!< The \f$ \mu + 2 \sigma \f$ threshold.*/ /** * \brief Compute the upper and lower limits of the test signal. diff --git a/tutorial/mean-drift/tutorial-meandrift.cpp b/tutorial/mean-drift/tutorial-meandrift.cpp index 945f312678..9ba89e457c 100644 --- a/tutorial/mean-drift/tutorial-meandrift.cpp +++ b/tutorial/mean-drift/tutorial-meandrift.cpp @@ -66,7 +66,7 @@ typedef enum TypeTest /** * \brief Permit to cast a \b TypeTest object into a string, for display purpose. * - * \param[in] choice The \b TypeTest object we want to know the name. + * \param[in] type The \b TypeTest object we want to know the name. * \return std::string The corresponding name. */ std::string typeTestToString(const TypeTest &type) @@ -264,6 +264,9 @@ std::vector meanDriftArrayToVectorOfString(const bool array[vpStati * a single string listing all the alarms. * * \param[in] array The array of boolean indicating which alarm are set. + * \param[in] prefix The returned string prefix. + * \param[in] sep The returned string separator. + * \param[in] suffix The returned string suffix. * \return std::string The corresponding string listing the names of alarms. */ std::string meanDriftArrayToString(const bool array[vpStatisticalTestAbstract::MEAN_DRIFT_COUNT], From e0deb7f1b0866f61c6e61ffceaa389d18759257d Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Mon, 11 Mar 2024 17:19:42 +0100 Subject: [PATCH 091/164] Changes to be able to build/use Apriltag 3rdparty when std::threads are disabled setting USE_THREADS=OFF - Allow to use Apriltag on ubuntu 12.04 --- CMakeLists.txt | 13 +++++++------ cmake/AddExtraCompilationFlags.cmake | 3 ++- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 300a3b42de..69baf3046c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -694,13 +694,14 @@ if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_11) message(WARNING "std::thread was detected but needs at least c++11 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable std::thread usage turning USE_THREADS=OFF.") unset(USE_THREADS) set(USE_THREADS OFF CACHE BOOL "Include std::thread support" FORCE) - elseif(UNIX) - # Apriltag on unix needs pthread. On windows we are using pthread built-in - if(Threads_FOUND) - set(USE_PTHREAD ON) # for AprilTag only - endif() endif() endif() + +if(UNIX AND Threads_FOUND) + # Apriltag on unix needs native pthread. On windows we are using pthread built-in + set(USE_PTHREAD ON) # for AprilTag only +endif() + # ---------------------------------------------------------------------------- # Build-in 3rd parties. Should be after c++ standard potential modification # ---------------------------------------------------------------------------- @@ -1732,7 +1733,7 @@ status("") status(" Optimization: ") status(" Use OpenMP:" USE_OPENMP THEN "yes" ELSE "no") status(" Use std::thread:" USE_THREADS THEN "yes" ELSE "no") -status(" Use pthread:" USE_PHREADS THEN "yes" ELSE "no") +status(" Use pthread:" USE_PTHREAD THEN "yes" ELSE "no") status(" Use pthread (built-in):" WITH_PTHREAD THEN "yes (ver ${PTHREADS_VERSION})" ELSE "no") status(" Use simdlib (built-in):" WITH_SIMDLIB THEN "yes" ELSE "no") status("") diff --git a/cmake/AddExtraCompilationFlags.cmake b/cmake/AddExtraCompilationFlags.cmake index 0cec5eef4e..7adb63f986 100644 --- a/cmake/AddExtraCompilationFlags.cmake +++ b/cmake/AddExtraCompilationFlags.cmake @@ -117,7 +117,8 @@ if(USE_OPENMP) add_extra_compiler_option("${OpenMP_CXX_FLAGS}") endif() -if(USE_THREADS) +if(USE_THREADS OR USE_PTHREAD) + # Condider the case of Apriltags on Unix that needs pthread if(THREADS_HAVE_PTHREAD_ARG) add_extra_compiler_option("-pthread") endif() From df526022a88c9064ea7e43d9fea46f5907be8e69 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Mon, 11 Mar 2024 17:28:29 +0100 Subject: [PATCH 092/164] Update change log with last/coming changes --- ChangeLog.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ChangeLog.txt b/ChangeLog.txt index d8a85ed998..0962d7d15e 100644 --- a/ChangeLog.txt +++ b/ChangeLog.txt @@ -30,6 +30,8 @@ ViSP 3.x.x (Version in development) https://visp-doc.inria.fr/doxygen/visp-daily/tutorial-tracking-mb-generic-rgbd-Blender.html . New tutorial: Installation from prebuilt Conda packages for Linux / OSX / Windows https://visp-doc.inria.fr/doxygen/visp-daily/tutorial-install-conda-package.html + . New tutorial: Using Statistical Process Control to monitor your signal + https://visp-doc.inria.fr/doxygen/visp-daily/tutorial-spc.html - Bug fixed . [#1251] Bug in vpDisplay::displayFrame() . [#1270] Build issue around std::clamp and optional header which are not found with cxx17 @@ -40,6 +42,8 @@ ViSP 3.x.x (Version in development) . [#1279] Issue in vpPoseVector json serialization . [#1296] Unable to parse camera parameters with vpXmlParserCamera::parse() when camera name is empty . [#1307] Cannot set cxx standard when configuring for Visual Studio + . [#1320] Broken links in the documentation + . [#1341] SVD computation fails with Lapack when m < n ---------------------------------------------- ViSP 3.6.0 (released September 22, 2023) - Contributors: From 36ad312d6e0de72759ca4a91017452d1e82254e2 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Mon, 11 Mar 2024 18:00:11 +0100 Subject: [PATCH 093/164] Fix operators generation and logging, clean up lambda for ops --- modules/python/config/core.json | 51 +++++++++++++++++++ modules/python/config/core_image.json | 36 ++++++------- .../generator/visp_python_bindgen/header.py | 46 ++++++++--------- .../generator/visp_python_bindgen/methods.py | 30 +++++++++-- 4 files changed, 116 insertions(+), 47 deletions(-) diff --git a/modules/python/config/core.json b/modules/python/config/core.json index f27121c4c9..aa3e22243e 100644 --- a/modules/python/config/core.json +++ b/modules/python/config/core.json @@ -250,6 +250,17 @@ "use_default_param_policy": false, "param_is_input": [true, false], "param_is_output": [false, true] + }, + { + "static": true, + "signature": "void getMinMaxRoi(const std::vector&, int&, int&, int&, int&)", + "use_default_param_policy": false, + "param_is_input": [ + true, false, false, false, false + ], + "param_is_output": [ + false, true, true, true, true + ] } ] }, @@ -301,6 +312,31 @@ "static": true, "signature": "vpImagePoint computeCurvePoint(double, unsigned int, unsigned int, std::vector &, std::vector&)", "custom_name": "computeCurvePointFromSpline" + }, + { + "static": false, + "signature": "void get_crossingPoints(std::list&)", + "use_default_param_policy": false, + "param_is_input": [ + false + ], + "param_is_output": [ + true + ] + }, + { + "static": false, + "signature": "void get_knots(std::list&)", + "use_default_param_policy": false, + "param_is_input": [false], + "param_is_output": [true] + }, + { + "static": false, + "signature": "void get_controlPoints(std::list&)", + "use_default_param_policy": false, + "param_is_input": [false], + "param_is_output": [true] } ] }, @@ -773,6 +809,21 @@ true, false ] + }, + { + "static": true, + "signature": "bool getKeyboardEvent(const vpImage&, std::string&, bool)", + "use_default_param_policy": false, + "param_is_input": [ + true, + false, + true + ], + "param_is_output": [ + false, + true, + false + ] } ] }, diff --git a/modules/python/config/core_image.json b/modules/python/config/core_image.json index 89d85ee3b7..3fd597c991 100644 --- a/modules/python/config/core_image.json +++ b/modules/python/config/core_image.json @@ -68,24 +68,24 @@ "ignore": true } ] + }, + "vpRGBf": { + "methods": [ + { + "static": false, + "signature": "vpRGBf& operator=(const vpRGBf&&)", + "ignore": true + } + ] + }, + "vpRGBa": { + "methods": [ + { + "static": false, + "signature": "vpRGBa& operator=(const vpRGBa&&)", + "ignore": true + } + ] } - }, - "vpRGBf": { - "methods": [ - { - "static": false, - "signature": "vpRGBf& operator=(const vpRGBf&&)", - "ignore": true - } - ] - }, - "vpRGBa": { - "methods": [ - { - "static": false, - "signature": "vpRGBa& operator=(const vpRGBa&&)", - "ignore": true - } - ] } } diff --git a/modules/python/generator/visp_python_bindgen/header.py b/modules/python/generator/visp_python_bindgen/header.py index 159bce1b07..42b1e8d8fb 100644 --- a/modules/python/generator/visp_python_bindgen/header.py +++ b/modules/python/generator/visp_python_bindgen/header.py @@ -380,35 +380,29 @@ def add_method_doc_to_pyargs(method: types.Method, py_arg_strs: List[str]) -> Li elif len(params_strs) < 1: for cpp_op, python_op_name in unary_return_ops.items(): if method_name == f'operator{cpp_op}': - operator_str = f''' -{python_ident}.def("__{python_op_name}__", []({"const" if method_is_const else ""} {name_cpp}& self) -> {return_type_str} {{ - return {cpp_op}self; -}}, {", ".join(py_args)});''' + operator_str = lambda_const_return_unary_op(python_ident, python_op_name, cpp_op, + method_is_const, name_cpp, + return_type_str, py_args) add_to_method_dict(f'__{python_op_name}__', MethodBinding(operator_str, is_static=False, is_lambda=True, is_operator=True, is_constructor=False)) break - - logging.info(f'Found unary operator {name_cpp}::{method_name}, skipping') - continue - for cpp_op, python_op_name in binary_return_ops.items(): - if method_name == f'operator{cpp_op}': - operator_str = f''' -{python_ident}.def("__{python_op_name}__", []({"const" if method_is_const else ""} {name_cpp}& self, {params_strs[0]} o) -> {return_type_str} {{ - return (self {cpp_op} o); -}}, {", ".join(py_args)});''' - add_to_method_dict(f'__{python_op_name}__', MethodBinding(operator_str, is_static=False, is_lambda=True, - is_operator=True, is_constructor=False)) - break - for cpp_op, python_op_name in binary_in_place_ops.items(): - if method_name == f'operator{cpp_op}': - operator_str = f''' -{python_ident}.def("__{python_op_name}__", []({"const" if method_is_const else ""} {name_cpp}& self, {params_strs[0]} o) -> {return_type_str} {{ - self {cpp_op} o; - return self; -}}, {", ".join(py_args)});''' - add_to_method_dict(f'__{python_op_name}__', MethodBinding(operator_str, is_static=False, is_lambda=True, - is_operator=True, is_constructor=False)) - break + elif len(params_strs) == 1: # e.g., self + other + for cpp_op, python_op_name in binary_return_ops.items(): + if method_name == f'operator{cpp_op}': + operator_str = lambda_const_return_binary_op(python_ident, python_op_name, cpp_op, + method_is_const, name_cpp, params_strs[0], + return_type_str, py_args) + add_to_method_dict(f'__{python_op_name}__', MethodBinding(operator_str, is_static=False, is_lambda=True, + is_operator=True, is_constructor=False)) + break + for cpp_op, python_op_name in binary_in_place_ops.items(): + if method_name == f'operator{cpp_op}': + operator_str = lambda_in_place_binary_op(python_ident, python_op_name, cpp_op, + method_is_const, name_cpp, params_strs[0], + return_type_str, py_args) + add_to_method_dict(f'__{python_op_name}__', MethodBinding(operator_str, is_static=False, is_lambda=True, + is_operator=True, is_constructor=False)) + break # Define classical methods class_def_names = BoundObjectNames(python_ident, name_python, name_cpp_no_template, name_cpp) diff --git a/modules/python/generator/visp_python_bindgen/methods.py b/modules/python/generator/visp_python_bindgen/methods.py index 09ebaf0ef3..bd884dec53 100644 --- a/modules/python/generator/visp_python_bindgen/methods.py +++ b/modules/python/generator/visp_python_bindgen/methods.py @@ -93,6 +93,13 @@ def supported_const_return_binary_op_map(): '^': 'xor', } +def lambda_const_return_binary_op(python_ident: str, python_op_name: str, cpp_op: str, method_is_const: bool, + cpp_type: str, param_type: str, return_type: str, py_args: List[str]) -> str: + return f''' +{python_ident}.def("__{python_op_name}__", []({"const" if method_is_const else ""} {cpp_type}& self, {param_type} o) -> {return_type} {{ + return (self {cpp_op} o); +}}, {", ".join(py_args)});''' + def supported_in_place_binary_op_map(): return { '+=': 'iadd', @@ -101,11 +108,28 @@ def supported_in_place_binary_op_map(): '/=': 'itruediv', } +def lambda_in_place_binary_op(python_ident: str, python_op_name: str, cpp_op: str, method_is_const: bool, + cpp_type: str, param_type: str, return_type: str, py_args: List[str]) -> str: + return f''' +{python_ident}.def("__{python_op_name}__", []({"const" if method_is_const else ""} {cpp_type}& self, {param_type} o) -> {return_type} {{ + self {cpp_op} o; + return self; +}}, {", ".join(py_args)});''' + def supported_const_return_unary_op_map(): return { '-': 'neg', '~': 'invert', } + +def lambda_const_return_unary_op(python_ident: str, python_op_name: str, cpp_op: str, method_is_const: bool, + cpp_type: str, return_type: str, py_args: List[str]) -> str: + return f''' +{python_ident}.def("__{python_op_name}__", []({"const" if method_is_const else ""} {cpp_type}& self) -> {return_type} {{ + return {cpp_op}self; +}}, {", ".join(py_args)});''' + + def find_and_define_repr_str(cls: ClassScope, cls_name: str, python_ident: str) -> str: for friend in cls.friends: if friend.fn is not None: @@ -419,13 +443,13 @@ def get_bindable_methods_with_config(submodule: 'Submodule', methods: List[types (lambda m, _: not m.constructor and is_unsupported_return_type(m.return_type), NotGeneratedReason.ReturnType) ] for method in methods: - method_config = submodule.get_method_config(cls_name, method, specializations, mapping) + method_config = submodule.get_method_config(cls_name, method, {}, mapping) method_can_be_bound = True for predicate, motive in filtering_predicates_and_motives: if predicate(method, method_config): - return_str = '' if method.return_type is None else (get_type(method.return_type, specializations, mapping) or '') + return_str = '' if method.return_type is None else (get_type(method.return_type, {}, mapping) or '') method_name = '::'.join(seg.name for seg in method.name.segments) - param_strs = [get_type(param.type, specializations, mapping) or '' for param in method.parameters] + param_strs = [get_type(param.type, {}, mapping) or '' for param in method.parameters] rejected_methods.append(RejectedMethod(cls_name, method, method_config, get_method_signature(method_name, return_str, param_strs), motive)) method_can_be_bound = False break From 2c238c6bb32c4147ce8c24d1f99e5d4e6826e334 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Mon, 11 Mar 2024 19:44:41 +0100 Subject: [PATCH 094/164] Fix various warnings detected with msvc17 --- modules/core/include/visp3/core/vpArray2D.h | 31 ++++++++++++++----- modules/core/include/visp3/core/vpImage.h | 4 ++- .../core/include/visp3/core/vpImageFilter.h | 8 ++--- .../core/include/visp3/core/vpImageTools.h | 5 +-- modules/core/include/visp3/core/vpMunkres.h | 4 +-- modules/core/src/image/vpImageCircle.cpp | 18 +++++------ modules/core/src/image/vpImageFilter.cpp | 2 +- modules/imgproc/src/vpImgproc.cpp | 18 +++++------ .../imgproc/test/with-dataset/testImgproc.cpp | 4 +-- .../io/src/image/private/vpImageIoOpenCV.cpp | 4 +-- modules/io/src/image/private/vpImageIoStb.cpp | 4 +-- .../real-robot/pololu-maestro/vpPololu.cpp | 4 +-- modules/tracker/mbt/src/edge/vpMbtMeLine.cpp | 6 ++-- .../me/src/moving-edges/vpMeEllipse.cpp | 26 +++++++++++----- .../tracker/me/src/moving-edges/vpMeLine.cpp | 26 ++++++++++------ .../vpHomographyRansac.cpp | 2 +- 16 files changed, 102 insertions(+), 64 deletions(-) diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index 5847aca8db..8372741f6a 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -320,7 +320,12 @@ template class vpArray2D // Reallocation of this->data array this->dsize = nrows * ncols; - this->data = (Type *)realloc(this->data, this->dsize * sizeof(Type)); + if (this->data) { + Type *tmp = (Type*)realloc(this->data, this->dsize * sizeof(Type)); + if (tmp) { + this->data = tmp; + } + } if ((nullptr == this->data) && (0 != this->dsize)) { if (copyTmp != nullptr) { delete[] copyTmp; @@ -328,7 +333,12 @@ template class vpArray2D throw(vpException(vpException::memoryAllocationError, "Memory allocation error when allocating 2D array data")); } - this->rowPtrs = (Type **)realloc(this->rowPtrs, nrows * sizeof(Type *)); + if (this->rowPtrs) { + Type **tmp = (Type**)realloc(this->rowPtrs, nrows * sizeof(Type*)); + if (tmp) { + this->rowPtrs = tmp; + } + } if ((nullptr == this->rowPtrs) && (0 != this->dsize)) { if (copyTmp != nullptr) { delete[] copyTmp; @@ -389,11 +399,18 @@ template class vpArray2D rowNum = nrows; colNum = ncols; - rowPtrs = reinterpret_cast(realloc(rowPtrs, nrows * sizeof(Type *))); - // Update rowPtrs - Type **t_ = rowPtrs; - for (unsigned int i = 0; i < dsize; i += ncols) { - *t_++ = data + i; + if (rowPtrs) { + Type **tmp = reinterpret_cast(realloc(rowPtrs, nrows * sizeof(Type*))); + if (tmp) { + this->rowPtrs = tmp; + } + } + if (rowPtrs) { + // Update rowPtrs + Type** t_ = rowPtrs; + for (unsigned int i = 0; i < dsize; i += ncols) { + *t_++ = data + i; + } } } diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index b3f82d0794..3687de81e9 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -844,7 +844,9 @@ vpImage::vpImage(const vpImage &I) : bitmap(nullptr), display(nullptr), npixels(0), width(0), height(0), row(nullptr), hasOwnership(true) { resize(I.getHeight(), I.getWidth()); - memcpy(static_cast(bitmap), static_cast(I.bitmap), I.npixels * sizeof(Type)); + if (bitmap) { + memcpy(static_cast(bitmap), static_cast(I.bitmap), I.npixels * sizeof(Type)); + } } #if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher diff --git a/modules/core/include/visp3/core/vpImageFilter.h b/modules/core/include/visp3/core/vpImageFilter.h index ee989955fa..ca778c813f 100644 --- a/modules/core/include/visp3/core/vpImageFilter.h +++ b/modules/core/include/visp3/core/vpImageFilter.h @@ -88,7 +88,7 @@ class VISP_EXPORT vpImageFilter } else { // Need to reset the image because some points will not be computed - I.resize(height, width, static_cast(0.)); + I.resize(height, width, static_cast(0)); } } @@ -227,7 +227,7 @@ class VISP_EXPORT vpImageFilter cv::Mat cv_I, cv_dIx, cv_dIy; vpImageConvert::convert(I, cv_I); computePartialDerivatives(cv_I, cv_dIx, cv_dIy, computeDx, computeDy, normalize, gaussianKernelSize, - gaussianStdev, apertureGradient, filteringType); + static_cast(gaussianStdev), apertureGradient, filteringType); if (computeDx) { vpImageConvert::convert(cv_dIx, dIx); } @@ -796,9 +796,9 @@ class VISP_EXPORT vpImageFilter FilterType result = static_cast(0.); for (unsigned int i = 1; i <= stop; ++i) { - result += filter[i] * static_cast(I[r][c + i] + I[r][c - i]); + result += filter[i] * static_cast(I[r][c + i] + I[r][c - i]); } - return result + filter[0] * static_cast(I[r][c]); + return result + filter[0] * static_cast(I[r][c]); } #ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/modules/core/include/visp3/core/vpImageTools.h b/modules/core/include/visp3/core/vpImageTools.h index 6c8fa38269..58a910d885 100644 --- a/modules/core/include/visp3/core/vpImageTools.h +++ b/modules/core/include/visp3/core/vpImageTools.h @@ -57,6 +57,7 @@ #include #include #include +#include #if defined(_OPENMP) #include @@ -1113,12 +1114,12 @@ void vpImageTools::resize(const vpImage &I, vpImage &Ires, const vpI #endif for (int i = 0; i < static_cast(Ires.getHeight()); i++) { const float v = (i + half) * scaleY - half; - const int v0 = static_cast(v); + const float v0 = std::floor(v); const float yFrac = v - v0; for (unsigned int j = 0; j < Ires.getWidth(); j++) { const float u = (j + half) * scaleX - half; - const int u0 = static_cast(u); + const float u0 = std::floor(u); const float xFrac = u - u0; if (method == INTERPOLATION_NEAREST) { diff --git a/modules/core/include/visp3/core/vpMunkres.h b/modules/core/include/visp3/core/vpMunkres.h index 802994da05..6d27fd48d2 100644 --- a/modules/core/include/visp3/core/vpMunkres.h +++ b/modules/core/include/visp3/core/vpMunkres.h @@ -314,8 +314,8 @@ inline vpMunkres::STEP_T vpMunkres::stepSix(std::vector > &cos template inline std::vector > vpMunkres::run(std::vector > costs) { - const auto original_row_size = costs.size(); - const auto original_col_size = costs.front().size(); + const auto original_row_size = static_cast(costs.size()); + const auto original_col_size = static_cast(costs.front().size()); const auto sq_size = std::max(original_row_size, original_col_size); auto mask = std::vector >( diff --git a/modules/core/src/image/vpImageCircle.cpp b/modules/core/src/image/vpImageCircle.cpp index 2bf69365e5..ffeb35c263 100644 --- a/modules/core/src/image/vpImageCircle.cpp +++ b/modules/core/src/image/vpImageCircle.cpp @@ -1043,7 +1043,7 @@ void incrementIfIsInMask(const vpImage &mask, const int &width, const int unsigned int vpImageCircle::computePixelsInMask(const vpImage &mask) const { - const int xm = m_center.get_u(), ym = m_center.get_v(); + const float xm = static_cast(m_center.get_u()), ym = static_cast(m_center.get_v()); const float r_float = static_cast(m_radius); const int width = mask.getWidth(); const int height = mask.getHeight(); @@ -1073,14 +1073,14 @@ unsigned int vpImageCircle::computePixelsInMask(const vpImage &mask) const float sin_theta = std::sin(theta); float rcos_pos = r_float * cos_theta; float rsin_pos = r_float * sin_theta; - x1 = xm + rcos_pos; // theta - y1 = ym + rsin_pos; // theta - x2 = xm - rsin_pos; // theta + pi - y2 = ym + rcos_pos; // theta + pi - x3 = xm - rcos_pos; // theta + pi/2 - y3 = ym - rsin_pos; // theta + pi/2 - x4 = xm + rsin_pos; // theta + pi - y4 = ym - rcos_pos; // theta + pi + x1 = static_cast(xm + rcos_pos); // theta + y1 = static_cast(ym + rsin_pos); // theta + x2 = static_cast(xm - rsin_pos); // theta + pi + y2 = static_cast(ym + rcos_pos); // theta + pi + x3 = static_cast(xm - rcos_pos); // theta + pi/2 + y3 = static_cast(ym - rsin_pos); // theta + pi/2 + x4 = static_cast(xm + rsin_pos); // theta + pi + y4 = static_cast(ym - rcos_pos); // theta + pi incrementIfIsInMask(mask, width, height, x1, y1, count); incrementIfIsInMask(mask, width, height, x2, y2, count); incrementIfIsInMask(mask, width, height, x3, y3, count); diff --git a/modules/core/src/image/vpImageFilter.cpp b/modules/core/src/image/vpImageFilter.cpp index fffa9016d0..a19508fa56 100644 --- a/modules/core/src/image/vpImageFilter.cpp +++ b/modules/core/src/image/vpImageFilter.cpp @@ -1119,7 +1119,7 @@ void vpImageFilter::canny(const vpImage &Isrc, vpImage &I, const vpImage *p_ I.getMinMaxValue(inputMin, inputMax); unsigned char inputRange = inputMax - inputMin; - float gamma_computed = (std::log(128.f) - std::log(256.f)) / (std::log(mean) - std::log(inputRange)); + float gamma_computed = static_cast((std::log(128.f) - std::log(256.f)) / (std::log(mean) - std::log(inputRange))); float inverse_gamma = 1.f / gamma_computed; // Construct the look-up table @@ -397,19 +397,19 @@ void gammaCorrectionClassificationBasedMethod(vpImage &I, const v float gamma = 0.f; if (isAlreadyHighContrast) { // Case medium to high contrast image - gamma = std::exp((1.f - (meanNormalized + stdevNormalized))/2.f); + gamma = static_cast(std::exp((1.f - (meanNormalized + stdevNormalized))/2.f)); } else { // Case low contrast image #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - gamma = -std::log2(stdevNormalized); + gamma = -static_cast(std::log2(stdevNormalized)); #else - gamma = -std::log(stdevNormalized) / std::log(2); + gamma = -static_cast(std::log(stdevNormalized) / std::log(2)); #endif } if (meanNormalized < 0.5) { // Case dark image - float meanPowerGamma = std::pow(meanNormalized, gamma); + float meanPowerGamma = static_cast(std::pow(meanNormalized, gamma)); for (unsigned int i = 0; i <= 255; i++) { float iNormalized = static_cast(i)/255.f; float iPowerGamma = std::pow(iNormalized, gamma); @@ -500,7 +500,7 @@ void gammaCorrectionSpatialBased(vpImage &I, const vpImage vpImageTools::resize(I_8_blur, L_8, width, height, vpImageTools::INTERPOLATION_CUBIC); const float alpha = 0.5f; unsigned int size = height * width; - float stdev = I.getStdev(p_mask); + float stdev = static_cast(I.getStdev(p_mask)); float p; if (stdev <= 40) { p = 2.f; @@ -546,7 +546,7 @@ void gammaCorrectionSpatialBased(vpImage &I, const vpImage *p_mask vpImage I_gray(height, width); for (unsigned int i = 0; i < size; ++i) { vpRGBa rgb = I.bitmap[i]; - I_gray.bitmap[i] = 0.299 * rgb.R + 0.587 * rgb.G + 0.114 *rgb.B; + I_gray.bitmap[i] = static_cast(0.299 * rgb.R + 0.587 * rgb.G + 0.114 * rgb.B); } vpImage I_2, I_4, I_8; I_gray.subsample(2, 2, I_2); @@ -565,7 +565,7 @@ void gammaCorrectionSpatialBased(vpImage &I, const vpImage *p_mask vpImageTools::resize(I_8_blur, L_8, width, height, vpImageTools::INTERPOLATION_CUBIC); const float alpha = 0.5f; - float stdev = I.getStdev(p_mask); + float stdev = static_cast(I.getStdev(p_mask)); float p; if (stdev <= 40) { p = 2.f; @@ -601,7 +601,7 @@ void gammaCorrection(vpImage &I, const float &gamma, const vpGamm { float inverse_gamma = 1.0; if ((gamma > 0) && (method == GAMMA_MANUAL)) { - inverse_gamma = 1.0 / gamma; + inverse_gamma = 1.0f / gamma; // Construct the look-up table unsigned char lut[256]; for (unsigned int i = 0; i < 256; i++) { diff --git a/modules/imgproc/test/with-dataset/testImgproc.cpp b/modules/imgproc/test/with-dataset/testImgproc.cpp index ba009c23fe..3f2fb03636 100644 --- a/modules/imgproc/test/with-dataset/testImgproc.cpp +++ b/modules/imgproc/test/with-dataset/testImgproc.cpp @@ -273,7 +273,7 @@ int main(int argc, const char **argv) // Gamma correction vpImage I_color_gamma_correction; - double gamma = 2.2; + float gamma = 2.2f; t = vpTime::measureTimeMs(); vp::gammaCorrection(I_color, I_color_gamma_correction, gamma); t = vpTime::measureTimeMs() - t; @@ -376,7 +376,7 @@ int main(int argc, const char **argv) // Gamma correction vpImage I_gamma_correction; - gamma = 1.8; + gamma = 1.8f; t = vpTime::measureTimeMs(); vp::gammaCorrection(I, I_gamma_correction, gamma); t = vpTime::measureTimeMs() - t; diff --git a/modules/io/src/image/private/vpImageIoOpenCV.cpp b/modules/io/src/image/private/vpImageIoOpenCV.cpp index 80a5466150..dceed26214 100644 --- a/modules/io/src/image/private/vpImageIoOpenCV.cpp +++ b/modules/io/src/image/private/vpImageIoOpenCV.cpp @@ -175,7 +175,7 @@ void readOpenCV(vpImage &I, const std::string &filename) */ void readPNGfromMemOpenCV(const std::vector &buffer, vpImage &I) { - cv::Mat1b buf(buffer.size(), 1, const_cast(buffer.data())); + cv::Mat1b buf(static_cast(buffer.size()), 1, const_cast(buffer.data())); cv::Mat1b img = cv::imdecode(buf, cv::IMREAD_GRAYSCALE); I.resize(img.rows, img.cols); std::copy(img.begin(), img.end(), I.bitmap); @@ -189,7 +189,7 @@ void readPNGfromMemOpenCV(const std::vector &buffer, vpImage &buffer, vpImage &I_color) { - cv::Mat1b buf(buffer.size(), 1, const_cast(buffer.data())); + cv::Mat1b buf(static_cast(buffer.size()), 1, const_cast(buffer.data())); cv::Mat3b img = cv::imdecode(buf, cv::IMREAD_COLOR); vpImageConvert::convert(img, I_color); } diff --git a/modules/io/src/image/private/vpImageIoStb.cpp b/modules/io/src/image/private/vpImageIoStb.cpp index 33dc4afa26..55c6699977 100644 --- a/modules/io/src/image/private/vpImageIoStb.cpp +++ b/modules/io/src/image/private/vpImageIoStb.cpp @@ -149,7 +149,7 @@ void readPNGfromMemStb(const std::vector &buffer, vpImage(buffer.size()), &x, &y, &comp, req_channels); assert(comp == req_channels); I.init(buffer_read, y, x, true); @@ -165,7 +165,7 @@ void readPNGfromMemStb(const std::vector &buffer, vpImage &buffer, vpImage &I_color) { int x = 0, y = 0, comp = 0; - unsigned char *buffer_read = stbi_load_from_memory(buffer.data(), buffer.size(), &x, &y, &comp, 0); + unsigned char *buffer_read = stbi_load_from_memory(buffer.data(), static_cast(buffer.size()), &x, &y, &comp, 0); if (comp == 4) { const bool copyData = true; diff --git a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp index 43cc96719d..3f631be8fe 100644 --- a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp +++ b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp @@ -122,7 +122,7 @@ unsigned short vpPololu::radToPwm(float angle) const float a = m_range_pwm / m_range_angle; float b = m_min_pwm - m_min_angle * a; - return (a * angle + b); + return static_cast(a * angle + b); } bool vpPololu::connected() const @@ -194,7 +194,7 @@ void vpPololu::setAngularPosition(float pos_rad, float vel_rad_s) { if ((m_min_angle <= pos_rad) && (pos_rad <= m_max_angle)) { unsigned short pos_pwm = radToPwm(pos_rad); - unsigned short pos_speed = std::fabs(radSToSpeed(vel_rad_s)); + unsigned short pos_speed = static_cast(std::fabs(radSToSpeed(vel_rad_s))); // Handle the case where pos_speed = 0 which corresponds to the pwm max speed if (pos_speed == 0) { pos_speed = 1; diff --git a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp index 03cc98fa22..cada111ec9 100644 --- a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp @@ -173,9 +173,11 @@ void vpMbtMeLine::sample(const vpImage &I, bool doNoTrack) vpImagePoint iP; iP.set_i(is); iP.set_j(js); + unsigned int is_uint = static_cast(is); + unsigned int js_uint = static_cast(js); // If point is in the image, add to the sample list - if ((!outOfImage(iP, (int)(m_me->getRange() + m_me->getMaskSize() + 1), nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + if ((!outOfImage(iP, (int)(m_me->getRange() + m_me->getMaskSize() + 1), nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), m_delta, 0, m_sign); pix.setDisplay(m_selectDisplay); diff --git a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp index 664f440e9a..8f400cc72d 100644 --- a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp @@ -65,7 +65,7 @@ vpMeEllipse::vpMeEllipse(const vpMeEllipse &me_ellipse) m_alphamin(me_ellipse.m_alphamin), m_alphamax(me_ellipse.m_alphamax), m_uc(me_ellipse.m_uc), m_vc(me_ellipse.m_vc), m_n20(me_ellipse.m_n20), m_n11(me_ellipse.m_n11), m_n02(me_ellipse.m_n02), m_expectedDensity(me_ellipse.m_expectedDensity), m_numberOfGoodPoints(me_ellipse.m_numberOfGoodPoints), - m_trackCircle(me_ellipse.m_trackCircle), m_trackArc(me_ellipse.m_trackArc) + m_trackCircle(me_ellipse.m_trackCircle), m_trackArc(me_ellipse.m_trackArc), m_arcEpsilon(me_ellipse.m_arcEpsilon) { } vpMeEllipse::~vpMeEllipse() @@ -300,8 +300,10 @@ void vpMeEllipse::sample(const vpImage &I, bool doNotTrack) computePointOnEllipse(ang, iP); // If point is in the image, add to the sample list // Check done in (i,j) frame) - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { const unsigned int crossSize = 5; vpDisplay::displayCross(I, iP, crossSize, vpColor::red); @@ -361,7 +363,9 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) while (ang < (nextang - incr)) { vpImagePoint iP; computePointOnEllipse(ang, iP); - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint)) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); @@ -420,7 +424,9 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) ang = (nextang + ang) / 2.0; // point added at mid angle vpImagePoint iP; computePointOnEllipse(ang, iP); - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint)) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); @@ -479,7 +485,9 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) for (unsigned int i = 0; i < nbpts; ++i) { vpImagePoint iP; computePointOnEllipse(ang, iP); - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint)) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); @@ -529,7 +537,9 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) for (unsigned int i = 0; i < nbpts; ++i) { vpImagePoint iP; computePointOnEllipse(ang, iP); - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint)) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); @@ -1241,7 +1251,7 @@ void vpMeEllipse::initTracking(const vpImage &I, const vpColVecto computeAbeFromNij(); computeKiFromNij(); - if (m_trackArc) { + if (m_trackArc && pt1 && pt2) { m_alpha1 = computeAngleOnEllipse(*pt1); m_alpha2 = computeAngleOnEllipse(*pt2); if ((m_alpha2 <= m_alpha1) || (std::fabs(m_alpha2 - m_alpha1) < m_arcEpsilon)) { diff --git a/modules/tracker/me/src/moving-edges/vpMeLine.cpp b/modules/tracker/me/src/moving-edges/vpMeLine.cpp index 41501bd559..39e01e785f 100644 --- a/modules/tracker/me/src/moving-edges/vpMeLine.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeLine.cpp @@ -161,9 +161,11 @@ void vpMeLine::sample(const vpImage &I, bool doNotTrack) vpImagePoint iP; iP.set_i(is); iP.set_j(js); + unsigned int is_uint = static_cast(is); + unsigned int js_uint = static_cast(js); // If point is in the image, add to the sample list - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), m_delta, 0, m_sign); pix.setDisplay(m_selectDisplay); @@ -523,16 +525,18 @@ void vpMeLine::seekExtremities(const vpImage &I) for (int i = 0; i < 3; i++) { P.m_ifloat = P.m_ifloat + di * sample_step; - P.m_i = (int)P.m_ifloat; + P.m_i = static_cast(P.m_ifloat); P.m_jfloat = P.m_jfloat + dj * sample_step; - P.m_j = (int)P.m_jfloat; + P.m_j = static_cast(P.m_jfloat); vpImagePoint iP; iP.set_i(P.m_ifloat); iP.set_j(P.m_jfloat); - if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(P.m_ifloat); + unsigned int js_uint = static_cast(P.m_jfloat); + if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { @@ -553,16 +557,18 @@ void vpMeLine::seekExtremities(const vpImage &I) P.setDisplay(m_selectDisplay); for (int i = 0; i < 3; i++) { P.m_ifloat = P.m_ifloat - di * sample_step; - P.m_i = (int)P.m_ifloat; + P.m_i = static_cast(P.m_ifloat); P.m_jfloat = P.m_jfloat - dj * sample_step; - P.m_j = (int)P.m_jfloat; + P.m_j = static_cast(P.m_jfloat); vpImagePoint iP; iP.set_i(P.m_ifloat); iP.set_j(P.m_jfloat); - if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(P.m_ifloat); + unsigned int js_uint = static_cast(P.m_jfloat); + if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { diff --git a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp index 80db43742d..816b71785d 100644 --- a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp @@ -432,7 +432,7 @@ bool vpHomography::ransac(const std::vector &xb, const std::vector= nbInliersConsensus) { - const unsigned int nbConsensus = best_consensus.size(); + const unsigned int nbConsensus = static_cast(best_consensus.size()); std::vector xa_best(nbConsensus); std::vector ya_best(nbConsensus); std::vector xb_best(nbConsensus); From 6234563a5804d1c362239c3f512b5b988dcc7480 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Tue, 12 Mar 2024 08:16:17 +0100 Subject: [PATCH 095/164] Fix previous changes introduced around realloc memory allocation --- modules/core/include/visp3/core/vpArray2D.h | 21 +++++++++------------ 1 file changed, 9 insertions(+), 12 deletions(-) diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index 8372741f6a..36b655d299 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -320,12 +320,11 @@ template class vpArray2D // Reallocation of this->data array this->dsize = nrows * ncols; - if (this->data) { - Type *tmp = (Type*)realloc(this->data, this->dsize * sizeof(Type)); - if (tmp) { - this->data = tmp; - } + Type *tmp_data = (Type *)realloc(this->data, this->dsize * sizeof(Type)); + if (tmp_data) { + this->data = tmp_data; } + if ((nullptr == this->data) && (0 != this->dsize)) { if (copyTmp != nullptr) { delete[] copyTmp; @@ -333,11 +332,9 @@ template class vpArray2D throw(vpException(vpException::memoryAllocationError, "Memory allocation error when allocating 2D array data")); } - if (this->rowPtrs) { - Type **tmp = (Type**)realloc(this->rowPtrs, nrows * sizeof(Type*)); - if (tmp) { - this->rowPtrs = tmp; - } + Type **tmp_rowPtrs = (Type **)realloc(this->rowPtrs, nrows * sizeof(Type *)); + if (tmp_rowPtrs) { + this->rowPtrs = tmp_rowPtrs; } if ((nullptr == this->rowPtrs) && (0 != this->dsize)) { if (copyTmp != nullptr) { @@ -400,14 +397,14 @@ template class vpArray2D rowNum = nrows; colNum = ncols; if (rowPtrs) { - Type **tmp = reinterpret_cast(realloc(rowPtrs, nrows * sizeof(Type*))); + Type **tmp = reinterpret_cast(realloc(rowPtrs, nrows * sizeof(Type *))); if (tmp) { this->rowPtrs = tmp; } } if (rowPtrs) { // Update rowPtrs - Type** t_ = rowPtrs; + Type **t_ = rowPtrs; for (unsigned int i = 0; i < dsize; i += ncols) { *t_++ = data + i; } From 83fba5e81b49e51aa9f759cc5621fca4360463a5 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Tue, 12 Mar 2024 10:26:27 +0100 Subject: [PATCH 096/164] Remove remaining debug printings --- modules/core/src/tools/file/vpIoTools.cpp | 41 ++++++++++------------- 1 file changed, 18 insertions(+), 23 deletions(-) diff --git a/modules/core/src/tools/file/vpIoTools.cpp b/modules/core/src/tools/file/vpIoTools.cpp index f02b4279b5..f4b25f22af 100644 --- a/modules/core/src/tools/file/vpIoTools.cpp +++ b/modules/core/src/tools/file/vpIoTools.cpp @@ -832,20 +832,15 @@ bool vpIoTools::checkDirectory(const std::string &dirname) std::string _dirname = path(dirname); if (VP_STAT(_dirname.c_str(), &stbuf) != 0) { - std::cout << "DEBUG 1 _dirname: " << _dirname << " is not a dir" << std::endl; // Test adding the separator if not already present if (_dirname.at(_dirname.size() - 1) != separator) { - std::cout << "DEBUG 2 test if _dirname + separator: " << _dirname + separator << " is a dir ?" << std::endl; if (VP_STAT((_dirname + separator).c_str(), &stbuf) != 0) { - std::cout << "DEBUG 2 _dirname + separator: " << _dirname + separator << " is not a dir" << std::endl; return false; } } // Test removing the separator if already present if (_dirname.at(_dirname.size() - 1) == separator) { - std::cout << "DEBUG 2 test if _dirname - separator: " << _dirname.substr(0, _dirname.size() - 1) << " is a dir ?" << std::endl; if (VP_STAT((_dirname.substr(0, _dirname.size() - 1)).c_str(), &stbuf) != 0) { - std::cout << "DEBUG 3 _dirname - separator: " << _dirname.substr(0, _dirname.size() - 1) << " is not a dir" << std::endl; return false; } } @@ -2071,16 +2066,16 @@ std::string vpIoTools::toLowerCase(const std::string &input) out += std::tolower(*it); } return out; -} + } -/** - * @brief Return a upper-case version of the string \b input . - * Numbers and special characters stay the same - * - * @param input The input string for which we want to ensure that all the characters are in upper case. - * @return std::string A upper-case version of the string \b input, where - * numbers and special characters stay the same - */ + /** + * @brief Return a upper-case version of the string \b input . + * Numbers and special characters stay the same + * + * @param input The input string for which we want to ensure that all the characters are in upper case. + * @return std::string A upper-case version of the string \b input, where + * numbers and special characters stay the same + */ std::string vpIoTools::toUpperCase(const std::string &input) { std::string out; @@ -2092,16 +2087,16 @@ std::string vpIoTools::toUpperCase(const std::string &input) out += std::toupper(*it); } return out; -} + } -/*! - Returns the absolute path using realpath() on Unix systems or - GetFullPathName() on Windows systems. \return According to realpath() - manual, returns an absolute pathname that names the same file, whose - resolution does not involve '.', '..', or symbolic links for Unix systems. - According to GetFullPathName() documentation, retrieves the full path of the - specified file for Windows systems. - */ + /*! + Returns the absolute path using realpath() on Unix systems or + GetFullPathName() on Windows systems. \return According to realpath() + manual, returns an absolute pathname that names the same file, whose + resolution does not involve '.', '..', or symbolic links for Unix systems. + According to GetFullPathName() documentation, retrieves the full path of the + specified file for Windows systems. + */ std::string vpIoTools::getAbsolutePathname(const std::string &pathname) { From ed0c3ce7780bffc6f6c8cf89f71671f8c6623e9c Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Tue, 12 Mar 2024 10:37:57 +0100 Subject: [PATCH 097/164] Add debug info --- example/math/quadprog.cpp | 10 +++++++++- example/math/quadprog_eq.cpp | 14 ++++++++++++++ 2 files changed, 23 insertions(+), 1 deletion(-) diff --git a/example/math/quadprog.cpp b/example/math/quadprog.cpp index 58c96eb47b..cb6af9ef59 100644 --- a/example/math/quadprog.cpp +++ b/example/math/quadprog.cpp @@ -105,8 +105,10 @@ int main(int argc, char **argv) r = randV(o) * 5; C = randM(p, n) * 5; - // make sure Cx <= d has a solution within Ax = b + std::cout << "DEBUG 1 before solveBySVD()" << std::endl; + // make sure Cx <= d has a solution within Ax = b vpColVector x = A.solveBySVD(b); + std::cout << "DEBUG 2 after solveBySVD()" << std::endl; d = C * x; for (int i = 0; i < p; ++i) d[i] += (5. * rand()) / RAND_MAX; @@ -114,6 +116,8 @@ int main(int argc, char **argv) // solver with warm start vpQuadProg qp_WS; + std::cout << "DEBUG 3 after vpQuadProg()" << std::endl; + // timing int total = 100; double t_WS(0), t_noWS(0); @@ -142,7 +146,9 @@ int main(int argc, char **argv) vpQuadProg qp; x = 0; double t = vpTime::measureTimeMs(); + std::cout << "DEBUG 4 before solveQP()" << std::endl; qp.solveQP(Q, r, A, b, C, d, x); + std::cout << "DEBUG 4 after solveQP()" << std::endl; t_noWS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY @@ -153,7 +159,9 @@ int main(int argc, char **argv) // with warm start x = 0; t = vpTime::measureTimeMs(); + std::cout << "DEBUG 5 before solveQP()" << std::endl; qp_WS.solveQP(Q, r, A, b, C, d, x); + std::cout << "DEBUG 5 after solveQP()" << std::endl; t_WS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY diff --git a/example/math/quadprog_eq.cpp b/example/math/quadprog_eq.cpp index 0605f4e7c6..7c90d93579 100644 --- a/example/math/quadprog_eq.cpp +++ b/example/math/quadprog_eq.cpp @@ -105,17 +105,23 @@ int main(int argc, char **argv) C = randM(p, n) * 5; // make sure Cx <= d has a solution within Ax = b + + std::cout << "DEBUG 1 before solveBySVD()" << std::endl; vpColVector x = A.solveBySVD(b); + std::cout << "DEBUG 1 after solveBySVD()" << std::endl; d = C * x; for (int i = 0; i < p; ++i) d[i] += (5. * rand()) / RAND_MAX; // solver with stored equality and warm start vpQuadProg qp_WS; + std::cout << "DEBUG 2 before setEqualityConstraint()" << std::endl; qp_WS.setEqualityConstraint(A, b); + std::cout << "DEBUG 2 after setEqualityConstraint()" << std::endl; vpQuadProg qp_ineq_WS; qp_ineq_WS.setEqualityConstraint(A, b); + std::cout << "DEBUG 3 after setEqualityConstraint()" << std::endl; // timing int total = 100; @@ -140,7 +146,9 @@ int main(int argc, char **argv) // without warm start x = 0; double t = vpTime::measureTimeMs(); + std::cout << "DEBUG 4 before solveQPe()" << std::endl; vpQuadProg::solveQPe(Q, r, A, b, x); + std::cout << "DEBUG 4 after solveQPe()" << std::endl; t_noWS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY @@ -151,7 +159,9 @@ int main(int argc, char **argv) // with pre-solved Ax = b x = 0; t = vpTime::measureTimeMs(); + std::cout << "DEBUG 5 before solveQPe()" << std::endl; qp_WS.solveQPe(Q, r, x); + std::cout << "DEBUG 5 after solveQPe()" << std::endl; t_WS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY @@ -164,7 +174,9 @@ int main(int argc, char **argv) x = 0; vpQuadProg qp; t = vpTime::measureTimeMs(); + std::cout << "DEBUG 6 before solveQP()" << std::endl; qp.solveQP(Q, r, A, b, C, d, x); + std::cout << "DEBUG 6 after solveQP()" << std::endl; t_ineq_noWS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY @@ -175,7 +187,9 @@ int main(int argc, char **argv) // with warm start + pre-solving x = 0; t = vpTime::measureTimeMs(); + std::cout << "DEBUG 7 before solveQPi()" << std::endl; qp_ineq_WS.solveQPi(Q, r, C, d, x, true); + std::cout << "DEBUG 7 after solveQPi()" << std::endl; t_ineq_WS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY From 22f679c6ea8c097e595d90d7a18948a8004b0b89 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Tue, 12 Mar 2024 13:55:57 +0100 Subject: [PATCH 098/164] Add verbose option to ctest --- .github/workflows/ubuntu-sanitizers.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ubuntu-sanitizers.yml b/.github/workflows/ubuntu-sanitizers.yml index 9894441bac..e215a425c0 100644 --- a/.github/workflows/ubuntu-sanitizers.yml +++ b/.github/workflows/ubuntu-sanitizers.yml @@ -82,4 +82,4 @@ jobs: # SUMMARY: AddressSanitizer: odr-violation: global 'ALIGNMENT' at /home/runner/work/visp/visp/3rdparty/simdlib/Simd/SimdLib.cpp:82:18 ASAN_OPTIONS: detect_odr_violation=0 working-directory: build - run: ctest -j$(nproc) --output-on-failure + run: ctest -j$(nproc) --output-on-failure -V From e73843c98594bc1009bd7e7663c4f97eeebff596 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 12 Mar 2024 14:02:07 +0100 Subject: [PATCH 099/164] Attempt at fixing failing test on conda ci --- modules/python/test/test_conversions.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/python/test/test_conversions.py b/modules/python/test/test_conversions.py index 922b3ffdca..e6a542fb18 100644 --- a/modules/python/test/test_conversions.py +++ b/modules/python/test/test_conversions.py @@ -78,7 +78,7 @@ def test_demosaic(): for fn in fns: for dtype in [np.uint8, np.uint16]: bayer_data = np.ones((h, w), dtype=dtype) * 128 - rgba = np.empty((h, w, 4), dtype=dtype) + rgba = np.zeros((h, w, 4), dtype=dtype) old_rgba = rgba.copy() fn(bayer_data, rgba) assert not np.allclose(rgba, old_rgba), f'Error when testing {fn}, with dtype {dtype}' From 394b3698e24b9f34f32cb09d18651176d5fb7996 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Tue, 12 Mar 2024 14:35:02 +0100 Subject: [PATCH 100/164] Fix warnings detected with msvc --- .../imgproc/src/vpCircleHoughTransform.cpp | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index a30d1829f9..9806d6be74 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -315,12 +315,12 @@ vpCircleHoughTransform::detect(const vpImage &I) // the pixelization of the image const float minCenterPositionDiff = 3.f; if ((m_algoParams.m_centerXlimits.second - m_algoParams.m_centerXlimits.first) < minCenterPositionDiff) { - m_algoParams.m_centerXlimits.second += minCenterPositionDiff / 2.f; - m_algoParams.m_centerXlimits.first -= minCenterPositionDiff / 2.f; + m_algoParams.m_centerXlimits.second += static_cast(minCenterPositionDiff / 2.f); + m_algoParams.m_centerXlimits.first -= static_cast(minCenterPositionDiff / 2.f); } if ((m_algoParams.m_centerYlimits.second - m_algoParams.m_centerYlimits.first) < minCenterPositionDiff) { - m_algoParams.m_centerYlimits.second += minCenterPositionDiff / 2.f; - m_algoParams.m_centerYlimits.first -= minCenterPositionDiff / 2.f; + m_algoParams.m_centerYlimits.second += static_cast(minCenterPositionDiff / 2.f); + m_algoParams.m_centerYlimits.first -= static_cast(minCenterPositionDiff / 2.f); } // First thing, we need to apply a Gaussian filter on the image to remove some spurious noise @@ -397,7 +397,7 @@ void vpCircleHoughTransform::computeVotingMask(const vpImage &I, #endif { bool hasFoundSimilarCircle = false; - unsigned int nbPreviouslyDetected = m_finalCircles.size(); + unsigned int nbPreviouslyDetected = static_cast(m_finalCircles.size()); unsigned int id = 0; // Looking for a circle that was detected and is similar to the one given to the function while ((id < nbPreviouslyDetected) && (!hasFoundSimilarCircle)) { @@ -410,7 +410,7 @@ void vpCircleHoughTransform::computeVotingMask(const vpImage &I, { hasFoundSimilarCircle = true; // We found a circle that is similar to the one given to the function => updating the mask - const unsigned int nbVotingPoints = m_finalCirclesVotingPoints[id].size(); + const unsigned int nbVotingPoints = static_cast(m_finalCirclesVotingPoints[id].size()); for (unsigned int idPoint = 0; idPoint < nbVotingPoints; ++idPoint) { const std::pair &votingPoint = m_finalCirclesVotingPoints[id][idPoint]; #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_17) @@ -858,11 +858,11 @@ vpCircleHoughTransform::computeCenterCandidates() std::sort(merged_peaks_position_votes.begin(), merged_peaks_position_votes.end(), sortingCenters); nbPeaks = static_cast(merged_peaks_position_votes.size()); - int nbPeaksToKeep = (m_algoParams.m_expectedNbCenters > 0 ? m_algoParams.m_expectedNbCenters : nbPeaks); - nbPeaksToKeep = std::min(nbPeaksToKeep, (int)nbPeaks); + int nbPeaksToKeep = (m_algoParams.m_expectedNbCenters > 0 ? m_algoParams.m_expectedNbCenters : static_cast(nbPeaks)); + nbPeaksToKeep = std::min(nbPeaksToKeep, static_cast(nbPeaks)); for (int i = 0; i < nbPeaksToKeep; i++) { m_centerCandidatesList.push_back(merged_peaks_position_votes[i].first); - m_centerVotes.push_back(merged_peaks_position_votes[i].second); + m_centerVotes.push_back(static_cast(merged_peaks_position_votes[i].second)); } } } @@ -1049,17 +1049,17 @@ vpCircleHoughTransform::computeCircleCandidates() } } - unsigned int nbCandidates = v_r_effective.size(); + unsigned int nbCandidates = static_cast(v_r_effective.size()); for (unsigned int idBin = 0; idBin < nbCandidates; ++idBin) { // If the circle of center CeC_i and radius RCB_k has enough votes, it is added to the list // of Circle Candidates float r_effective = v_r_effective[idBin]; vpImageCircle candidateCircle(vpImagePoint(centerCandidate.first, centerCandidate.second), r_effective); - float proba = computeCircleProbability(candidateCircle, v_votes_effective[idBin]); + float proba = computeCircleProbability(candidateCircle, static_cast(v_votes_effective[idBin])); if (proba > m_algoParams.m_circleProbaThresh) { m_circleCandidates.push_back(candidateCircle); m_circleCandidatesProbabilities.push_back(proba); - m_circleCandidatesVotes.push_back(v_votes_effective[idBin]); + m_circleCandidatesVotes.push_back(static_cast(v_votes_effective[idBin])); if (m_algoParams.m_recordVotingPoints) { if (v_hasMerged_effective[idBin]) { // Remove potential duplicated points @@ -1081,7 +1081,7 @@ vpCircleHoughTransform::computeCircleProbability(const vpImageCircle &circle, co float visibleArc(static_cast(nbVotes)); float theoreticalLenght; if (mp_mask != nullptr) { - theoreticalLenght = circle.computePixelsInMask(*mp_mask); + theoreticalLenght = static_cast(circle.computePixelsInMask(*mp_mask)); } else { theoreticalLenght = circle.computeArcLengthInRoI(vpRect(vpImagePoint(0, 0), m_edgeMap.getWidth(), m_edgeMap.getHeight())); From 3ce7b01dc27762cd395385866e16c5fe9985d656 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 12 Mar 2024 15:40:03 +0100 Subject: [PATCH 101/164] some config, add n-ary operators (mostly vpImage) --- modules/python/config/core_image.json | 17 ++++++---- .../generator/visp_python_bindgen/header.py | 33 +++++++++++-------- .../generator/visp_python_bindgen/methods.py | 16 +++++++++ 3 files changed, 47 insertions(+), 19 deletions(-) diff --git a/modules/python/config/core_image.json b/modules/python/config/core_image.json index 3fd597c991..ac27d0d275 100644 --- a/modules/python/config/core_image.json +++ b/modules/python/config/core_image.json @@ -39,32 +39,37 @@ }, { "static": false, - "signature": "vpImage(vpImage&&)", + "signature": "vpImage(vpImage&&)", "ignore": true }, { "static": false, - "signature": " vpImage(vpImage&&)", + "signature": "vpImage(Type*, unsigned int, unsigned int, bool)", "ignore": true }, { "static": false, - "signature": " vpImage(vpImage&&)", + "signature": "void init(Type*, unsigned int, unsigned int, bool)", "ignore": true }, { "static": false, - "signature": " vpImage(vpImage&&)", + "signature": "Type* operator[](unsigned int)", "ignore": true }, { "static": false, - "signature": " vpImage(vpImage&&)", + "signature": "Type* operator[](int)", "ignore": true }, { "static": false, - "signature": " vpImage(vpImage&&)", + "signature": "const Type* operator[](unsigned int)", + "ignore": true + }, + { + "static": false, + "signature": "const Type* operator[](int)", "ignore": true } ] diff --git a/modules/python/generator/visp_python_bindgen/header.py b/modules/python/generator/visp_python_bindgen/header.py index 42b1e8d8fb..8b785b9c0c 100644 --- a/modules/python/generator/visp_python_bindgen/header.py +++ b/modules/python/generator/visp_python_bindgen/header.py @@ -357,9 +357,6 @@ def add_method_doc_to_pyargs(method: types.Method, py_arg_strs: List[str]) -> Li is_operator=False, is_constructor=True)) # Operator definitions - binary_return_ops = supported_const_return_binary_op_map() - binary_in_place_ops = supported_in_place_binary_op_map() - unary_return_ops = supported_const_return_unary_op_map() for method, method_config in operators: method_name = get_name(method.name) @@ -369,16 +366,17 @@ def add_method_doc_to_pyargs(method: types.Method, py_arg_strs: List[str]) -> Li py_args = get_py_args(method.parameters, owner_specs, header_env.mapping) py_args = py_args + ['py::is_operator()'] param_names = [param.name or 'arg' + str(i) for i, param in enumerate(method.parameters)] - py_args = add_method_doc_to_pyargs(method, py_args) - if len(params_strs) > 1: - logging.info(f'Found operator {name_cpp}{method_name} with more than one parameter, skipping') - rejection = RejectedMethod(name_cpp, method, method_config, get_method_signature(method_name, return_type_str, params_strs), NotGeneratedReason.NotHandled) - self.submodule.report.add_non_generated_method(rejection) - continue - elif len(params_strs) < 1: - for cpp_op, python_op_name in unary_return_ops.items(): + # if len(params_strs) > 1: + # logging.info(f'Found operator {name_cpp}{method_name} with more than one parameter, skipping') + # rejection_param_strs = [get_type(param.type, {}, header_env.mapping) for param in method.parameters] + # rejection_return_type_str = get_type(method.return_type, {}, header_env.mapping) + # rejection = RejectedMethod(name_cpp, method, method_config, get_method_signature(method_name, rejection_return_type_str, rejection_param_strs), NotGeneratedReason.NotHandled) + # self.submodule.report.add_non_generated_method(rejection) + # continue + if len(params_strs) < 1: # Unary ops + for cpp_op, python_op_name in supported_const_return_unary_op_map().items(): if method_name == f'operator{cpp_op}': operator_str = lambda_const_return_unary_op(python_ident, python_op_name, cpp_op, method_is_const, name_cpp, @@ -387,7 +385,7 @@ def add_method_doc_to_pyargs(method: types.Method, py_arg_strs: List[str]) -> Li is_operator=True, is_constructor=False)) break elif len(params_strs) == 1: # e.g., self + other - for cpp_op, python_op_name in binary_return_ops.items(): + for cpp_op, python_op_name in supported_const_return_binary_op_map().items(): if method_name == f'operator{cpp_op}': operator_str = lambda_const_return_binary_op(python_ident, python_op_name, cpp_op, method_is_const, name_cpp, params_strs[0], @@ -395,7 +393,7 @@ def add_method_doc_to_pyargs(method: types.Method, py_arg_strs: List[str]) -> Li add_to_method_dict(f'__{python_op_name}__', MethodBinding(operator_str, is_static=False, is_lambda=True, is_operator=True, is_constructor=False)) break - for cpp_op, python_op_name in binary_in_place_ops.items(): + for cpp_op, python_op_name in supported_in_place_binary_op_map().items(): if method_name == f'operator{cpp_op}': operator_str = lambda_in_place_binary_op(python_ident, python_op_name, cpp_op, method_is_const, name_cpp, params_strs[0], @@ -403,6 +401,15 @@ def add_method_doc_to_pyargs(method: types.Method, py_arg_strs: List[str]) -> Li add_to_method_dict(f'__{python_op_name}__', MethodBinding(operator_str, is_static=False, is_lambda=True, is_operator=True, is_constructor=False)) break + else: # N-ary operators + for cpp_op, python_op_name in supported_nary_op_map().items(): + if method_name == f'operator{cpp_op}': + operator_str = lambda_nary_op(python_ident, python_op_name, cpp_op, + method_is_const, name_cpp, params_strs, + return_type_str, py_args) + add_to_method_dict(f'__{python_op_name}__', MethodBinding(operator_str, is_static=False, is_lambda=True, + is_operator=True, is_constructor=False)) + break # Define classical methods class_def_names = BoundObjectNames(python_ident, name_python, name_cpp_no_template, name_cpp) diff --git a/modules/python/generator/visp_python_bindgen/methods.py b/modules/python/generator/visp_python_bindgen/methods.py index bd884dec53..12748c093d 100644 --- a/modules/python/generator/visp_python_bindgen/methods.py +++ b/modules/python/generator/visp_python_bindgen/methods.py @@ -129,6 +129,22 @@ def lambda_const_return_unary_op(python_ident: str, python_op_name: str, cpp_op: return {cpp_op}self; }}, {", ".join(py_args)});''' +def supported_nary_op_map(): + return { + '()': 'call', + } + +def lambda_nary_op(python_ident: str, python_op_name: str, cpp_op: str, method_is_const: bool, + cpp_type: str, param_types: List[str], return_type: str, py_args: List[str]) -> str: + param_names = [f'arg{i}' for i in range(len(param_types))] + param_types_and_names = [f'{t} {n}' for t,n in zip(param_types, param_names)] + maybe_return = '' if return_type == 'void' else 'return' + + return f''' +{python_ident}.def("__{python_op_name}__", []({"const" if method_is_const else ""} {cpp_type}& self, {",".join(param_types_and_names)}) -> {return_type} {{ + {maybe_return} self.operator{cpp_op}({",".join(param_names)}); +}}, {", ".join(py_args)});''' + def find_and_define_repr_str(cls: ClassScope, cls_name: str, python_ident: str) -> str: for friend in cls.friends: From 2dc88099e09141d113cdf766397bd7bd7e7f0e49 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Tue, 12 Mar 2024 16:54:41 +0100 Subject: [PATCH 102/164] Fix modules dependencies --- example/CMakeLists.txt | 2 +- tutorial/CMakeLists.txt | 2 +- tutorial/gui/pcl-visualizer/CMakeLists.txt | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/example/CMakeLists.txt b/example/CMakeLists.txt index 592d13f381..884f6bae92 100644 --- a/example/CMakeLists.txt +++ b/example/CMakeLists.txt @@ -71,7 +71,7 @@ visp_add_subdirectory(direct-visual-servoing REQUIRED_DEPS visp_core visp_robo visp_add_subdirectory(homography REQUIRED_DEPS visp_core visp_vision visp_io) visp_add_subdirectory(image REQUIRED_DEPS visp_core visp_io) visp_add_subdirectory(manual REQUIRED_DEPS visp_core visp_sensor visp_vs visp_robot visp_ar visp_vision visp_io visp_gui) -visp_add_subdirectory(math REQUIRED_DEPS visp_core visp_vision visp_io) +visp_add_subdirectory(math REQUIRED_DEPS visp_core visp_io) visp_add_subdirectory(moments/image REQUIRED_DEPS visp_core visp_vs visp_robot visp_gui) visp_add_subdirectory(moments/points REQUIRED_DEPS visp_core visp_vs visp_robot visp_gui) visp_add_subdirectory(moments/polygon REQUIRED_DEPS visp_core visp_vs visp_robot visp_gui) diff --git a/tutorial/CMakeLists.txt b/tutorial/CMakeLists.txt index 7ede770bdd..beed9db781 100644 --- a/tutorial/CMakeLists.txt +++ b/tutorial/CMakeLists.txt @@ -28,7 +28,7 @@ endif() visp_add_subdirectory(bridge/opencv REQUIRED_DEPS visp_core visp_io) visp_add_subdirectory(computer-vision REQUIRED_DEPS visp_core visp_blob visp_vision visp_io visp_gui visp_detection visp_sensor) visp_add_subdirectory(grabber REQUIRED_DEPS visp_core visp_sensor visp_io visp_gui) -visp_add_subdirectory(gui/pcl-visualizer REQUIRED_DEPS visp_core visp_gui) +visp_add_subdirectory(gui/pcl-visualizer REQUIRED_DEPS visp_core visp_gui visp_io) visp_add_subdirectory(detection/barcode REQUIRED_DEPS visp_core visp_detection visp_io visp_gui visp_sensor) visp_add_subdirectory(detection/dnn REQUIRED_DEPS visp_core visp_detection visp_io visp_gui visp_sensor) visp_add_subdirectory(detection/face REQUIRED_DEPS visp_core visp_detection visp_io visp_gui visp_sensor) diff --git a/tutorial/gui/pcl-visualizer/CMakeLists.txt b/tutorial/gui/pcl-visualizer/CMakeLists.txt index 9f559fa083..de775cc076 100644 --- a/tutorial/gui/pcl-visualizer/CMakeLists.txt +++ b/tutorial/gui/pcl-visualizer/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5) project(tutorial-gui-pcl-visualizer) -find_package(VISP REQUIRED visp_core visp_gui) +find_package(VISP REQUIRED visp_core visp_gui visp_io) # set the list of source files set(tutorial_cpp From 5ebfa01b9db7f12cc4d4d7add1b01db6722df314 Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 12 Mar 2024 17:38:55 +0100 Subject: [PATCH 103/164] fix method parameters constness, mark some methods as const --- modules/core/include/visp3/core/vpBSpline.h | 29 ++++++++++---------- modules/core/include/visp3/core/vpRequest.h | 10 +++---- modules/core/include/visp3/core/vpServer.h | 8 +++--- modules/core/src/math/spline/vpBSpline.cpp | 22 +++++++-------- modules/core/src/tools/network/vpRequest.cpp | 15 +++++----- 5 files changed, 43 insertions(+), 41 deletions(-) diff --git a/modules/core/include/visp3/core/vpBSpline.h b/modules/core/include/visp3/core/vpBSpline.h index 29debfaf87..7181f7f491 100644 --- a/modules/core/include/visp3/core/vpBSpline.h +++ b/modules/core/include/visp3/core/vpBSpline.h @@ -57,7 +57,8 @@ - k indicates which kth derivative is computed. - value is the numerical value of \f$ N_{i,p}^k(u) \f$. */ -typedef struct vpBasisFunction { +typedef struct vpBasisFunction +{ unsigned int i; unsigned int p; double u; @@ -104,8 +105,8 @@ typedef struct vpBasisFunction { class VISP_EXPORT vpBSpline { - public /*protected*/: - //! Vector wich contains the control points +public /*protected*/: +//! Vector wich contains the control points std::vector controlPoints; //! Vector which contain the knots \f$ {u0, ..., um} \f$ std::vector knots; @@ -214,24 +215,24 @@ class VISP_EXPORT vpBSpline } } - static unsigned int findSpan(double l_u, unsigned int l_p, std::vector &l_knots); - unsigned int findSpan(double u); + static unsigned int findSpan(double l_u, unsigned int l_p, const std::vector &l_knots); + unsigned int findSpan(double u) const; static vpBasisFunction *computeBasisFuns(double l_u, unsigned int l_i, unsigned int l_p, - std::vector &l_knots); - vpBasisFunction *computeBasisFuns(double u); + const std::vector &l_knots); + vpBasisFunction *computeBasisFuns(double u) const; static vpBasisFunction **computeDersBasisFuns(double l_u, unsigned int l_i, unsigned int l_p, unsigned int l_der, - std::vector &l_knots); - vpBasisFunction **computeDersBasisFuns(double u, unsigned int der); + const std::vector &l_knots); + vpBasisFunction **computeDersBasisFuns(double u, unsigned int der) const; - static vpImagePoint computeCurvePoint(double l_u, unsigned int l_i, unsigned int l_p, std::vector &l_knots, - std::vector &l_controlPoints); - vpImagePoint computeCurvePoint(double u); + static vpImagePoint computeCurvePoint(double l_u, unsigned int l_i, unsigned int l_p, const std::vector &l_knots, + const std::vector &l_controlPoints); + vpImagePoint computeCurvePoint(double u) const; static vpImagePoint *computeCurveDers(double l_u, unsigned int l_i, unsigned int l_p, unsigned int l_der, - std::vector &l_knots, std::vector &l_controlPoints); - vpImagePoint *computeCurveDers(double u, unsigned int der); + const std::vector &l_knots, const std::vector &l_controlPoints); + vpImagePoint *computeCurveDers(double u, unsigned int der) const; }; #endif diff --git a/modules/core/include/visp3/core/vpRequest.h b/modules/core/include/visp3/core/vpRequest.h index 41aa8c521a..20939485e7 100644 --- a/modules/core/include/visp3/core/vpRequest.h +++ b/modules/core/include/visp3/core/vpRequest.h @@ -133,9 +133,9 @@ class VISP_EXPORT vpRequest vpRequest(); virtual ~vpRequest(); - void addParameter(char *params); - void addParameter(std::string ¶ms); - void addParameter(std::vector &listOfparams); + void addParameter(const char *params); + void addParameter(const std::string ¶ms); + void addParameter(const std::vector &listOfparams); template void addParameterObject(T *params, const int &sizeOfObject = sizeof(T)); /*! @@ -178,7 +178,7 @@ class VISP_EXPORT vpRequest \return ID of the request. */ - std::string getId() { return request_id; } + std::string getId() const { return request_id; } /*! Change the ID of the request. @@ -194,7 +194,7 @@ class VISP_EXPORT vpRequest \return Number of parameters. */ - unsigned int size() { return (unsigned int)listOfParams.size(); } + unsigned int size() const { return (unsigned int)listOfParams.size(); } }; //######## Definition of Template Functions ######## diff --git a/modules/core/include/visp3/core/vpServer.h b/modules/core/include/visp3/core/vpServer.h index b2c06cd1c5..2ab89b9ded 100644 --- a/modules/core/include/visp3/core/vpServer.h +++ b/modules/core/include/visp3/core/vpServer.h @@ -185,7 +185,7 @@ class VISP_EXPORT vpServer : public vpNetwork \return True if the server is started, false otherwise. */ - bool isStarted() { return started; } + bool isStarted() const { return started; } /*! Get the maximum number of clients that can be connected to the server. @@ -194,14 +194,14 @@ class VISP_EXPORT vpServer : public vpNetwork \return Maximum number of clients. */ - unsigned int getMaxNumberOfClients() { return max_clients; } + unsigned int getMaxNumberOfClients() const { return max_clients; } /*! Get the number of clients connected to the server. \return Number of clients connected. */ - unsigned int getNumberOfClients() { return (unsigned int)receptor_list.size(); } + unsigned int getNumberOfClients() const { return (unsigned int)receptor_list.size(); } void print(); @@ -214,7 +214,7 @@ class VISP_EXPORT vpServer : public vpNetwork \param l : Maximum number of clients. */ - void setMaxNumberOfClients(unsigned int &l) { max_clients = l; } + void setMaxNumberOfClients(const unsigned int &l) { max_clients = l; } }; #endif diff --git a/modules/core/src/math/spline/vpBSpline.cpp b/modules/core/src/math/spline/vpBSpline.cpp index 408757f339..4f4b16cfb1 100644 --- a/modules/core/src/math/spline/vpBSpline.cpp +++ b/modules/core/src/math/spline/vpBSpline.cpp @@ -76,7 +76,7 @@ vpBSpline::~vpBSpline() { } \return the number of the knot interval in which \f$ l_u \f$ lies. */ -unsigned int vpBSpline::findSpan(double l_u, unsigned int l_p, std::vector &l_knots) +unsigned int vpBSpline::findSpan(double l_u, unsigned int l_p, const std::vector &l_knots) { unsigned int m = (unsigned int)l_knots.size() - 1; @@ -120,7 +120,7 @@ unsigned int vpBSpline::findSpan(double l_u, unsigned int l_p, std::vector &l_knots) + const std::vector &l_knots) { vpBasisFunction *N = new vpBasisFunction[l_p + 1]; @@ -190,7 +190,7 @@ vpBasisFunction *vpBSpline::computeBasisFuns(double l_u, unsigned int l_i, unsig \return An array containing the nonvanishing basis functions at \f$ u \f$. The size of the array is \f$ p +1 \f$. */ -vpBasisFunction *vpBSpline::computeBasisFuns(double u) +vpBasisFunction *vpBSpline::computeBasisFuns(double u) const { unsigned int i = findSpan(u); return computeBasisFuns(u, i, p, knots); @@ -226,7 +226,7 @@ vpBasisFunction *vpBSpline::computeBasisFuns(double u) functions. return[k] is the list of the kth derivatives. */ vpBasisFunction **vpBSpline::computeDersBasisFuns(double l_u, unsigned int l_i, unsigned int l_p, unsigned int l_der, - std::vector &l_knots) + const std::vector &l_knots) { vpBasisFunction **N; N = new vpBasisFunction *[l_der + 1]; @@ -355,7 +355,7 @@ vpBasisFunction **vpBSpline::computeDersBasisFuns(double l_u, unsigned int l_i, Example : return[0] is the list of the 0th derivatives ie the basis functions. return[k] is the list of the kth derivatives. */ -vpBasisFunction **vpBSpline::computeDersBasisFuns(double u, unsigned int der) +vpBasisFunction **vpBSpline::computeDersBasisFuns(double u, unsigned int der) const { unsigned int i = findSpan(u); return computeDersBasisFuns(u, i, p, der, knots); @@ -372,8 +372,8 @@ vpBasisFunction **vpBSpline::computeDersBasisFuns(double u, unsigned int der) return the coordinates of a point corresponding to the knot \f$ u \f$. */ -vpImagePoint vpBSpline::computeCurvePoint(double l_u, unsigned int l_i, unsigned int l_p, std::vector &l_knots, - std::vector &l_controlPoints) +vpImagePoint vpBSpline::computeCurvePoint(double l_u, unsigned int l_i, unsigned int l_p, const std::vector &l_knots, + const std::vector &l_controlPoints) { vpBasisFunction *N = computeBasisFuns(l_u, l_i, l_p, l_knots); vpImagePoint pt; @@ -401,7 +401,7 @@ vpImagePoint vpBSpline::computeCurvePoint(double l_u, unsigned int l_i, unsigned return the coordinates of a point corresponding to the knot \f$ u \f$. */ -vpImagePoint vpBSpline::computeCurvePoint(double u) +vpImagePoint vpBSpline::computeCurvePoint(double u) const { vpBasisFunction *N = computeBasisFuns(u); vpImagePoint pt; @@ -443,7 +443,7 @@ vpImagePoint vpBSpline::computeCurvePoint(double u) the array. */ vpImagePoint *vpBSpline::computeCurveDers(double l_u, unsigned int l_i, unsigned int l_p, unsigned int l_der, - std::vector &l_knots, std::vector &l_controlPoints) + const std::vector &l_knots, const std::vector &l_controlPoints) { vpImagePoint *derivate = new vpImagePoint[l_der + 1]; vpBasisFunction **N; @@ -489,7 +489,7 @@ vpImagePoint *vpBSpline::computeCurveDers(double l_u, unsigned int l_i, unsigned for \f$ k = 0, ... , der \f$. The kth derivative is in the kth cell of the array. */ -vpImagePoint *vpBSpline::computeCurveDers(double u, unsigned int der) +vpImagePoint *vpBSpline::computeCurveDers(double u, unsigned int der) const { vpImagePoint *derivate = new vpImagePoint[der + 1]; vpBasisFunction **N; diff --git a/modules/core/src/tools/network/vpRequest.cpp b/modules/core/src/tools/network/vpRequest.cpp index 80d23fa814..bc3fd7b313 100644 --- a/modules/core/src/tools/network/vpRequest.cpp +++ b/modules/core/src/tools/network/vpRequest.cpp @@ -38,9 +38,9 @@ #include -vpRequest::vpRequest() : request_id(""), listOfParams() {} +vpRequest::vpRequest() : request_id(""), listOfParams() { } -vpRequest::~vpRequest() {} +vpRequest::~vpRequest() { } /*! Add a message as parameter of the request. @@ -49,7 +49,7 @@ vpRequest::~vpRequest() {} \param params : Array of characters representing the message to add. */ -void vpRequest::addParameter(char *params) +void vpRequest::addParameter(const char *params) { std::string val = params; listOfParams.push_back(val); @@ -62,7 +62,7 @@ void vpRequest::addParameter(char *params) \param params : std::string representing the message to add. */ -void vpRequest::addParameter(std::string ¶ms) { listOfParams.push_back(params); } +void vpRequest::addParameter(const std::string ¶ms) { listOfParams.push_back(params); } /*! Add messages as parameters of the request. @@ -72,8 +72,9 @@ void vpRequest::addParameter(std::string ¶ms) { listOfParams.push_back(param \param listOfparams : Array of std::string representing the messages to add. */ -void vpRequest::addParameter(std::vector &listOfparams) +void vpRequest::addParameter(const std::vector &listOfparams) { - for (unsigned int i = 0; i < listOfparams.size(); i++) - listOfparams.push_back(listOfparams[i]); + for (unsigned int i = 0; i < listOfparams.size(); i++) { + this->listOfParams.push_back(listOfparams[i]); + } } From acc23273895472901fadad6f5e63a72cd8af60eb Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 12 Mar 2024 17:39:12 +0100 Subject: [PATCH 104/164] Some more configuration --- modules/python/config/core.json | 396 ++-------------- modules/python/config/core_image.json | 439 ++++++++++++++++++ .../generator/visp_python_bindgen/header.py | 2 +- .../visp_python_bindgen/template_expansion.py | 1 + 4 files changed, 491 insertions(+), 347 deletions(-) diff --git a/modules/python/config/core.json b/modules/python/config/core.json index aa3e22243e..49797242f6 100644 --- a/modules/python/config/core.json +++ b/modules/python/config/core.json @@ -305,12 +305,12 @@ [ { "static": true, - "signature": "unsigned int findSpan(double, unsigned int, std::vector &)", + "signature": "unsigned int findSpan(double, unsigned int, const std::vector &)", "custom_name": "findSpanFromSpline" }, { "static": true, - "signature": "vpImagePoint computeCurvePoint(double, unsigned int, unsigned int, std::vector &, std::vector&)", + "signature": "vpImagePoint computeCurvePoint(double, unsigned int, unsigned int, const std::vector &, const std::vector&)", "custom_name": "computeCurvePointFromSpline" }, { @@ -350,349 +350,6 @@ } ] }, - "vpImageTools": { - "methods": - [ - { - "static": true, - "signature": "void warpImage(const vpImage&, const vpMatrix&, vpImage&, const vpImageTools::vpImageInterpolationType&, bool, bool)", - "specializations": - [ - ["unsigned char"], - ["vpRGBa"] - ] - } - ] - }, - "vpImageConvert": { - "additional_bindings": "bindings_vpImageConvert", - "methods": - [ - { - "static": true, - "signature": "void RGBaToRGB(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBaToGrey(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBToRGBa(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBToGrey(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBToGrey(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV444ToRGBa(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV444ToRGB(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV444ToGrey(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void GreyToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void GreyToRGBa(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void GreyToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void GreyToRGB(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUYVToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUYVToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUYVToGrey(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV411ToRGBa(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV411ToRGB(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV411ToGrey(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV422ToRGBa(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV422ToRGB(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV422ToGrey(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV420ToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV420ToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YUV420ToGrey(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YV12ToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YV12ToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YVU9ToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YVU9ToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YCbCrToRGB(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YCbCrToRGBa(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YCbCrToGrey(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YCrCbToRGB(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void YCrCbToRGBa(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBaToHSV(const unsigned char*, unsigned char*, unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void HSVToRGB(const double*, const double*, const double*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void HSVToRGB(const unsigned char*, const unsigned char*, const unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void HSVToRGBa(const unsigned char*, const unsigned char*, const unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void HSVToRGBa(const double*, const double*, const double*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBToHSV(const unsigned char*, double*, double*, double*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBToHSV(const unsigned char*, unsigned char*, unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBaToHSV(const unsigned char*, unsigned char*, unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void RGBaToHSV(const unsigned char*, double*, double*, double*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void MONO16ToGrey(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void MONO16ToRGBa(unsigned char*, unsigned char*, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void BGRaToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", - "ignore": true - }, - { - "static": true, - "signature": "void BGRToGrey(unsigned char*, unsigned char*, unsigned int, unsigned int, bool, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void BGRToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicBGGRToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicBGGRToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicGBRGToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicGBRGToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicGRBGToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - - }, - { - "static": true, - "signature": "void demosaicGRBGToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicRGGBToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicRGGBToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicBGGRToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicBGGRToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicGBRGToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - - }, - { - "static": true, - "signature": "void demosaicGBRGToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - - }, - { - "static": true, - "signature": "void demosaicGRBGToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicGRBGToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicRGGBToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - }, - { - "static": true, - "signature": "void demosaicRGGBToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", - "ignore": true - } - ] - }, "vpConvert": { "methods": [ { @@ -844,6 +501,22 @@ } ] }, + "vpMomentObject": { + "methods": [ + { + "static": false, + "signature": "void fromVector(std::vector&)", + "use_default_param_policy": false, + "param_is_input": [ + true + ], + "param_is_output": [ + true + ], + "comment": "The point list is modified, cannot be consted. So it is taken as input and returned." + } + ] + }, "vpPixelMeterConversion": { "additional_bindings": "bindings_vpPixelMeterConversion", "methods": [ @@ -1102,6 +775,37 @@ "static": false, "signature": "int receive(void*, size_t, int)", "ignore": true + }, + { + "static": false, + "signature": "int receive(std::string&, int)", + "use_default_param_policy": false, + "param_is_input": [ + false, + true + ], + "param_is_output": [ + true, + false + ] + } + ] + }, + "vpUDPServer": { + "methods": [ + { + "static": false, + "signature": "int receive(std::string&, std::string&, int)", + "use_default_param_policy": false, + "param_is_input": [false, false, true], + "param_is_output": [true, true, false] + }, + { + "static": false, + "signature": "int receive(std::string&, int)", + "use_default_param_policy": false, + "param_is_input": [false, true], + "param_is_output": [true, false] } ] }, @@ -1125,7 +829,7 @@ }, { "static": false, - "signature": "unsigned getValey(std::list&)", + "signature": "unsigned getValey(std::list&)", "use_default_param_policy": false, "param_is_input": [false], "param_is_output": [true] diff --git a/modules/python/config/core_image.json b/modules/python/config/core_image.json index ac27d0d275..11369876c3 100644 --- a/modules/python/config/core_image.json +++ b/modules/python/config/core_image.json @@ -91,6 +91,445 @@ "ignore": true } ] + }, + "vpImageTools": { + "methods": + [ + { + "static": true, + "signature": "void warpImage(const vpImage&, const vpMatrix&, vpImage&, const vpImageTools::vpImageInterpolationType&, bool, bool)", + "specializations": + [ + ["unsigned char"], + ["float"], + ["double"], + ["uint16_t"], + ["vpRGBa"] + ] + }, + { + "static": true, + "signature": "void crop(const vpImage&, double, double, unsigned int, unsigned int, vpImage&, unsigned int, unsigned int)", + "specializations": + [ + ["TypeImage"] + ] + }, + { + "static": true, + "signature": "void crop(const vpImage&, const vpImagePoint&, unsigned int, unsigned int, vpImage&, unsigned int, unsigned int)", + "specializations": + [ + ["TypeImage"] + ] + }, + { + "static": true, + "signature": "void crop(const vpImage&, const vpRect&, vpImage&, unsigned int, unsigned int)", + "specializations": + [ + ["TypeImage"] + ] + }, + { + "static": true, + "signature": "void crop(const unsigned char*, unsigned int, unsigned int, const vpRect&, vpImage&, unsigned int, unsigned int)", + "ignore": true + } + ] + }, + "vpImageConvert": { + "additional_bindings": "bindings_vpImageConvert", + "methods": + [ + { + "static": true, + "signature": "void RGBaToRGB(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBaToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBToRGBa(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBToGrey(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV444ToRGBa(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV444ToRGB(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV444ToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void GreyToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void GreyToRGBa(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void GreyToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void GreyToRGB(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUYVToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUYVToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUYVToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV411ToRGBa(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV411ToRGB(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV411ToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV422ToRGBa(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV422ToRGB(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV422ToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV420ToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV420ToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YUV420ToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YV12ToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YV12ToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YVU9ToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YVU9ToRGB(unsigned char*, unsigned char*, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YCbCrToRGB(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YCbCrToRGBa(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YCbCrToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YCrCbToRGB(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void YCrCbToRGBa(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBaToHSV(const unsigned char*, unsigned char*, unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void HSVToRGB(const double*, const double*, const double*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void HSVToRGB(const unsigned char*, const unsigned char*, const unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void HSVToRGBa(const unsigned char*, const unsigned char*, const unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void HSVToRGBa(const double*, const double*, const double*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBToHSV(const unsigned char*, double*, double*, double*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBToHSV(const unsigned char*, unsigned char*, unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBaToHSV(const unsigned char*, unsigned char*, unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void RGBaToHSV(const unsigned char*, double*, double*, double*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void MONO16ToGrey(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void MONO16ToRGBa(unsigned char*, unsigned char*, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void BGRaToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void BGRToGrey(unsigned char*, unsigned char*, unsigned int, unsigned int, bool, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void BGRToRGBa(unsigned char*, unsigned char*, unsigned int, unsigned int, bool)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicBGGRToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicBGGRToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicGBRGToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicGBRGToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicGRBGToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + + }, + { + "static": true, + "signature": "void demosaicGRBGToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicRGGBToRGBaBilinear(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicRGGBToRGBaBilinear(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicBGGRToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicBGGRToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicGBRGToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + + }, + { + "static": true, + "signature": "void demosaicGBRGToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + + }, + { + "static": true, + "signature": "void demosaicGRBGToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicGRBGToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicRGGBToRGBaMalvar(const uint8_t*, uint8_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + }, + { + "static": true, + "signature": "void demosaicRGGBToRGBaMalvar(const uint16_t*, uint16_t*, unsigned int, unsigned int, unsigned int)", + "ignore": true, + "custom_implem": true + } + ] } } } diff --git a/modules/python/generator/visp_python_bindgen/header.py b/modules/python/generator/visp_python_bindgen/header.py index 8b785b9c0c..c32bc6db6a 100644 --- a/modules/python/generator/visp_python_bindgen/header.py +++ b/modules/python/generator/visp_python_bindgen/header.py @@ -488,7 +488,7 @@ def add_method_doc_to_pyargs(method: types.Method, py_arg_strs: List[str]) -> Li if len(error_generating_overloads) > 0: logging.error(f'Overloads defined for instance and class, this will generate a pybind error') logging.error(error_generating_overloads) - raise RuntimeError + raise RuntimeError('Error generating overloads:\n' + '\n'.join(error_generating_overloads)) field_dict = {} for field in cls.fields: diff --git a/modules/python/generator/visp_python_bindgen/template_expansion.py b/modules/python/generator/visp_python_bindgen/template_expansion.py index 0af35c2c43..69700e5e19 100644 --- a/modules/python/generator/visp_python_bindgen/template_expansion.py +++ b/modules/python/generator/visp_python_bindgen/template_expansion.py @@ -5,6 +5,7 @@ 'TypePythonScalar': ['int', 'double'], # Python itself doesn't make the distinction between int, uint, int16_t etc. 'TypeFilterable': ['unsigned char', 'float', 'double'], 'TypeErodableDilatable': ['unsigned char', 'float', 'double'], + 'TypeImage': ['unsigned char', 'uint16_t', 'float', 'double', 'bool', 'vpRGBa', 'vpRGBf'], 'TypeBaseImagePixel': ['unsigned char', 'vpRGBa'] } From a66a8c72d76be24bae2711e026b6616b76716089 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Tue, 12 Mar 2024 17:45:09 +0100 Subject: [PATCH 105/164] [WIP] Specialization of vpImage::getStdev for vpRGBa and vpRGBf. Problems with Doxygen --- modules/core/include/visp3/core/vpImage.h | 153 +++++++++++++++++++++- 1 file changed, 151 insertions(+), 2 deletions(-) diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index b3f82d0794..3bb4ebfb9e 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -1043,6 +1043,130 @@ template double vpImage::getStdev(const double &mean, const u return std::sqrt(sum); } +/** + * \relates vpImage + * + * For a vpRGBa image, we compute the standard deviation as follow: + * + * \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} I[r][c].R + I[r][c].G + I[r][c].B - \mu}\f$ + * + * where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . + * + * \return The sum of the R, G and B components of all pixels. + */ +template <> inline double vpImage::getStdev(const double &mean) const +{ + if ((height == 0) || (width == 0)) { + return 0.0; + } + + double res = 0.0; + const unsigned int size = height * width; + for (unsigned int i = 0; i < size; ++i) { + double val = static_cast(bitmap[i].R) + static_cast(bitmap[i].G) + static_cast(bitmap[i].B); + res += (val - mean) * (val - mean); + } + res /= static_cast(size); + return res; +} + +/** + * \relates vpImage + * + * For a vpRGBa image, we compute the standard deviation as follow: + * + * \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} I[r][c].R + I[r][c].G + I[r][c].B - \mu}\f$ + * + * where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . + * + * \param[in] mean The mean of the image. + * \param[in] nbValidPoints Number of points that are valid according to the boolean mask. + * \param[in] p_mask A boolean mask that indicates which points must be considered, if set. + */ +template <> inline double vpImage::getStdev(const double &mean, const unsigned int &nbValidPoints, const vpImage *p_mask) const +{ + if ((height == 0) || (width == 0)) { + return 0.0; + } + + if (p_mask == nullptr) { + return getStdev(mean); + } + + const unsigned int size = width * height; + double sum = 0.; + for (unsigned int i = 0; i < size; ++i) { + if (p_mask->bitmap[i]) { + double val = static_cast(bitmap[i].R) + static_cast(bitmap[i].G) + static_cast(bitmap[i].B); + sum += (val - mean) * (val - mean); + } + } + sum /= static_cast(nbValidPoints); + return sum; +} + +/** + * \relates vpImage + * + * For a vpRGBf image, we compute the standard deviation as follow: + * + * \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} I[r][c].R + I[r][c].G + I[r][c].B - \mu}\f$ + * + * where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . + * + * \return The sum of the R, G and B components of all pixels. + */ +template <> inline double vpImage::getStdev(const double &mean) const +{ + if ((height == 0) || (width == 0)) { + return 0.0; + } + + double res = 0.0; + const unsigned int size = height * width; + for (unsigned int i = 0; i < size; ++i) { + double val = static_cast(bitmap[i].R) + static_cast(bitmap[i].G) + static_cast(bitmap[i].B); + res += (val - mean) * (val - mean); + } + res /= static_cast(size); + return res; +} + +/** + * \relates vpImage + * + * For a vpRGBf image, we compute the standard deviation as follow: + * + * \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} I[r][c].R + I[r][c].G + I[r][c].B - \mu}\f$ + * + * where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . + * + * \param[in] mean The mean of the image. + * \param[in] nbValidPoints Number of points that are valid according to the boolean mask. + * \param[in] p_mask A boolean mask that indicates which points must be considered, if set. + */ +template <> inline double vpImage::getStdev(const double &mean, const unsigned int &nbValidPoints, const vpImage *p_mask) const +{ + if ((height == 0) || (width == 0)) { + return 0.0; + } + + if (p_mask == nullptr) { + return getStdev(mean); + } + + const unsigned int size = width * height; + double sum = 0.; + for (unsigned int i = 0; i < size; ++i) { + if (p_mask->bitmap[i]) { + double val = static_cast(bitmap[i].R) + static_cast(bitmap[i].G) + static_cast(bitmap[i].B); + sum += (val - mean) * (val - mean); + } + } + sum /= static_cast(nbValidPoints); + return sum; +} + /*! * \brief Return the minimum value within the bitmap * \param onlyFiniteVal : This parameter is ignored for non double or non float bitmap. @@ -1950,7 +2074,7 @@ template <> inline vpRGBa vpImage::getValue(const vpImagePoint &ip) cons } /** - * Compute the sum of image intensities. + * \brief Compute the sum of image intensities. * For vpRGBa image type, compute the sum (R+G+B) of image intensities. */ template inline double vpImage::getSum() const @@ -1966,7 +2090,7 @@ template inline double vpImage::getSum() const } /** - * Compute the sum of image intensities. + * \brief Compute the sum of image intensities. * For vpRGBa image type, compute the sum (R+G+B) of image intensities. * * \param[in] p_mask Boolean mask that indicates the valid points by a true flag. @@ -1995,6 +2119,11 @@ template inline double vpImage::getSum(const vpImage *p /** * \relates vpImage + * + * \brief Get the sum of the image. + * For a vpRGBf image, we takes the sum of the R, G and B components. + * + * \return The sum of the R, G and B components of all pixels. */ template <> inline double vpImage::getSum() const { @@ -2010,6 +2139,14 @@ template <> inline double vpImage::getSum() const /** * \relates vpImage + * \brief Get the sum of the image, taking into account the boolean mask \b p_mask + * for which a true value indicates to consider a pixel and false means to ignore it. + * For a vpRGBa image, we takes the sum of the R, G and B components. + * + * \param[in] p_mask If different from nullptr, boolean mask that tells which pixels are + * to be considered. + * \param[out] nbValidPoints The number of pixels which were taken into account. + * \return The sum of the R, G and B components of all pixels that were taken into account. */ template <> inline double vpImage::getSum(const vpImage *p_mask, unsigned int &nbValidPoints) const { @@ -2036,6 +2173,10 @@ template <> inline double vpImage::getSum(const vpImage *p_mask, u /** * \relates vpImage + * \brief Get the sum of the image. + * For a vpRGBf image, we takes the sum of the R, G and B components. + * + * \return The sum of the R, G and B components of all pixels. */ template <> inline double vpImage::getSum() const { @@ -2051,6 +2192,14 @@ template <> inline double vpImage::getSum() const /** * \relates vpImage + * \brief Get the sum of the image, taking into account the boolean mask \b p_mask + * for which a true value indicates to consider a pixel and false means to ignore it. + * For a vpRGBf image, we takes the sum of the R, G and B components. + * + * \param[in] p_mask If different from nullptr, boolean mask that tells which pixels are + * to be considered. + * \param[out] nbValidPoints The number of pixels which were taken into account. + * \return The sum of the R, G and B components of all pixels that were taken into account. */ template <> inline double vpImage::getSum(const vpImage *p_mask, unsigned int &nbValidPoints) const { From aa81465de4607b523bed3ed8c718392b0af14a91 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Tue, 12 Mar 2024 21:04:36 +0100 Subject: [PATCH 106/164] [DOC] Found a fix for doxygen problem --- modules/core/include/visp3/core/vpImage.h | 123 +++++++++++++--------- 1 file changed, 75 insertions(+), 48 deletions(-) diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 3bb4ebfb9e..3ffcbdc9b1 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -1006,8 +1006,14 @@ template double vpImage::getStdev(const vpImage *p_mask /*! * \brief Return the standard deviation of the bitmap -* -* \param[in] mean The mean of the image. + * For a vpRGBa or a vpRGBf image, we compute the standard deviation as follow: + * + * \f$ stdev = \sqrt{\frac{1}{nbValidPoints} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} (I[r][c].R + I[r][c].G + I[r][c].B - \mu)^2}\f$ + * + * where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . + * + * \param[in] mean The mean of the image. + * \return double The standard deviation of the color image. */ template double vpImage::getStdev(const double &mean) const { @@ -1023,9 +1029,16 @@ template double vpImage::getStdev(const double &mean) const /*! * \brief Return the standard deviation of the bitmap * +* For a vpRGBa or a vpRGBf image, we compute the standard deviation as follow: +* +* \f$ stdev = \sqrt{\frac{1}{nbValidPoints} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} (I[r][c].R + I[r][c].G + I[r][c].B - \mu)^2 \delta(r,c)} where \delta(r,c) = 1 if p_mask[r][c], 0 otherwise\f$ +* +* where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . +* * \param[in] mean The mean of the image. * \param[in] nbValidPoints Number of points that are valid according to the boolean mask. * \param[in] p_mask A boolean mask that indicates which points must be considered, if set. +* \return double The standard deviation taking into account only the points for which the mask is true. */ template double vpImage::getStdev(const double &mean, const unsigned int &nbValidPoints, const vpImage *p_mask) const { @@ -1043,17 +1056,19 @@ template double vpImage::getStdev(const double &mean, const u return std::sqrt(sum); } -/** - * \relates vpImage - * - * For a vpRGBa image, we compute the standard deviation as follow: - * - * \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} I[r][c].R + I[r][c].G + I[r][c].B - \mu}\f$ - * - * where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . - * - * \return The sum of the R, G and B components of all pixels. - */ +/* +/!\ Did not use Doxygen for this method because it does not handle template specialization +* Return the standard deviation of the bitmap +* +* For a vpRGBa or a vpRGBf image, we compute the standard deviation as follow: +* +* \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} (I[r][c].R + I[r][c].G + I[r][c].B - \mu)^2}\f$ +* +* where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . +* +* param[in] mean The mean of the image. +* return The standard deviation. +*/ template <> inline double vpImage::getStdev(const double &mean) const { if ((height == 0) || (width == 0)) { @@ -1070,19 +1085,21 @@ template <> inline double vpImage::getStdev(const double &mean) const return res; } -/** - * \relates vpImage - * - * For a vpRGBa image, we compute the standard deviation as follow: - * - * \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} I[r][c].R + I[r][c].G + I[r][c].B - \mu}\f$ - * - * where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . - * - * \param[in] mean The mean of the image. - * \param[in] nbValidPoints Number of points that are valid according to the boolean mask. - * \param[in] p_mask A boolean mask that indicates which points must be considered, if set. - */ +/* +/!\ Did not use Doxygen for this method because it does not handle template specialization +* Return the standard deviation of the bitmap +* +* For a vpRGBa or a vpRGBf image, we compute the standard deviation as follow: +* +* \f$ stdev = \sqrt{\frac{1}{nbValidPoints} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} (I[r][c].R + I[r][c].G + I[r][c].B - \mu)^2 \delta(r,c)} where \delta(r,c) = 1 if p_mask[r][c], 0 otherwise\f$ +* +* where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . +* +* param[in] mean The mean of the image. +* param[in] nbValidPoints Number of points that are valid according to the boolean mask. +* param[in] p_mask A boolean mask that indicates which points must be considered, if set. +* return The standard deviation taking into account only the points for which the mask is true.The standard deviation taking into account only the points for which the mask is true. +*/ template <> inline double vpImage::getStdev(const double &mean, const unsigned int &nbValidPoints, const vpImage *p_mask) const { if ((height == 0) || (width == 0)) { @@ -1105,17 +1122,22 @@ template <> inline double vpImage::getStdev(const double &mean, const un return sum; } +/* +/!\ Did not use Doxygen for this method because it does not handle template specialization +* Return the standard deviation of the bitmap +* +* For a vpRGBa or a vpRGBf image, we compute the standard deviation as follow: +* +* \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} (I[r][c].R + I[r][c].G + I[r][c].B - \mu)^2}\f$ +* +* where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . +* +* param[in] mean The mean of the image. +* return The standard deviation. +*/ /** - * \relates vpImage - * - * For a vpRGBf image, we compute the standard deviation as follow: - * - * \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} I[r][c].R + I[r][c].G + I[r][c].B - \mu}\f$ - * - * where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . - * - * \return The sum of the R, G and B components of all pixels. - */ +* \brief \copybrief double vpImage::getStdev(const double &) const +*/ template <> inline double vpImage::getStdev(const double &mean) const { if ((height == 0) || (width == 0)) { @@ -1132,19 +1154,24 @@ template <> inline double vpImage::getStdev(const double &mean) const return res; } +/* +/!\ Did not use Doxygen for this method because it does not handle template specialization +* Return the standard deviation of the bitmap +* +* For a vpRGBa or a vpRGBf image, we compute the standard deviation as follow: +* +* \f$ stdev = \sqrt{\frac{1}{nbValidPoints} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} (I[r][c].R + I[r][c].G + I[r][c].B - \mu)^2 \delta(r,c)} where \delta(r,c) = 1 if p_mask[r][c], 0 otherwise\f$ +* +* where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . +* +* param[in] mean The mean of the image. +* param[in] nbValidPoints Number of points that are valid according to the boolean mask. +* param[in] p_mask A boolean mask that indicates which points must be considered, if set. +* return The standard deviation taking into account only the points for which the mask is true. +*/ /** - * \relates vpImage - * - * For a vpRGBf image, we compute the standard deviation as follow: - * - * \f$ stdev = \sqrt{\frac{1}{width * height} \sum_{r = 0}^{height-1} \sum_{c = 0}^{width-1} I[r][c].R + I[r][c].G + I[r][c].B - \mu}\f$ - * - * where \f$ \mu \f$ is the mean of the image as computed by \b vpImage::getMeanValue() . - * - * \param[in] mean The mean of the image. - * \param[in] nbValidPoints Number of points that are valid according to the boolean mask. - * \param[in] p_mask A boolean mask that indicates which points must be considered, if set. - */ +* \brief \copybrief double vpImage::getStdev(const double &, const unsigned int&, const vpImage*) const +*/ template <> inline double vpImage::getStdev(const double &mean, const unsigned int &nbValidPoints, const vpImage *p_mask) const { if ((height == 0) || (width == 0)) { From bc3384d66417c9c42b47b58ed12d959dd8a6b116 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 09:28:34 +0100 Subject: [PATCH 107/164] Fix warning detected by ros2 ci See https://build.ros2.org/job/Hdev__visp__ubuntu_jammy_amd64/181/ --- modules/core/include/visp3/core/vpHinkley.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/modules/core/include/visp3/core/vpHinkley.h b/modules/core/include/visp3/core/vpHinkley.h index 6d9ee47e07..046e6fa8ae 100644 --- a/modules/core/include/visp3/core/vpHinkley.h +++ b/modules/core/include/visp3/core/vpHinkley.h @@ -43,6 +43,7 @@ #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) /*! \class vpHinkley + \deprecated This class is deprecated. You should rather use vpStatisticalTestHinkley. \ingroup group_core_math_tools \brief This class implements the Hinkley's cumulative sum test. @@ -89,7 +90,7 @@ N_{k^{'}} = 0 \f$. */ -class vp_deprecated vpHinkley +class VISP_EXPORT vpHinkley { public: /*! \enum vpHinkleyJumpType @@ -103,9 +104,9 @@ class vp_deprecated vpHinkley } vpHinkleyJumpType; public: - vpHinkley(); + vp_deprecated vpHinkley(); virtual ~vpHinkley(); - vpHinkley(double alpha, double delta); + vp_deprecated vpHinkley(double alpha, double delta); void init(); void init(double alpha, double delta); From b1c4c58d4624b6f47aacc155658b455f4bad1780 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 09:29:42 +0100 Subject: [PATCH 108/164] Update copyright header --- modules/core/include/visp3/core/vpStatisticalTestAbstract.h | 6 +++--- modules/core/include/visp3/core/vpStatisticalTestEWMA.h | 6 +++--- modules/core/include/visp3/core/vpStatisticalTestHinkley.h | 6 +++--- .../include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h | 6 +++--- modules/core/include/visp3/core/vpStatisticalTestShewhart.h | 6 +++--- modules/core/include/visp3/core/vpStatisticalTestSigma.h | 6 +++--- modules/core/src/math/misc/vpStatisticalTestAbstract.cpp | 5 ++--- modules/core/src/math/misc/vpStatisticalTestEWMA.cpp | 5 ++--- modules/core/src/math/misc/vpStatisticalTestHinkley.cpp | 5 ++--- .../src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp | 5 ++--- modules/core/src/math/misc/vpStatisticalTestShewhart.cpp | 5 ++--- modules/core/src/math/misc/vpStatisticalTestSigma.cpp | 5 ++--- 12 files changed, 30 insertions(+), 36 deletions(-) diff --git a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h index dbf9604a2d..cd7e0454e9 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestAbstract.h +++ b/modules/core/include/visp3/core/vpStatisticalTestAbstract.h @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,8 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ + /*! * \file vpStatisticalTestAbstract.h * \brief Base class for Statistical Process Control methods implementation. diff --git a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h index 134debf418..63893668c9 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestEWMA.h +++ b/modules/core/include/visp3/core/vpStatisticalTestEWMA.h @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,8 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ + /*! * \file vpStatisticalTestEWMA.h * \brief Statistical Process Control Exponentially Weighted Moving Average implementation. diff --git a/modules/core/include/visp3/core/vpStatisticalTestHinkley.h b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h index e07d4b1591..9a8dcc2724 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestHinkley.h +++ b/modules/core/include/visp3/core/vpStatisticalTestHinkley.h @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,8 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ + /*! * \file vpStatisticalTestHinkley.h * \brief Statistical Process Control Hinkley's test implementation. diff --git a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h index fdb9f09ebf..8a39d7d8f0 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h +++ b/modules/core/include/visp3/core/vpStatisticalTestMeanAdjustedCUSUM.h @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,8 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ + /*! * \file vpStatisticalTestMeanAdjustedCUSUM.h * \brief Statistical Process Control mean adjusted CUSUM implementation. diff --git a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h index 32c543086a..9954831496 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestShewhart.h +++ b/modules/core/include/visp3/core/vpStatisticalTestShewhart.h @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,8 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ + /*! * \file vpStatisticalTestShewhart.h * \brief Statistical Process Control Shewhart's test implementation. diff --git a/modules/core/include/visp3/core/vpStatisticalTestSigma.h b/modules/core/include/visp3/core/vpStatisticalTestSigma.h index 3c0f10facd..210da6eba0 100644 --- a/modules/core/include/visp3/core/vpStatisticalTestSigma.h +++ b/modules/core/include/visp3/core/vpStatisticalTestSigma.h @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,8 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ + /*! * \file vpStatisticalTestSigma.h * \brief Statistical Process Control sigma test implementation. diff --git a/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp index 399b4b3ddd..3f1cb6e76a 100644 --- a/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestAbstract.cpp @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,7 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ /** * diff --git a/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp b/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp index 6cb06fee31..6e1d925f82 100644 --- a/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestEWMA.cpp @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,7 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ /** * diff --git a/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp b/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp index 6d75931952..84655b3aad 100644 --- a/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestHinkley.cpp @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,7 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ /** * diff --git a/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp b/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp index 0007b0a0eb..c5fbb5fbdb 100644 --- a/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestMeanAdjustedCUSUM.cpp @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,7 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ /** * diff --git a/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp index b30bcf0a1f..f514b7be8c 100644 --- a/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestShewhart.cpp @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,7 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ /** * diff --git a/modules/core/src/math/misc/vpStatisticalTestSigma.cpp b/modules/core/src/math/misc/vpStatisticalTestSigma.cpp index 5a64cacbbc..6180460386 100644 --- a/modules/core/src/math/misc/vpStatisticalTestSigma.cpp +++ b/modules/core/src/math/misc/vpStatisticalTestSigma.cpp @@ -1,7 +1,7 @@ /**************************************************************************** * * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -27,8 +27,7 @@ * * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. - * -*****************************************************************************/ + */ /** * From 998b744b7fac123cf69290fe9ae96303b408d178 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Wed, 13 Mar 2024 09:54:45 +0100 Subject: [PATCH 109/164] [TEST] Added a test for vpImage::getSum, getMeanValue and getStdev. Missing the getStdev tests for the moment --- .../core/test/image/testImageMeanAndStdev.cpp | 425 ++++++++++++++++++ 1 file changed, 425 insertions(+) create mode 100644 modules/core/test/image/testImageMeanAndStdev.cpp diff --git a/modules/core/test/image/testImageMeanAndStdev.cpp b/modules/core/test/image/testImageMeanAndStdev.cpp new file mode 100644 index 0000000000..c785110b82 --- /dev/null +++ b/modules/core/test/image/testImageMeanAndStdev.cpp @@ -0,0 +1,425 @@ +/**************************************************************************** + * + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * + * Description: + * Test for vpImagePoint::getValue(). + * +*****************************************************************************/ +/*! + \example testImageMeanAndStdev.cpp + + \brief Test for vpImage::getMeanValue() and vpImage::getStdev(). +*/ + +#include +#include + +void printHelp(const std::string &progName) +{ + std::cout << "SYNOPSIS: " << std::endl; + std::cout << " " << progName << " [-v, --verbose] [-h, --help]" << std::endl; + std::cout << "DETAILS:" << std::endl; + std::cout << " -v, --verbose" << std::endl; + std::cout << " Activate verbose mode to have some logs in the console." << std::endl; + std::cout << std::endl; + std::cout << " -h, --help" << std::endl; + std::cout << " Display the help about the program." << std::endl; + std::cout << std::endl; +} + +int main(const int argc, const char *argv[]) +{ + bool opt_verbose = false; + for (int i = 1; i < argc; ++i) { + std::string argName(argv[i]); + if ((argName == "-v") || (argName == "--verbose")) { + opt_verbose = true; + } + else if ((argName == "-h") || (argName == "--help")) { + printHelp(std::string(argv[0])); + return EXIT_FAILURE; + } + } + + const unsigned int nbRows = 4, nbCols = 4; + vpImage I_uchar_ref(nbRows, nbCols); + vpImage I_rgba_ref(nbRows, nbCols); + vpImage I_rgbf_ref(nbRows, nbCols); + double sum_uchar_ref = 0.; + double sum_rgba_ref = 0.; + double sum_rgbf_ref = 0.; + unsigned int count_ref = 0; + for (unsigned int r = 0; r < nbRows; ++r) { + for (unsigned int c = 0; c < nbCols; ++c) { + unsigned int val = r * nbCols + c; + I_uchar_ref[r][c] = val; + I_rgba_ref[r][c].R = val; + I_rgba_ref[r][c].G = 2*val; + I_rgba_ref[r][c].B = 3*val; + I_rgbf_ref[r][c].R = I_rgba_ref[r][c].R; + I_rgbf_ref[r][c].G = I_rgba_ref[r][c].G; + I_rgbf_ref[r][c].B = I_rgba_ref[r][c].B; + sum_uchar_ref += static_cast(val); + double val_rgb = static_cast(I_rgba_ref[r][c].R) + static_cast(I_rgba_ref[r][c].G) + static_cast(I_rgba_ref[r][c].B); + sum_rgba_ref += val_rgb; + sum_rgbf_ref += val_rgb; + ++count_ref; + } + } + double mean_uchar_ref = sum_uchar_ref / static_cast(count_ref); + double mean_rgba_ref = sum_rgba_ref / static_cast(count_ref); + double mean_rgbf_ref = sum_rgbf_ref / static_cast(count_ref); + if (opt_verbose) { + std::cout << "----- Input data-----" << std::endl; + std::cout << "I_uchar_ref = \n" << I_uchar_ref << std::endl; + std::cout << "mean_uchar_ref(I_uchar_ref) = " << mean_uchar_ref << std::endl; + std::cout << "sum_uchar_ref(I_uchar_ref) = " << sum_uchar_ref << std::endl; + std::cout << std::endl; + std::cout << "I_rgba_ref = \n" << I_rgba_ref << std::endl; + std::cout << "mean_rgba_ref(I_uchar_ref) = " << mean_rgba_ref << std::endl; + std::cout << "sum_rgba_ref(I_uchar_ref) = " << sum_rgba_ref << std::endl; + std::cout << std::endl; + std::cout << "I_rgbf_ref = \n" << I_rgbf_ref << std::endl; + std::cout << "mean_rgbf_ref(I_uchar_ref) = " << mean_rgbf_ref << std::endl; + std::cout << "sum_rgbf_ref(I_uchar_ref) = " << sum_rgbf_ref << std::endl; + std::cout << std::endl; + } + + vpImage I_mask(nbRows, nbCols); + unsigned int count_true = 0; + double sum_uchar_true = 0.; + double sum_rgba_true = 0.; + double sum_rgbf_true = 0.; + for (unsigned int r = 0; r < nbRows; ++r) { + for (unsigned int c = 0; c < nbCols; ++c) { + bool isTrue = ((r + c) % 2) == 0; + I_mask[r][c] = isTrue; + if (isTrue) { + ++count_true; + sum_uchar_true += static_cast(I_uchar_ref[r][c]); + double val_rgba = static_cast(I_rgba_ref[r][c].R) + static_cast(I_rgba_ref[r][c].G) + static_cast(I_rgba_ref[r][c].B); + sum_rgba_true += val_rgba; + double val_rgbf = static_cast(I_rgbf_ref[r][c].R) + static_cast(I_rgbf_ref[r][c].G) + static_cast(I_rgbf_ref[r][c].B); + sum_rgbf_true += val_rgbf; + } + } + } + double mean_uchar_true = sum_uchar_true / static_cast(count_true); + double mean_rgba_true = sum_rgba_true / static_cast(count_true); + double mean_rgbf_true = sum_rgbf_true / static_cast(count_true); + if (opt_verbose) { + std::cout << "I_mask = \n"; + for (unsigned int r = 0; r < nbRows; ++r) { + for (unsigned int c = 0; c < nbCols; ++c) { + std::cout << (I_mask[r][c] ? "true" : "false") << " "; + } + std::cout << "\n"; + } + std::cout << std::endl; + std::cout << "nb_true(I_uchar_ref, I_mask) = " << count_true << std::endl; + std::cout << "sum_uchar_true(I_uchar_ref, I_mask) = " << sum_uchar_true << std::endl; + std::cout << "mean_uchar_true(I_uchar_ref, I_mask) = " << mean_uchar_true << std::endl; + std::cout << "sum_rgba_true(I_rgba_ref, I_mask) = " << sum_rgba_true << std::endl; + std::cout << "mean_rgba_true(I_rgba_ref, I_mask) = " << mean_rgba_true << std::endl; + std::cout << "sum_rgbf_true(I_rgbf_ref, I_mask) = " << sum_rgbf_true << std::endl; + std::cout << "mean_rgbf_true(I_rgbf_ref, I_mask) = " << mean_rgbf_true << std::endl; + std::cout << std::endl; + } + + bool areTestOK = true; + unsigned int nbFailedTests = 0; + std::vector failedTestsNames; + if (opt_verbose) { + std::cout << "----- BEGIN tests-----" << std::endl; + } + + // Tests on the sum + { + if (opt_verbose) { + std::cout << "Tests on the sum" << std::endl; + } + std::string nameTest("vpImage::getSum()"); + double sum = I_uchar_ref.getSum(); + bool success = vpMath::equal(sum, sum_uchar_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical sum = " << sum_uchar_ref << " | returned value = " << sum << std::endl; + } + } + + unsigned int nbValidPoints = 0; + nameTest = ("vpImage::getSum( const vpImage*, unsigned int& )"); + sum = I_uchar_ref.getSum(&I_mask, nbValidPoints); + success = vpMath::equal(sum, sum_uchar_true) && (nbValidPoints == count_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << count_true << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical sum = " << sum_uchar_true << " | returned value = " << sum << std::endl; + } + } + + nameTest = ("vpImage::getSum()"); + sum = I_rgba_ref.getSum(); + success = vpMath::equal(sum, sum_rgba_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical sum = " << sum_rgba_ref << " | returned value = " << sum << std::endl; + } + } + + nameTest = ("vpImage::getSum( const vpImage*, unsigned int& )"); + sum = I_rgba_ref.getSum(&I_mask, nbValidPoints); + success = vpMath::equal(sum, sum_rgba_true) && (nbValidPoints == count_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << count_true << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical sum = " << sum_rgba_true << " | returned value = " << sum << std::endl; + } + } + + nameTest = ("vpImage::getSum()"); + sum = I_rgbf_ref.getSum(); + success = vpMath::equal(sum, sum_rgbf_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical sum = " << sum_rgbf_ref << " | returned value = " << sum << std::endl; + } + } + + nameTest = ("vpImage::getSum( const vpImage*, unsigned int& )"); + sum = I_rgbf_ref.getSum(&I_mask, nbValidPoints); + success = vpMath::equal(sum, sum_rgbf_true) && (nbValidPoints == count_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << count_true << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical sum = " << sum_rgbf_true << " | returned value = " << sum << std::endl; + } + } + } + + // Tests on the mean + { + if (opt_verbose) { + std::cout << "Tests on the mean" << std::endl; + } + std::string nameTest("vpImage::getMeanValue()"); + double mean = I_uchar_ref.getMeanValue(); + bool success = vpMath::equal(mean, mean_uchar_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical mean = " << mean_uchar_ref << " | returned value = " << mean << std::endl; + } + } + + nameTest = "vpImage::getMeanValue(const vpImage*)"; + mean = I_uchar_ref.getMeanValue(&I_mask); + success = vpMath::equal(mean, mean_uchar_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical mean = " << mean_uchar_true << " | returned value = " << mean << std::endl; + } + } + + unsigned int nbValidPoints = 0; + nameTest = "vpImage::getMeanValue(const vpImage*, unsigned int &)"; + mean = I_uchar_ref.getMeanValue(&I_mask, nbValidPoints); + success = vpMath::equal(mean, mean_uchar_true) && (nbValidPoints == count_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << count_true << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical mean = " << mean_uchar_true << " | returned value = " << mean << std::endl; + } + } + + nameTest = "vpImage::getMeanValue()"; + mean = I_rgba_ref.getMeanValue(); + success = vpMath::equal(mean, mean_rgba_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical mean = " << mean_rgba_ref << " | returned value = " << mean << std::endl; + } + } + + nameTest = "vpImage::getMeanValue(const vpImage*)"; + mean = I_rgba_ref.getMeanValue(&I_mask); + success = vpMath::equal(mean, mean_rgba_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical mean = " << mean_rgba_true << " | returned value = " << mean << std::endl; + } + } + + nbValidPoints = 0; + nameTest = "vpImage::getMeanValue(const vpImage*, unsigned int &)"; + mean = I_rgba_ref.getMeanValue(&I_mask, nbValidPoints); + success = vpMath::equal(mean, mean_rgba_true) && (nbValidPoints == count_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << count_true << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical mean = " << mean_rgba_true << " | returned value = " << mean << std::endl; + } + } + + nameTest = "vpImage::getMeanValue()"; + mean = I_rgbf_ref.getMeanValue(); + success = vpMath::equal(mean, mean_rgbf_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical mean = " << mean_rgbf_ref << " | returned value = " << mean << std::endl; + } + } + + nameTest = "vpImage::getMeanValue(const vpImage*)"; + mean = I_rgbf_ref.getMeanValue(&I_mask); + success = vpMath::equal(mean, mean_rgbf_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical mean = " << mean_rgbf_true << " | returned value = " << mean << std::endl; + } + } + + nbValidPoints = 0; + nameTest = "vpImage::getMeanValue(const vpImage*, unsigned int &)"; + mean = I_rgbf_ref.getMeanValue(&I_mask, nbValidPoints); + success = vpMath::equal(mean, mean_rgbf_true) && (nbValidPoints == count_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << count_true << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical mean = " << mean_rgbf_true << " | returned value = " << mean << std::endl; + } + } + } + + if (areTestOK) { + if (opt_verbose) { + std::cout << "All tests succeeded" << std::endl; + } + return EXIT_SUCCESS; + } + else { + if (opt_verbose) { + std::cerr << nbFailedTests << " tests failed: " << std::endl; + for (unsigned int i = 0; i < nbFailedTests; ++i) { + std::cerr << " - " << failedTestsNames[i] << std::endl; + } + } + return EXIT_FAILURE; + } +} From 8f0c01c01b6f3e2d454e5be804c765e2599ddcda Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 10:47:45 +0100 Subject: [PATCH 110/164] Fix potential double free in vpMatrix and vpArray --- example/math/quadprog.cpp | 8 ---- example/math/quadprog_eq.cpp | 13 ------ modules/core/include/visp3/core/vpArray2D.h | 18 +++++++-- modules/core/src/math/matrix/vpMatrix.cpp | 8 +++- modules/core/test/math/testMatrix.cpp | 45 +++++++++++++++++++++ 5 files changed, 65 insertions(+), 27 deletions(-) diff --git a/example/math/quadprog.cpp b/example/math/quadprog.cpp index cb6af9ef59..6d89a741a2 100644 --- a/example/math/quadprog.cpp +++ b/example/math/quadprog.cpp @@ -105,10 +105,8 @@ int main(int argc, char **argv) r = randV(o) * 5; C = randM(p, n) * 5; - std::cout << "DEBUG 1 before solveBySVD()" << std::endl; // make sure Cx <= d has a solution within Ax = b vpColVector x = A.solveBySVD(b); - std::cout << "DEBUG 2 after solveBySVD()" << std::endl; d = C * x; for (int i = 0; i < p; ++i) d[i] += (5. * rand()) / RAND_MAX; @@ -116,8 +114,6 @@ int main(int argc, char **argv) // solver with warm start vpQuadProg qp_WS; - std::cout << "DEBUG 3 after vpQuadProg()" << std::endl; - // timing int total = 100; double t_WS(0), t_noWS(0); @@ -146,9 +142,7 @@ int main(int argc, char **argv) vpQuadProg qp; x = 0; double t = vpTime::measureTimeMs(); - std::cout << "DEBUG 4 before solveQP()" << std::endl; qp.solveQP(Q, r, A, b, C, d, x); - std::cout << "DEBUG 4 after solveQP()" << std::endl; t_noWS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY @@ -159,9 +153,7 @@ int main(int argc, char **argv) // with warm start x = 0; t = vpTime::measureTimeMs(); - std::cout << "DEBUG 5 before solveQP()" << std::endl; qp_WS.solveQP(Q, r, A, b, C, d, x); - std::cout << "DEBUG 5 after solveQP()" << std::endl; t_WS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY diff --git a/example/math/quadprog_eq.cpp b/example/math/quadprog_eq.cpp index 7c90d93579..72d9ef40b1 100644 --- a/example/math/quadprog_eq.cpp +++ b/example/math/quadprog_eq.cpp @@ -106,22 +106,17 @@ int main(int argc, char **argv) // make sure Cx <= d has a solution within Ax = b - std::cout << "DEBUG 1 before solveBySVD()" << std::endl; vpColVector x = A.solveBySVD(b); - std::cout << "DEBUG 1 after solveBySVD()" << std::endl; d = C * x; for (int i = 0; i < p; ++i) d[i] += (5. * rand()) / RAND_MAX; // solver with stored equality and warm start vpQuadProg qp_WS; - std::cout << "DEBUG 2 before setEqualityConstraint()" << std::endl; qp_WS.setEqualityConstraint(A, b); - std::cout << "DEBUG 2 after setEqualityConstraint()" << std::endl; vpQuadProg qp_ineq_WS; qp_ineq_WS.setEqualityConstraint(A, b); - std::cout << "DEBUG 3 after setEqualityConstraint()" << std::endl; // timing int total = 100; @@ -146,9 +141,7 @@ int main(int argc, char **argv) // without warm start x = 0; double t = vpTime::measureTimeMs(); - std::cout << "DEBUG 4 before solveQPe()" << std::endl; vpQuadProg::solveQPe(Q, r, A, b, x); - std::cout << "DEBUG 4 after solveQPe()" << std::endl; t_noWS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY @@ -159,9 +152,7 @@ int main(int argc, char **argv) // with pre-solved Ax = b x = 0; t = vpTime::measureTimeMs(); - std::cout << "DEBUG 5 before solveQPe()" << std::endl; qp_WS.solveQPe(Q, r, x); - std::cout << "DEBUG 5 after solveQPe()" << std::endl; t_WS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY @@ -174,9 +165,7 @@ int main(int argc, char **argv) x = 0; vpQuadProg qp; t = vpTime::measureTimeMs(); - std::cout << "DEBUG 6 before solveQP()" << std::endl; qp.solveQP(Q, r, A, b, C, d, x); - std::cout << "DEBUG 6 after solveQP()" << std::endl; t_ineq_noWS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY @@ -187,9 +176,7 @@ int main(int argc, char **argv) // with warm start + pre-solving x = 0; t = vpTime::measureTimeMs(); - std::cout << "DEBUG 7 before solveQPi()" << std::endl; qp_ineq_WS.solveQPi(Q, r, C, d, x, true); - std::cout << "DEBUG 7 after solveQPi()" << std::endl; t_ineq_WS += vpTime::measureTimeMs() - t; #ifdef VISP_HAVE_DISPLAY diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index 36b655d299..1644e15f37 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -320,10 +320,13 @@ template class vpArray2D // Reallocation of this->data array this->dsize = nrows * ncols; - Type *tmp_data = (Type *)realloc(this->data, this->dsize * sizeof(Type)); + Type *tmp_data = reinterpret_cast(realloc(this->data, this->dsize * sizeof(Type))); if (tmp_data) { this->data = tmp_data; } + else { + this->data = nullptr; + } if ((nullptr == this->data) && (0 != this->dsize)) { if (copyTmp != nullptr) { @@ -332,10 +335,13 @@ template class vpArray2D throw(vpException(vpException::memoryAllocationError, "Memory allocation error when allocating 2D array data")); } - Type **tmp_rowPtrs = (Type **)realloc(this->rowPtrs, nrows * sizeof(Type *)); + Type **tmp_rowPtrs = reinterpret_cast(realloc(this->rowPtrs, nrows * sizeof(Type *))); if (tmp_rowPtrs) { this->rowPtrs = tmp_rowPtrs; } + else { + this->rowPtrs = nullptr; + } if ((nullptr == this->rowPtrs) && (0 != this->dsize)) { if (copyTmp != nullptr) { delete[] copyTmp; @@ -472,8 +478,12 @@ template class vpArray2D vpArray2D &operator=(vpArray2D &&other) noexcept { if (this != &other) { - free(data); - free(rowPtrs); + if (data) { + free(data); + } + if (rowPtrs) { + free(rowPtrs); + } rowNum = other.rowNum; colNum = other.colNum; diff --git a/modules/core/src/math/matrix/vpMatrix.cpp b/modules/core/src/math/matrix/vpMatrix.cpp index 87b7cfbca6..4463b6eda9 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -681,8 +681,12 @@ vpMatrix &vpMatrix::operator=(const vpMatrix &A) vpMatrix &vpMatrix::operator=(vpMatrix &&other) { if (this != &other) { - free(data); - free(rowPtrs); + if (data) { + free(data); + } + if (rowPtrs) { + free(rowPtrs); + } rowNum = other.rowNum; colNum = other.colNum; diff --git a/modules/core/test/math/testMatrix.cpp b/modules/core/test/math/testMatrix.cpp index 65f6f0b6c4..b894a63a42 100644 --- a/modules/core/test/math/testMatrix.cpp +++ b/modules/core/test/math/testMatrix.cpp @@ -53,6 +53,29 @@ namespace { +bool test_memory(unsigned int nrows, unsigned int ncols, const vpMatrix &M, const std::string &matrix_name, bool pointer_is_null) +{ + if (pointer_is_null) { + if (M.data) { + std::cerr << "Wrong data pointer (" << M.data << ") in matrix " << matrix_name << ": should be null" << std::endl; + } + } + else { + if (!M.data) { + std::cerr << "Wrong data pointer (" << M.data << ") in matrix " << matrix_name << ": should be non null" << std::endl; + return false; + } + } + + if (M.getRows() != nrows || M.getCols() != ncols) { + std::cerr << "Wrong matrix " << matrix_name << "(" << nrows << ", " << ncols << " size: " + << M.getRows() << " x " << M.getCols() << std::endl; + return false; + } + std::cout << "Test matrix " << matrix_name << " succeed" << std::endl; + return true; +} + bool test(const std::string &s, const vpMatrix &M, const std::vector &bench) { static unsigned int cpt = 0; @@ -122,6 +145,28 @@ int main(int argc, char *argv[]) } } + { + unsigned int nrows = 2, ncols = 3; + vpMatrix A(nrows, ncols); + if (test_memory(nrows, ncols, A, "A", false) == false) { + return EXIT_FAILURE; + } + vpMatrix B, C; + if (test_memory(0, 0, B, "B", true) == false) { + return EXIT_FAILURE; + } + if (test_memory(0, 0, C, "C", true)== false) { + return EXIT_FAILURE; + } + B = A; + if (test_memory(nrows, ncols, B, "B", false)== false) { + return EXIT_FAILURE; + } + B = C; + if (test_memory(0, 0, C, "C", true)== false) { + return EXIT_FAILURE; + } + } { const double val = 10.0; vpMatrix M, M2(5, 5, val); From aee3b66e2c1554b117c4d53ec47aa7987e122f35 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Wed, 13 Mar 2024 10:54:58 +0100 Subject: [PATCH 111/164] [FIX] Fix stdev for vpRGBa and vpRGBf + [TEST] Finished tests for stdev --- modules/core/include/visp3/core/vpImage.h | 8 +- .../core/test/image/testImageMeanAndStdev.cpp | 246 +++++++++++++++++- 2 files changed, 246 insertions(+), 8 deletions(-) diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 3ffcbdc9b1..7962847d84 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -1082,7 +1082,7 @@ template <> inline double vpImage::getStdev(const double &mean) const res += (val - mean) * (val - mean); } res /= static_cast(size); - return res; + return std::sqrt(res); } /* @@ -1119,7 +1119,7 @@ template <> inline double vpImage::getStdev(const double &mean, const un } } sum /= static_cast(nbValidPoints); - return sum; + return std::sqrt(sum); } /* @@ -1151,7 +1151,7 @@ template <> inline double vpImage::getStdev(const double &mean) const res += (val - mean) * (val - mean); } res /= static_cast(size); - return res; + return std::sqrt(res); } /* @@ -1191,7 +1191,7 @@ template <> inline double vpImage::getStdev(const double &mean, const un } } sum /= static_cast(nbValidPoints); - return sum; + return std::sqrt(sum); } /*! diff --git a/modules/core/test/image/testImageMeanAndStdev.cpp b/modules/core/test/image/testImageMeanAndStdev.cpp index c785110b82..fde91f3eaa 100644 --- a/modules/core/test/image/testImageMeanAndStdev.cpp +++ b/modules/core/test/image/testImageMeanAndStdev.cpp @@ -76,6 +76,7 @@ int main(const int argc, const char *argv[]) double sum_rgba_ref = 0.; double sum_rgbf_ref = 0.; unsigned int count_ref = 0; + // Initialization of the images for (unsigned int r = 0; r < nbRows; ++r) { for (unsigned int c = 0; c < nbCols; ++c) { unsigned int val = r * nbCols + c; @@ -93,22 +94,42 @@ int main(const int argc, const char *argv[]) ++count_ref; } } + + // Computation of the means double mean_uchar_ref = sum_uchar_ref / static_cast(count_ref); double mean_rgba_ref = sum_rgba_ref / static_cast(count_ref); double mean_rgbf_ref = sum_rgbf_ref / static_cast(count_ref); + + // Computation of the standard deviations + double stdev_uchar_ref = 0.; + double stdev_rgba_ref = 0.; + double stdev_rgbf_ref = 0.; + for (unsigned int r = 0; r < nbRows; ++r) { + for (unsigned int c = 0; c < nbCols; ++c) { + stdev_uchar_ref += std::pow(static_cast(I_uchar_ref[r][c]) - mean_uchar_ref, 2); + stdev_rgba_ref += std::pow(static_cast(I_rgba_ref[r][c].R) + static_cast(I_rgba_ref[r][c].G) + static_cast(I_rgba_ref[r][c].B) - mean_rgba_ref, 2); + stdev_rgbf_ref += std::pow(static_cast(I_rgbf_ref[r][c].R) + static_cast(I_rgbf_ref[r][c].G) + static_cast(I_rgbf_ref[r][c].B) - mean_rgbf_ref, 2); + } + } + stdev_uchar_ref = std::sqrt((1./static_cast(nbRows * nbCols))* stdev_uchar_ref); + stdev_rgba_ref = std::sqrt((1./static_cast(nbRows * nbCols))* stdev_rgba_ref); + stdev_rgbf_ref = std::sqrt((1./static_cast(nbRows * nbCols))* stdev_rgbf_ref); if (opt_verbose) { std::cout << "----- Input data-----" << std::endl; std::cout << "I_uchar_ref = \n" << I_uchar_ref << std::endl; - std::cout << "mean_uchar_ref(I_uchar_ref) = " << mean_uchar_ref << std::endl; std::cout << "sum_uchar_ref(I_uchar_ref) = " << sum_uchar_ref << std::endl; + std::cout << "mean_uchar_ref(I_uchar_ref) = " << mean_uchar_ref << std::endl; + std::cout << "stdev_uchar_ref(I_uchar_ref) = " << stdev_uchar_ref << std::endl; std::cout << std::endl; std::cout << "I_rgba_ref = \n" << I_rgba_ref << std::endl; - std::cout << "mean_rgba_ref(I_uchar_ref) = " << mean_rgba_ref << std::endl; std::cout << "sum_rgba_ref(I_uchar_ref) = " << sum_rgba_ref << std::endl; + std::cout << "mean_rgba_ref(I_rgba_ref) = " << mean_rgba_ref << std::endl; + std::cout << "stdev_rgba_ref(I_rgba_ref) = " << stdev_rgba_ref << std::endl; std::cout << std::endl; std::cout << "I_rgbf_ref = \n" << I_rgbf_ref << std::endl; - std::cout << "mean_rgbf_ref(I_uchar_ref) = " << mean_rgbf_ref << std::endl; - std::cout << "sum_rgbf_ref(I_uchar_ref) = " << sum_rgbf_ref << std::endl; + std::cout << "sum_rgbf_ref(I_rgbf_ref) = " << sum_rgbf_ref << std::endl; + std::cout << "mean_rgbf_ref(I_rgbf_ref) = " << mean_rgbf_ref << std::endl; + std::cout << "stdev_rgbf_ref(I_rgbf_ref) = " << stdev_rgbf_ref << std::endl; std::cout << std::endl; } @@ -131,9 +152,28 @@ int main(const int argc, const char *argv[]) } } } + // Computation of the means when a boolean mask is used double mean_uchar_true = sum_uchar_true / static_cast(count_true); double mean_rgba_true = sum_rgba_true / static_cast(count_true); double mean_rgbf_true = sum_rgbf_true / static_cast(count_true); + // Computation of the standard deviations when a boolean mask is used + double stdev_uchar_true = 0.; + double stdev_rgba_true = 0.; + double stdev_rgbf_true = 0.; + for (unsigned int r = 0; r < nbRows; ++r) { + for (unsigned int c = 0; c < nbCols; ++c) { + if (I_mask[r][c]) { + stdev_uchar_true += (static_cast(I_uchar_ref[r][c]) - mean_uchar_true) * (static_cast(I_uchar_ref[r][c]) - mean_uchar_true); + double val_rgba = static_cast(I_rgba_ref[r][c].R) + static_cast(I_rgba_ref[r][c].G) + static_cast(I_rgba_ref[r][c].B); + stdev_rgba_true += (val_rgba - mean_rgba_true) * (val_rgba - mean_rgba_true); + double val_rgbf = static_cast(I_rgbf_ref[r][c].R) + static_cast(I_rgbf_ref[r][c].G) + static_cast(I_rgbf_ref[r][c].B); + stdev_rgbf_true += (val_rgbf - mean_rgbf_true) * (val_rgbf - mean_rgbf_true); + } + } + } + stdev_uchar_true = std::sqrt((1./static_cast(count_true)) * stdev_uchar_true); + stdev_rgba_true = std::sqrt((1./static_cast(count_true)) * stdev_rgba_true); + stdev_rgbf_true = std::sqrt((1./static_cast(count_true)) * stdev_rgbf_true); if (opt_verbose) { std::cout << "I_mask = \n"; for (unsigned int r = 0; r < nbRows; ++r) { @@ -146,10 +186,13 @@ int main(const int argc, const char *argv[]) std::cout << "nb_true(I_uchar_ref, I_mask) = " << count_true << std::endl; std::cout << "sum_uchar_true(I_uchar_ref, I_mask) = " << sum_uchar_true << std::endl; std::cout << "mean_uchar_true(I_uchar_ref, I_mask) = " << mean_uchar_true << std::endl; + std::cout << "stdev_uchar_true(I_uchar_ref, I_mask) = " << stdev_uchar_true << std::endl; std::cout << "sum_rgba_true(I_rgba_ref, I_mask) = " << sum_rgba_true << std::endl; std::cout << "mean_rgba_true(I_rgba_ref, I_mask) = " << mean_rgba_true << std::endl; + std::cout << "stdev_rgba_true(I_rgba_ref, I_mask) = " << stdev_rgba_true << std::endl; std::cout << "sum_rgbf_true(I_rgbf_ref, I_mask) = " << sum_rgbf_true << std::endl; std::cout << "mean_rgbf_true(I_rgbf_ref, I_mask) = " << mean_rgbf_true << std::endl; + std::cout << "stdev_rgbf_true(I_rgbf_ref, I_mask) = " << stdev_rgbf_true << std::endl; std::cout << std::endl; } @@ -407,6 +450,201 @@ int main(const int argc, const char *argv[]) } } + // Tests on the stdev + { + if (opt_verbose) { + std::cout << "Tests on the stdev" << std::endl; + } + std::string nameTest("vpImage::getStdev()"); + double stdev = I_uchar_ref.getStdev(); + bool success = vpMath::equal(stdev, stdev_uchar_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_uchar_ref << " | returned value = " << stdev << std::endl; + } + } + + nameTest = ("vpImage::getStdev(const vpImage *)"); + stdev = I_uchar_ref.getStdev(&I_mask); + success = vpMath::equal(stdev, stdev_uchar_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_uchar_true << " | returned value = " << stdev << std::endl; + } + } + + nameTest = ("vpImage::getStdev(const double &)"); + double mean = I_uchar_ref.getMeanValue(); + stdev = I_uchar_ref.getStdev(mean); + success = vpMath::equal(stdev, stdev_uchar_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_uchar_ref << " | returned value = " << stdev << std::endl; + } + } + + nameTest = ("vpImage::getStdev(const double &, const unsigned int&, const vpImage*)"); + unsigned int nbValidPoints = 0; + mean = I_uchar_ref.getMeanValue(&I_mask, nbValidPoints); + stdev = I_uchar_ref.getStdev(mean, nbValidPoints, &I_mask); + success = vpMath::equal(stdev, stdev_uchar_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_uchar_true << " | returned value = " << stdev << std::endl; + } + } + + nameTest = "vpImage::getStdev()"; + stdev = I_rgba_ref.getStdev(); + success = vpMath::equal(stdev, stdev_rgba_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgba_ref << " | returned value = " << stdev << std::endl; + } + } + + nameTest = ("vpImage::getStdev(const vpImage *)"); + stdev = I_rgba_ref.getStdev(&I_mask); + success = vpMath::equal(stdev, stdev_rgba_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgba_true << " | returned value = " << stdev << std::endl; + } + } + + nameTest = ("vpImage::getStdev(const double &)"); + mean = I_rgba_ref.getMeanValue(); + stdev = I_rgba_ref.getStdev(mean); + success = vpMath::equal(stdev, stdev_rgba_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgba_ref << " | returned value = " << stdev << std::endl; + } + } + + nameTest = ("vpImage::getStdev(const double &, const unsigned int&, const vpImage*)"); + nbValidPoints = 0; + mean = I_rgba_ref.getMeanValue(&I_mask, nbValidPoints); + stdev = I_rgba_ref.getStdev(mean, nbValidPoints, &I_mask); + success = vpMath::equal(stdev, stdev_rgba_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgba_true << " | returned value = " << stdev << std::endl; + } + } + + nameTest = "vpImage::getStdev()"; + stdev = I_rgbf_ref.getStdev(); + success = vpMath::equal(stdev, stdev_rgbf_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgbf_ref << " | returned value = " << stdev << std::endl; + } + } + + nameTest = ("vpImage::getStdev(const vpImage *)"); + stdev = I_rgbf_ref.getStdev(&I_mask); + success = vpMath::equal(stdev, stdev_rgbf_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgbf_true << " | returned value = " << stdev << std::endl; + } + } + + nameTest = ("vpImage::getStdev(const double &)"); + mean = I_rgbf_ref.getMeanValue(); + stdev = I_rgbf_ref.getStdev(mean); + success = vpMath::equal(stdev, stdev_rgbf_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgbf_ref << " | returned value = " << stdev << std::endl; + } + } + + nameTest = ("vpImage::getStdev(const double &, const unsigned int&, const vpImage*)"); + nbValidPoints = 0; + mean = I_rgbf_ref.getMeanValue(&I_mask, nbValidPoints); + stdev = I_rgbf_ref.getStdev(mean, nbValidPoints, &I_mask); + success = vpMath::equal(stdev, stdev_rgbf_true); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgbf_true << " | returned value = " << stdev << std::endl; + } + } + } + if (areTestOK) { if (opt_verbose) { std::cout << "All tests succeeded" << std::endl; From a1f1fea2cca82685f338b5884c70ab8aac61f4b4 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 14:24:11 +0100 Subject: [PATCH 112/164] =?UTF-8?q?Fix=20visp=5Fpython=5Fbindings=20build?= =?UTF-8?q?=20error=20in=20vpImageTools.h=20around=20lerp()=20usage=20C:\v?= =?UTF-8?q?isp-ws\visp\modules\core\include\visp3\core\vpImageTools.h(1589?= =?UTF-8?q?,31):=20error=20C2666:=20'vpImageTools=20::lerp'=C2=A0:=20les?= =?UTF-8?q?=20fonctions=20surcharg=C3=A9es=20ont=20des=20conversions=20sim?= =?UTF-8?q?ilaires.=20[C:\visp-ws\visp-build-bindings-vc17\modules\python\?= =?UTF-8?q?bindings\=5Fvisp.vcxproj]?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../core/include/visp3/core/vpImageTools.h | 34 +++++++++---------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/modules/core/include/visp3/core/vpImageTools.h b/modules/core/include/visp3/core/vpImageTools.h index 6c8fa38269..367d7b7d6a 100644 --- a/modules/core/include/visp3/core/vpImageTools.h +++ b/modules/core/include/visp3/core/vpImageTools.h @@ -1132,7 +1132,7 @@ void vpImageTools::resize(const vpImage &I, vpImage &Ires, const vpI } } } - } +} #if defined(VISP_HAVE_SIMDLIB) template <> @@ -1510,24 +1510,24 @@ void vpImageTools::warpLinear(const vpImage &src, const vpMatrix &T, vpIma const float s = xi_ - x_; if (y_ < static_cast(src.getHeight()) - 1 && x_ < static_cast(src.getWidth()) - 1) { - const Type val00 = src[y_][x_]; - const Type val01 = src[y_][x_ + 1]; - const Type val10 = src[y_ + 1][x_]; - const Type val11 = src[y_ + 1][x_ + 1]; + const float val00 = static_cast(src[y_][x_]); + const float val01 = static_cast(src[y_][x_ + 1]); + const float val10 = static_cast(src[y_ + 1][x_]); + const float val11 = static_cast(src[y_ + 1][x_ + 1]); const float col0 = lerp(val00, val01, s); const float col1 = lerp(val10, val11, s); const float interp = lerp(col0, col1, t); dst[i][j] = vpMath::saturate(interp); } else if (y_ < static_cast(src.getHeight()) - 1) { - const Type val00 = src[y_][x_]; - const Type val10 = src[y_ + 1][x_]; + const float val00 = static_cast(src[y_][x_]); + const float val10 = static_cast(src[y_ + 1][x_]); const float interp = lerp(val00, val10, t); dst[i][j] = vpMath::saturate(interp); } else if (x_ < static_cast(src.getWidth()) - 1) { - const Type val00 = src[y_][x_]; - const Type val01 = src[y_][x_ + 1]; + const float val00 = static_cast(src[y_][x_]); + const float val01 = static_cast(src[y_][x_ + 1]); const float interp = lerp(val00, val01, s); dst[i][j] = vpMath::saturate(interp); } @@ -1582,24 +1582,24 @@ void vpImageTools::warpLinear(const vpImage &src, const vpMatrix &T, vpIma double t = y - y_lower; if (y_lower < static_cast(src.getHeight()) - 1 && x_lower < static_cast(src.getWidth()) - 1) { - const Type val00 = src[y_lower][x_lower]; - const Type val01 = src[y_lower][x_lower + 1]; - const Type val10 = src[y_lower + 1][x_lower]; - const Type val11 = src[y_lower + 1][x_lower + 1]; + const double val00 = static_cast(src[y_lower][x_lower]); + const double val01 = static_cast(src[y_lower][x_lower + 1]); + const double val10 = static_cast(src[y_lower + 1][x_lower]); + const double val11 = static_cast(src[y_lower + 1][x_lower + 1]); const double col0 = lerp(val00, val01, s); const double col1 = lerp(val10, val11, s); const double interp = lerp(col0, col1, t); dst[i][j] = vpMath::saturate(interp); } else if (y_lower < static_cast(src.getHeight()) - 1) { - const Type val00 = src[y_lower][x_lower]; - const Type val10 = src[y_lower + 1][x_lower]; + const double val00 = static_cast(src[y_lower][x_lower]); + const double val10 = static_cast(src[y_lower + 1][x_lower]); const double interp = lerp(val00, val10, t); dst[i][j] = vpMath::saturate(interp); } else if (x_lower < static_cast(src.getWidth()) - 1) { - const Type val00 = src[y_lower][x_lower]; - const Type val01 = src[y_lower][x_lower + 1]; + const double val00 = static_cast(src[y_lower][x_lower]); + const double val01 = static_cast(src[y_lower][x_lower + 1]); const double interp = lerp(val00, val01, s); dst[i][j] = vpMath::saturate(interp); } From 6be65b45390c442797d5f5508a6598b14390d091 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 14:57:48 +0100 Subject: [PATCH 113/164] Update instructions for python bindings on windows with conda --- .../tutorial-install-python-bindings.dox | 54 +++++++------------ 1 file changed, 20 insertions(+), 34 deletions(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 2dca74e165..62607fdeb3 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -397,39 +397,26 @@ We strongly recommend using Conda to build ViSP Python bindings. Below are instr (base) $ conda activate visp-conda-ws (visp-conda-ws) $ -- Install pybind11 using conda (this will install Python as it is a dependency of pybind11): - - (visp-conda-ws) $ conda install pybind11 - - Proceed ([y]/n)? y - - You can also specify the Python version if desired: - - (visp-conda-ws) $ conda install pybind11 python=3.10 - -- At this stage, you can also install the other ViSP dependencies using conda, depending on the features you wish to compile. +- Install `pybind11` and all the other ViSP dependencies you wish to enable using conda. - **A. On macOS**: - You will need to install at least the X11 libraries: - - (visp-conda-ws) $ conda install xorg-libx11 - - However, we recommend this minimal set of dependencies to get the main features of ViSP available: - - (visp-conda-ws) $ conda install xorg-libx11 eigen libopencv libjpeg-turbo libpng + (visp-conda-ws) $ conda install cmake xorg-libx11 xorg-libxfixes libxml2 libdc1394 >=2.2.6 librealsense libopencv eigen libjpeg-turbo libpng libopenblas llvm-openmp pybind11 - **B. On Ubuntu or other linux-like**: We recommend this minimal set of dependencies to get the main features of ViSP available: - (visp-conda-ws) $ conda install eigen libopencv libjpeg-turbo libpng + (visp-conda-ws) $ conda install cmake xorg-libx11 xorg-libxfixes libxml2 libdc1394 >=2.2.6 librealsense libgomp libopencv eigen libjpeg-turbo libpng mkl-devel pybind11 - **C. On Windows**: We recommend this minimal set of dependencies to get the main features of ViSP available: - (visp-conda-ws) C:\Users\User> conda install eigen libopencv libjpeg-turbo libpng + (visp-conda-ws) C:\Users\User> conda install cmake llvm-openmp openmp libopencv eigen libjpeg-turbo libpng mkl-devel pybind11 + +\note In the previous installation commands you can also specify the Python version if desired adding +for example `python=3.10` to the previous command lines. - Create a ViSP workspace to host source code and the build material @@ -481,20 +468,7 @@ We strongly recommend using Conda to build ViSP Python bindings. Below are instr (visp-conda-ws) C:\visp-ws> mkdir visp-build-bindings (visp-conda-ws) C:\visp-ws> cd visp-build-bindings - (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake -G "Visual Studio 17 2022" -A "x64" ../visp -DCMAKE_PREFIX_PATH=%CONDA_PREFIX% -DCMAKE_INSTALL_PREFIX=%CONDA_PREFIX% -DBUILD_PYTHON_BINDINGS=OFF -DVISP_LIB_INSTALL_PATH=lib -DVISP_BIN_INSTALL_PATH=bin -DVISP_CONFIG_INSTALL_PATH=cmake - (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake --build . --config Release --target install --parallel 8 - - At this point, ViSP DLL should be installed in `%CONDA_PREFIX%/bin`. This can be checked by: - - (visp-conda-ws) C:\visp-ws\visp-build-bindings> dir %CONDA_PREFIX%\bin - ... libvisp_ar361.dll - ... libvisp_blob361.dll - ... libvisp_core361.dll - ... - - Then configure ViSP again to enable Python bindings: - - (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake -G "Visual Studio 17 2022" -A "x64" ../visp -DCMAKE_PREFIX_PATH=%CONDA_PREFIX% -DCMAKE_INSTALL_PREFIX=%CONDA_PREFIX% -DBUILD_PYTHON_BINDINGS=ON + (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake -G "Visual Studio 17 2022" -A "x64" ../visp -DCMAKE_PREFIX_PATH=%CONDA_PREFIX% -DCMAKE_INSTALL_PREFIX=%CONDA_PREFIX%\Library -DVISP_LIB_INSTALL_PATH="lib" -DVISP_BIN_INSTALL_PATH="bin" -DVISP_CONFIG_INSTALL_PATH="cmake" - At this point, in the build folder there is the `ViSP-third-party.txt` file in which you should see something similar @@ -534,6 +508,18 @@ We strongly recommend using Conda to build ViSP Python bindings. Below are instr - **C. On Windows**: + (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake --build . --config Release --target install --parallel 8 + + At this point, ViSP DLL should be installed in `%CONDA_PREFIX%/Library/bin`. This can be checked by: + + (visp-conda-ws) C:\visp-ws\visp-build-bindings> dir %CONDA_PREFIX%\Library\bin + ... libvisp_ar361.dll + ... libvisp_blob361.dll + ... libvisp_core361.dll + ... + + Now you cab build the bindings + (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake --build . --config Release --target visp_python_bindings --parallel 8 - Test the Python bindings From 4184b8059e16db9210e41fbeca57e8e5ffe76c32 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 15:04:29 +0100 Subject: [PATCH 114/164] Fix typo --- doc/tutorial/python/tutorial-install-python-bindings.dox | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 62607fdeb3..938058d273 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -358,7 +358,7 @@ We strongly recommend using Conda to build ViSP Python bindings. Below are instr [no] >>> yes - **C. On Windows**, you may rather download and execute - https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-Winwdos-x86_64.exe + https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-Windows-x86_64.exe Select default options and accept licence in the wizard. From 15f6f308d1f4f2325ecac8ddc639ca93255f06a8 Mon Sep 17 00:00:00 2001 From: rlagneau Date: Wed, 13 Mar 2024 15:53:10 +0100 Subject: [PATCH 115/164] [TEST] Tested nullptr cases too --- .../core/test/image/testImageMeanAndStdev.cpp | 243 ++++++++++++++++++ 1 file changed, 243 insertions(+) diff --git a/modules/core/test/image/testImageMeanAndStdev.cpp b/modules/core/test/image/testImageMeanAndStdev.cpp index fde91f3eaa..16176290f7 100644 --- a/modules/core/test/image/testImageMeanAndStdev.cpp +++ b/modules/core/test/image/testImageMeanAndStdev.cpp @@ -240,6 +240,22 @@ int main(const int argc, const char *argv[]) } } + nameTest = ("vpImage::getSum( const vpImage* = nullptr, unsigned int& )"); + sum = I_uchar_ref.getSum(nullptr, nbValidPoints); + success = vpMath::equal(sum, sum_uchar_ref) && (nbValidPoints == (nbCols * nbRows)); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << nbCols * nbRows << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical sum = " << sum_uchar_ref << " | returned value = " << sum << std::endl; + } + } + nameTest = ("vpImage::getSum()"); sum = I_rgba_ref.getSum(); success = vpMath::equal(sum, sum_rgba_ref); @@ -271,6 +287,22 @@ int main(const int argc, const char *argv[]) } } + nameTest = ("vpImage::getSum( const vpImage* = nullptr, unsigned int& )"); + sum = I_rgba_ref.getSum(nullptr, nbValidPoints); + success = vpMath::equal(sum, sum_rgba_ref) && (nbValidPoints == (nbCols * nbRows)); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << nbCols * nbRows << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical sum = " << sum_rgba_ref << " | returned value = " << sum << std::endl; + } + } + nameTest = ("vpImage::getSum()"); sum = I_rgbf_ref.getSum(); success = vpMath::equal(sum, sum_rgbf_ref); @@ -301,6 +333,22 @@ int main(const int argc, const char *argv[]) std::cout << "Theoretical sum = " << sum_rgbf_true << " | returned value = " << sum << std::endl; } } + + nameTest = ("vpImage::getSum( const vpImage* = nullptr, unsigned int& )"); + sum = I_rgbf_ref.getSum(nullptr, nbValidPoints); + success = vpMath::equal(sum, sum_rgbf_ref) && (nbValidPoints == (nbCols * nbRows)); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << nbCols * nbRows << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical sum = " << sum_rgbf_ref << " | returned value = " << sum << std::endl; + } + } } // Tests on the mean @@ -338,6 +386,21 @@ int main(const int argc, const char *argv[]) } } + nameTest = "vpImage::getMeanValue(const vpImage* = nullptr)"; + mean = I_uchar_ref.getMeanValue(nullptr); + success = vpMath::equal(mean, mean_uchar_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical mean = " << mean_uchar_ref << " | returned value = " << mean << std::endl; + } + } + unsigned int nbValidPoints = 0; nameTest = "vpImage::getMeanValue(const vpImage*, unsigned int &)"; mean = I_uchar_ref.getMeanValue(&I_mask, nbValidPoints); @@ -355,6 +418,23 @@ int main(const int argc, const char *argv[]) } } + nbValidPoints = 0; + nameTest = "vpImage::getMeanValue(const vpImage* = nullptr, unsigned int &)"; + mean = I_uchar_ref.getMeanValue(nullptr, nbValidPoints); + success = vpMath::equal(mean, mean_uchar_ref) && (nbValidPoints == (nbCols * nbRows)); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << nbCols * nbRows << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical mean = " << mean_uchar_ref << " | returned value = " << mean << std::endl; + } + } + nameTest = "vpImage::getMeanValue()"; mean = I_rgba_ref.getMeanValue(); success = vpMath::equal(mean, mean_rgba_ref); @@ -385,6 +465,21 @@ int main(const int argc, const char *argv[]) } } + nameTest = "vpImage::getMeanValue(const vpImage* = nullptr)"; + mean = I_rgba_ref.getMeanValue(nullptr); + success = vpMath::equal(mean, mean_rgba_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical mean = " << mean_rgba_ref << " | returned value = " << mean << std::endl; + } + } + nbValidPoints = 0; nameTest = "vpImage::getMeanValue(const vpImage*, unsigned int &)"; mean = I_rgba_ref.getMeanValue(&I_mask, nbValidPoints); @@ -402,6 +497,23 @@ int main(const int argc, const char *argv[]) } } + nbValidPoints = 0; + nameTest = "vpImage::getMeanValue(const vpImage* = nullptr, unsigned int &)"; + mean = I_rgba_ref.getMeanValue(nullptr, nbValidPoints); + success = vpMath::equal(mean, mean_rgba_ref) && (nbValidPoints == (nbRows * nbCols)); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << nbRows * nbCols << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical mean = " << mean_rgba_ref << " | returned value = " << mean << std::endl; + } + } + nameTest = "vpImage::getMeanValue()"; mean = I_rgbf_ref.getMeanValue(); success = vpMath::equal(mean, mean_rgbf_ref); @@ -432,6 +544,21 @@ int main(const int argc, const char *argv[]) } } + nameTest = "vpImage::getMeanValue(const vpImage* = nullptr)"; + mean = I_rgbf_ref.getMeanValue(nullptr); + success = vpMath::equal(mean, mean_rgbf_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical mean = " << mean_rgbf_ref << " | returned value = " << mean << std::endl; + } + } + nbValidPoints = 0; nameTest = "vpImage::getMeanValue(const vpImage*, unsigned int &)"; mean = I_rgbf_ref.getMeanValue(&I_mask, nbValidPoints); @@ -448,6 +575,23 @@ int main(const int argc, const char *argv[]) std::cout << "Theoretical mean = " << mean_rgbf_true << " | returned value = " << mean << std::endl; } } + + nbValidPoints = 0; + nameTest = "vpImage::getMeanValue(const vpImage* = nullptr, unsigned int &)"; + mean = I_rgbf_ref.getMeanValue(nullptr, nbValidPoints); + success = vpMath::equal(mean, mean_rgbf_ref) && (nbValidPoints == (nbRows * nbCols)); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << nbRows * nbCols << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical mean = " << mean_rgbf_ref << " | returned value = " << mean << std::endl; + } + } } // Tests on the stdev @@ -485,6 +629,21 @@ int main(const int argc, const char *argv[]) } } + nameTest = ("vpImage::getStdev(const vpImage * = nullptr)"); + stdev = I_uchar_ref.getStdev(nullptr); + success = vpMath::equal(stdev, stdev_uchar_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_uchar_ref << " | returned value = " << stdev << std::endl; + } + } + nameTest = ("vpImage::getStdev(const double &)"); double mean = I_uchar_ref.getMeanValue(); stdev = I_uchar_ref.getStdev(mean); @@ -518,6 +677,24 @@ int main(const int argc, const char *argv[]) } } + nameTest = ("vpImage::getStdev(const double &, const unsigned int&, const vpImage* = nullptr)"); + nbValidPoints = 0; + mean = I_uchar_ref.getMeanValue(nullptr, nbValidPoints); + stdev = I_uchar_ref.getStdev(mean, nbValidPoints, nullptr); + success = vpMath::equal(stdev, stdev_uchar_ref) && (nbValidPoints == (nbRows * nbCols)); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << nbRows * nbCols << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical stdev = " << stdev_uchar_ref << " | returned value = " << stdev << std::endl; + } + } + nameTest = "vpImage::getStdev()"; stdev = I_rgba_ref.getStdev(); success = vpMath::equal(stdev, stdev_rgba_ref); @@ -548,6 +725,21 @@ int main(const int argc, const char *argv[]) } } + nameTest = ("vpImage::getStdev(const vpImage * = nullptr)"); + stdev = I_rgba_ref.getStdev(nullptr); + success = vpMath::equal(stdev, stdev_rgba_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgba_ref << " | returned value = " << stdev << std::endl; + } + } + nameTest = ("vpImage::getStdev(const double &)"); mean = I_rgba_ref.getMeanValue(); stdev = I_rgba_ref.getStdev(mean); @@ -581,6 +773,24 @@ int main(const int argc, const char *argv[]) } } + nameTest = ("vpImage::getStdev(const double &, const unsigned int&, const vpImage* = nullptr)"); + nbValidPoints = 0; + mean = I_rgba_ref.getMeanValue(nullptr, nbValidPoints); + stdev = I_rgba_ref.getStdev(mean, nbValidPoints, nullptr); + success = vpMath::equal(stdev, stdev_rgba_ref) && (nbValidPoints == (nbRows * nbCols)); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << nbRows * nbCols << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical stdev = " << stdev_rgba_ref << " | returned value = " << stdev << std::endl; + } + } + nameTest = "vpImage::getStdev()"; stdev = I_rgbf_ref.getStdev(); success = vpMath::equal(stdev, stdev_rgbf_ref); @@ -611,6 +821,21 @@ int main(const int argc, const char *argv[]) } } + nameTest = ("vpImage::getStdev(const vpImage * = nullptr)"); + stdev = I_rgbf_ref.getStdev(nullptr); + success = vpMath::equal(stdev, stdev_rgbf_ref); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical stdev = " << stdev_rgbf_ref << " | returned value = " << stdev << std::endl; + } + } + nameTest = ("vpImage::getStdev(const double &)"); mean = I_rgbf_ref.getMeanValue(); stdev = I_rgbf_ref.getStdev(mean); @@ -643,6 +868,24 @@ int main(const int argc, const char *argv[]) std::cout << "Theoretical stdev = " << stdev_rgbf_true << " | returned value = " << stdev << std::endl; } } + + nameTest = ("vpImage::getStdev(const double &, const unsigned int&, const vpImage* = nullptr)"); + nbValidPoints = 0; + mean = I_rgbf_ref.getMeanValue(nullptr, nbValidPoints); + stdev = I_rgbf_ref.getStdev(mean, nbValidPoints, nullptr); + success = vpMath::equal(stdev, stdev_rgbf_ref) && (nbValidPoints == (nbRows * nbCols)); + if (!success) { + ++nbFailedTests; + failedTestsNames.push_back(nameTest); + areTestOK = false; + } + if (opt_verbose) { + std::cout << "\tTest " << nameTest << ": " << (success ? "OK" : "failure") << std::endl; + if (!success) { + std::cout << "Theoretical count = " << nbRows * nbCols << " | returned value = " << nbValidPoints << std::endl; + std::cout << "Theoretical stdev = " << stdev_rgbf_ref << " | returned value = " << stdev << std::endl; + } + } } if (areTestOK) { From 763516abe2333edec2c0fbbeb31e0d4cae359c3e Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 15:57:23 +0100 Subject: [PATCH 116/164] Fix new typo --- doc/tutorial/python/tutorial-install-python-bindings.dox | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/tutorial/python/tutorial-install-python-bindings.dox b/doc/tutorial/python/tutorial-install-python-bindings.dox index 938058d273..69f40c87d9 100644 --- a/doc/tutorial/python/tutorial-install-python-bindings.dox +++ b/doc/tutorial/python/tutorial-install-python-bindings.dox @@ -518,7 +518,7 @@ for example `python=3.10` to the previous command lines. ... libvisp_core361.dll ... - Now you cab build the bindings + Now you can build the bindings (visp-conda-ws) C:\visp-ws\visp-build-bindings> cmake --build . --config Release --target visp_python_bindings --parallel 8 From d478399910073d7717e130a49ad6ca041eb3a328 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 16:41:15 +0100 Subject: [PATCH 117/164] Doxygen doc indentation --- .../core/include/visp3/core/vpRxyzVector.h | 48 +++--- .../src/math/transformation/vpRxyzVector.cpp | 68 ++++----- .../src/math/transformation/vpRzyxVector.cpp | 65 ++++---- .../src/math/transformation/vpRzyzVector.cpp | 68 ++++----- .../math/transformation/vpThetaUVector.cpp | 142 +++++++++--------- .../transformation/vpTranslationVector.cpp | 53 ++++--- 6 files changed, 217 insertions(+), 227 deletions(-) diff --git a/modules/core/include/visp3/core/vpRxyzVector.h b/modules/core/include/visp3/core/vpRxyzVector.h index 9c13ec776c..2a72c79a65 100644 --- a/modules/core/include/visp3/core/vpRxyzVector.h +++ b/modules/core/include/visp3/core/vpRxyzVector.h @@ -137,37 +137,37 @@ class vpThetaUVector; from the build rotation matrix. \code -#include -#include -#include -#include + #include + #include + #include + #include -int main() -{ - vpRxyzVector rxyz; + int main() + { + vpRxyzVector rxyz; - // Initialise the Euler angles - rxyz[0] = vpMath::rad( 45.f); // phi angle in rad around x axis - rxyz[1] = vpMath::rad(-30.f); // theta angle in rad around y axis - rxyz[2] = vpMath::rad( 90.f); // psi angle in rad around z axis + // Initialise the Euler angles + rxyz[0] = vpMath::rad( 45.f); // phi angle in rad around x axis + rxyz[1] = vpMath::rad(-30.f); // theta angle in rad around y axis + rxyz[2] = vpMath::rad( 90.f); // psi angle in rad around z axis - // Construct a rotation matrix from the Euler angles - vpRotationMatrix R(rxyz); + // Construct a rotation matrix from the Euler angles + vpRotationMatrix R(rxyz); - // Extract the Euler angles around x,y,z axis from a rotation matrix - rxyz.buildFrom(R); + // Extract the Euler angles around x,y,z axis from a rotation matrix + rxyz.buildFrom(R); - // Print the extracted Euler angles. Values are the same than the - // one used for initialization - std::cout << rxyz; + // Print the extracted Euler angles. Values are the same than the + // one used for initialization + std::cout << rxyz; - // Since the rotation vector is 3 values column vector, the - // transpose operation produce a row vector. - vpRowVector rxyz_t = rxyz.t(); + // Since the rotation vector is 3 values column vector, the + // transpose operation produce a row vector. + vpRowVector rxyz_t = rxyz.t(); - // Print the transpose row vector - std::cout << rxyz_t << std::endl; -} + // Print the transpose row vector + std::cout << rxyz_t << std::endl; + } \endcode */ diff --git a/modules/core/src/math/transformation/vpRxyzVector.cpp b/modules/core/src/math/transformation/vpRxyzVector.cpp index 4eb17b8b43..704881fde9 100644 --- a/modules/core/src/math/transformation/vpRxyzVector.cpp +++ b/modules/core/src/math/transformation/vpRxyzVector.cpp @@ -31,8 +31,7 @@ * Description: * Rxyz angle parameterization for the rotation. * Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi). - * -*****************************************************************************/ + */ #include @@ -170,18 +169,18 @@ vpRxyzVector vpRxyzVector::buildFrom(const std::vector &rxyz) \param v : Angle value to set for each element of the vector. -\code -#include -#include + \code + #include + #include -int main() -{ - vpRxyzVector v; + int main() + { + vpRxyzVector v; - // Initialise the rotation vector - v = vpMath::rad( 45.f); // All the 3 angles are set to 45 degrees -} -\endcode + // Initialise the rotation vector + v = vpMath::rad( 45.f); // All the 3 angles are set to 45 degrees + } + \endcode */ vpRxyzVector &vpRxyzVector::operator=(double v) { @@ -196,23 +195,22 @@ vpRxyzVector &vpRxyzVector::operator=(double v) Copy operator that initializes a \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dimension column vector. - \param rxyz : 3-dimension vector containing the values of the rotation -vector. - -\code -#include + \param rxyz : 3-dimension vector containing the values of the rotation vector. -int main() -{ - vpColVector v(3); - v[0] = 0.1; - v[1] = 0.2; - v[2] = 0.3; - vpRxyzVector rxyz; - rxyz = v; - // rxyz is now equal to v : 0.1, 0.2, 0.3 -} -\endcode + \code + #include + + int main() + { + vpColVector v(3); + v[0] = 0.1; + v[1] = 0.2; + v[2] = 0.3; + vpRxyzVector rxyz; + rxyz = v; + // rxyz is now equal to v : 0.1, 0.2, 0.3 + } + \endcode */ vpRxyzVector &vpRxyzVector::operator=(const vpColVector &rxyz) { @@ -230,17 +228,17 @@ vpRxyzVector &vpRxyzVector::operator=(const vpColVector &rxyz) /*! Set vector from a list of 3 double angle values in radians. \code -#include + #include -int main() -{ - vpRxyzVector rxyz = {M_PI, 0, M_PI_2}; - std::cout << "rxyz: " << rxyz.t() << std::endl; -} + int main() + { + vpRxyzVector rxyz = {M_PI, 0, M_PI_2}; + std::cout << "rxyz: " << rxyz.t() << std::endl; + } \endcode It produces the following printings: \code -rxyz: 3.141592654 0 1.570796327 + rxyz: 3.141592654 0 1.570796327 \endcode \sa operator<<() */ diff --git a/modules/core/src/math/transformation/vpRzyxVector.cpp b/modules/core/src/math/transformation/vpRzyxVector.cpp index 523e917e93..1d8c7613e2 100644 --- a/modules/core/src/math/transformation/vpRzyxVector.cpp +++ b/modules/core/src/math/transformation/vpRzyxVector.cpp @@ -176,18 +176,18 @@ vpRzyxVector vpRzyxVector::buildFrom(const std::vector &rzyx) \param v : Angle value to set for each element of the vector. -\code -#include -#include + \code + #include + #include -int main() -{ - vpRzyxVector v; + int main() + { + vpRzyxVector v; - // Initialise the rotation vector - v = vpMath::rad( 45.f); // All the 3 angles are set to 45 degrees -} -\endcode + // Initialise the rotation vector + v = vpMath::rad( 45.f); // All the 3 angles are set to 45 degrees + } + \endcode */ vpRzyxVector &vpRzyxVector::operator=(double v) { @@ -202,23 +202,22 @@ vpRzyxVector &vpRzyxVector::operator=(double v) Copy operator that initializes a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dimension column vector. - \param rzyx : 3-dimension vector containing the values of the rotation -vector. - -\code -#include + \param rzyx : 3-dimension vector containing the values of the rotation vector. -int main() -{ - vpColVector v(3); - v[0] = 0.1; - v[1] = 0.2; - v[2] = 0.3; - vpRzyxVector rzyx; - rzyx = v; - // rzyx is now equal to v : 0.1, 0.2, 0.3 -} -\endcode + \code + #include + + int main() + { + vpColVector v(3); + v[0] = 0.1; + v[1] = 0.2; + v[2] = 0.3; + vpRzyxVector rzyx; + rzyx = v; + // rzyx is now equal to v : 0.1, 0.2, 0.3 + } + \endcode */ vpRzyxVector &vpRzyxVector::operator=(const vpColVector &rzyx) { @@ -236,17 +235,17 @@ vpRzyxVector &vpRzyxVector::operator=(const vpColVector &rzyx) /*! Set vector from a list of 3 double angle values in radians. \code -#include + #include -int main() -{ - vpRzyxVector rzyx = {M_PI, 0, M_PI_2}; - std::cout << "rzyx: " << rzyx.t() << std::endl; -} + int main() + { + vpRzyxVector rzyx = {M_PI, 0, M_PI_2}; + std::cout << "rzyx: " << rzyx.t() << std::endl; + } \endcode It produces the following printings: \code -rzyx: 3.141592654 0 1.570796327 + zyx: 3.141592654 0 1.570796327 \endcode \sa operator<<() */ diff --git a/modules/core/src/math/transformation/vpRzyzVector.cpp b/modules/core/src/math/transformation/vpRzyzVector.cpp index e396fb5fdb..f3fe667c06 100644 --- a/modules/core/src/math/transformation/vpRzyzVector.cpp +++ b/modules/core/src/math/transformation/vpRzyzVector.cpp @@ -31,8 +31,7 @@ * Description: * Euler angles parameterization for the rotation. * Rzyz(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(z,psi) - * -*****************************************************************************/ + */ #include #include @@ -154,18 +153,18 @@ vpRzyzVector vpRzyzVector::buildFrom(const std::vector &rzyz) \param v : Angle value to set for each element of the vector. -\code -#include -#include + \code + #include + #include -int main() -{ - vpRzyzVector r; + int main() + { + vpRzyzVector r; - // Initialise the rotation vector - r = vpMath::rad( 45.f); // All the 3 angles are set to 45 degrees -} -\endcode + // Initialise the rotation vector + r = vpMath::rad( 45.f); // All the 3 angles are set to 45 degrees + } + \endcode */ vpRzyzVector &vpRzyzVector::operator=(double v) { @@ -193,23 +192,22 @@ void vpRzyzVector::buildFrom(double phi, double theta, double psi) Copy operator that initializes a \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dimension column vector. - \param rzyz : 3-dimension vector containing the values of the rotation -vector. - -\code -#include + \param rzyz : 3-dimension vector containing the values of the rotation vector. -int main() -{ - vpColVector v(3); - v[0] = 0.1; - v[1] = 0.2; - v[2] = 0.3; - vpRzyxVector rzyz; - rzyz = v; - // rzyz is now equal to v : 0.1, 0.2, 0.3 -} -\endcode + \code + #include + + int main() + { + vpColVector v(3); + v[0] = 0.1; + v[1] = 0.2; + v[2] = 0.3; + vpRzyxVector rzyz; + rzyz = v; + // rzyz is now equal to v : 0.1, 0.2, 0.3 + } + \endcode */ vpRzyzVector &vpRzyzVector::operator=(const vpColVector &rzyz) { @@ -227,17 +225,17 @@ vpRzyzVector &vpRzyzVector::operator=(const vpColVector &rzyz) /*! Set vector from a list of 3 double angle values in radians. \code -#include + #include -int main() -{ - vpRzyzVector rzyz = {M_PI, 0, M_PI_2}; - std::cout << "rzyz: " << rzyz.t() << std::endl; -} + int main() + { + vpRzyzVector rzyz = {M_PI, 0, M_PI_2}; + std::cout << "rzyz: " << rzyz.t() << std::endl; + } \endcode It produces the following printings: \code -rzyz: 3.141592654 0 1.570796327 + rzyz: 3.141592654 0 1.570796327 \endcode \sa operator<<() */ diff --git a/modules/core/src/math/transformation/vpThetaUVector.cpp b/modules/core/src/math/transformation/vpThetaUVector.cpp index d9738d6dba..3f4ae7355a 100644 --- a/modules/core/src/math/transformation/vpThetaUVector.cpp +++ b/modules/core/src/math/transformation/vpThetaUVector.cpp @@ -30,13 +30,11 @@ * * Description: * Theta U parameterization for the rotation. - * -*****************************************************************************/ + */ /*! -\file vpThetaUVector.cpp -\brief class that consider the case of the Theta U parameterization for the -rotation + \file vpThetaUVector.cpp + \brief class that consider the case of the Theta U parameterization for the rotation */ #include // std::fabs @@ -85,17 +83,17 @@ vpThetaUVector::vpThetaUVector(const vpQuaternionVector &q) : vpRotationVector(3 /*! Build a \f$\theta {\bf u}\f$ vector from 3 angles in radians. \code -#include + #include -int main() -{ - vpThetaUVector tu(0, M_PI_2, M_PI); - std::cout << "tu: " << tu.t() << std::endl; -} + int main() + { + vpThetaUVector tu(0, M_PI_2, M_PI); + std::cout << "tu: " << tu.t() << std::endl; + } \endcode It produces the following printings: \code -tu: 0 1.570796327 3.141592654 + tu: 0 1.570796327 3.141592654 \endcode */ vpThetaUVector::vpThetaUVector(double tux, double tuy, double tuz) : vpRotationVector(3) { buildFrom(tux, tuy, tuz); } @@ -273,21 +271,20 @@ vpThetaUVector vpThetaUVector::buildFrom(const vpColVector &tu) Initialize each element of the \f$\theta {\bf u}\f$ vector to the same angle value \e v. - \param v : Angle value to set for each element of the \f$\theta {\bf - u}\f$ vector. + \param v : Angle value to set for each element of the \f$\theta {\bf u}\f$ vector. -\code -#include -#include + \code + #include + #include -int main() -{ - vpThetaUVector tu; + int main() + { + vpThetaUVector tu; - // Initialise the theta U rotation vector - tu = vpMath::rad( 45.f); // All the 3 angles are set to 45 degrees -} -\endcode + // Initialise the theta U rotation vector + tu = vpMath::rad( 45.f); // All the 3 angles are set to 45 degrees + } + \endcode */ vpThetaUVector &vpThetaUVector::operator=(double v) { @@ -300,25 +297,24 @@ vpThetaUVector &vpThetaUVector::operator=(double v) /*! Copy operator that initializes a \f$\theta {\bf u}\f$ vector from a -3-dimension column vector \e tu. + 3-dimension column vector \e tu. - \param tu : 3-dimension vector containing the values of the \f$\theta {\bf -u}\f$ vector. + \param tu : 3-dimension vector containing the values of the \f$\theta {\bf u}\f$ vector. -\code -#include + \code + #include -int main() -{ - vpColVector v(3); - v[0] = 0.1; - v[1] = 0.2; - v[2] = 0.3; - vpThetaUVector tu; - tu = v; - // tu is now equal to v : 0.1, 0.2, 0.3 -} -\endcode + int main() + { + vpColVector v(3); + v[0] = 0.1; + v[1] = 0.2; + v[2] = 0.3; + vpThetaUVector tu; + tu = v; + // tu is now equal to v : 0.1, 0.2, 0.3 + } + \endcode */ vpThetaUVector &vpThetaUVector::operator=(const vpColVector &tu) { @@ -344,18 +340,18 @@ vpThetaUVector &vpThetaUVector::operator=(const vpColVector &tu) The following example shows how to use this function: \code -#include + #include -int main() -{ - vpHomogeneousMatrix M(0, 0, 1., vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)); + int main() + { + vpHomogeneousMatrix M(0, 0, 1., vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)); - double theta; - vpColVector u; - M.getRotationMatrix().getThetaUVector().extract(theta, u); - std::cout << "theta: " << theta << std::endl; - std::cout << "u : " << u.t() << std::endl; -} + double theta; + vpColVector u; + M.getRotationMatrix().getThetaUVector().extract(theta, u); + std::cout << "theta: " << theta << std::endl; + std::cout << "u : " << u.t() << std::endl; + } \endcode \sa getTheta(), getU() @@ -377,21 +373,21 @@ void vpThetaUVector::extract(double &theta, vpColVector &u) const /*! Get the rotation angle \f$ \theta \f$ from the \f$ \theta {\bf u} \f$ -representation. + representation. \return Rotation angle \f$ \theta \f$ in rad. The following example shows how to use this function: \code -#include + #include -int main() -{ - vpHomogeneousMatrix M(0, 0, 1., vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)); + int main() + { + vpHomogeneousMatrix M(0, 0, 1., vpMath::rad(10), vpMath::rad(20), vpMath::rad(30)); - std::cout << "theta: " << M.getRotationMatrix().getThetaUVector().getTheta() << std::endl; - std::cout << "u : " << M.getRotationMatrix().getThetaUVector().getU().t() << std::endl; -} + std::cout << "theta: " << M.getRotationMatrix().getThetaUVector().getTheta() << std::endl; + std::cout << "u : " << M.getRotationMatrix().getThetaUVector().getU().t() << std::endl; + } \endcode \sa getTheta(), extract() @@ -401,22 +397,22 @@ double vpThetaUVector::getTheta() const { return sqrt(data[0] * data[0] + data[1 /*! Get the unit vector \f$\bf u \f$ from the \f$ \theta {\bf u} \f$ -representation. + representation. \return 3-dim unit vector \f${\bf u} = (u_{x},u_{y},u_{z})^{\top} \f$ representing the rotation axis. The following example shows how to use this function: \code -#include + #include -int main() -{ - vpHomogeneousMatrix M(0, 0, 1., vpMath::rad(10), vpMath::rad(20), pMath::rad(30)); + int main() + { + vpHomogeneousMatrix M(0, 0, 1., vpMath::rad(10), vpMath::rad(20), pMath::rad(30)); - std::cout << "theta: " << M.getRotationMatrix().getThetaUVector().getTheta() << std::endl; - std::cout << "u : " << M.getRotationMatrix().getThetaUVector().getU().t() << std::endl; -} + std::cout << "theta: " << M.getRotationMatrix().getThetaUVector().getTheta() << std::endl; + std::cout << "u : " << M.getRotationMatrix().getThetaUVector().getU().t() << std::endl; + } \endcode \sa getTheta(), extract() @@ -471,17 +467,17 @@ vpThetaUVector vpThetaUVector::operator*(const vpThetaUVector &tu_b) const /*! Set vector from a list of 3 double angle values in radians. \code -#include + #include -int main() -{ - vpThetaUVector tu = {M_PI, 0, M_PI_2}; - std::cout << "tu: " << tu.t() << std::endl; -} + int main() + { + vpThetaUVector tu = {M_PI, 0, M_PI_2}; + std::cout << "tu: " << tu.t() << std::endl; + } \endcode It produces the following printings: \code -tu: 3.141592654 0 1.570796327 + tu: 3.141592654 0 1.570796327 \endcode \sa operator<<() */ diff --git a/modules/core/src/math/transformation/vpTranslationVector.cpp b/modules/core/src/math/transformation/vpTranslationVector.cpp index 19767242a8..74a22cfa14 100644 --- a/modules/core/src/math/transformation/vpTranslationVector.cpp +++ b/modules/core/src/math/transformation/vpTranslationVector.cpp @@ -30,8 +30,7 @@ * * Description: * Translation vector. - * -*****************************************************************************/ + */ #include #include @@ -236,7 +235,7 @@ vpTranslationVector vpTranslationVector::operator+(const vpTranslationVector &tv \return The sum of the current translation vector (*this) and the column vector to add. -\code + \code vpTranslationVector t1(1,2,3); vpColVector v(3); v[0] = 4; @@ -510,17 +509,17 @@ vpTranslationVector &vpTranslationVector::operator=(double x) /*! Set vector from a list of 3 double values in meters. \code -#include + #include -int main() -{ - vpTranslationVector t = {0, 0.1, 0.5}; - std::cout << "t: " << t.t() << std::endl; -} + int main() + { + vpTranslationVector t = {0, 0.1, 0.5}; + std::cout << "t: " << t.t() << std::endl; + } \endcode It produces the following printings: \code -t: 0 0.1 0.5 + t: 0 0.1 0.5 \endcode \sa operator<<() */ @@ -544,18 +543,18 @@ vpTranslationVector &vpTranslationVector::operator=(const std::initializer_list< The following example shows how to initialize a translation vector from a list of 3 values [meter]. \code -#include + #include -int main() -{ - vpTranslationVector t; - t << 0, 0.1, 0.5; - std::cout << "t: " << t.t() << std::endl; -} + int main() + { + vpTranslationVector t; + t << 0, 0.1, 0.5; + std::cout << "t: " << t.t() << std::endl; + } \endcode It produces the following printings: \code -t: 0 0.1 0.5 + t: 0 0.1 0.5 \endcode \sa operator,() @@ -574,18 +573,18 @@ vpTranslationVector &vpTranslationVector::operator<<(double val) The following example shows how to initialize a translations vector from a list of 3 values [meter]. \code -#include + #include -int main() -{ - vpTranslationVector t; - t << 0, 0.1, 0.5; - std::cout << "t: " << t.t() << std::endl; -} + int main() + { + vpTranslationVector t; + t << 0, 0.1, 0.5; + std::cout << "t: " << t.t() << std::endl; + } \endcode It produces the following printings: \code -t: 0 0.1 0.5 + t: 0 0.1 0.5 \endcode \sa operator<<() @@ -742,7 +741,7 @@ double vpTranslationVector::frobeniusNorm() const vector t(m). \return The value \f[\sum{i=0}^{m} t_i^{2}\f]. - */ +*/ double vpTranslationVector::sumSquare() const { double sum_square = 0.0; From 25dcb1d0ceba86ab894b9e68fcbf94d722ac86a1 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 16:44:36 +0100 Subject: [PATCH 118/164] Fix build on centos 7.2 ci that has OpenCV 2.4.5 --- modules/core/include/visp3/core/vpImage.h | 2 +- .../core/include/visp3/core/vpImageConvert.h | 2 +- .../perfColorConversion.cpp | 2 +- .../image-with-dataset/perfGaussianFilter.cpp | 2 +- .../image-with-dataset/perfImageResize.cpp | 2 +- .../image-with-dataset/testConversion.cpp | 2 +- .../gui/include/visp3/gui/vpDisplayOpenCV.h | 7 +++ modules/gui/src/display/vpDisplayOpenCV.cpp | 48 ++++++++----------- tutorial/image/tutorial-image-converter.cpp | 2 +- 9 files changed, 34 insertions(+), 35 deletions(-) diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 3687de81e9..4f6ed7c048 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -845,7 +845,7 @@ vpImage::vpImage(const vpImage &I) { resize(I.getHeight(), I.getWidth()); if (bitmap) { - memcpy(static_cast(bitmap), static_cast(I.bitmap), I.npixels * sizeof(Type)); + memcpy(static_cast(bitmap), static_cast(I.bitmap), I.npixels * sizeof(Type)); } } diff --git a/modules/core/include/visp3/core/vpImageConvert.h b/modules/core/include/visp3/core/vpImageConvert.h index 1e566d531a..6d48456f6b 100644 --- a/modules/core/include/visp3/core/vpImageConvert.h +++ b/modules/core/include/visp3/core/vpImageConvert.h @@ -49,7 +49,7 @@ #include #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) -#include +#include #include #endif diff --git a/modules/core/test/image-with-dataset/perfColorConversion.cpp b/modules/core/test/image-with-dataset/perfColorConversion.cpp index 03d24abf5b..e6df803d23 100644 --- a/modules/core/test/image-with-dataset/perfColorConversion.cpp +++ b/modules/core/test/image-with-dataset/perfColorConversion.cpp @@ -47,7 +47,7 @@ #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS) && defined(HAVE_OPENCV_IMGPROC) #include -#include +#include #endif static std::string ipath = vpIoTools::getViSPImagesDataPath(); diff --git a/modules/core/test/image-with-dataset/perfGaussianFilter.cpp b/modules/core/test/image-with-dataset/perfGaussianFilter.cpp index 62adcee3c9..e557cf30ce 100644 --- a/modules/core/test/image-with-dataset/perfGaussianFilter.cpp +++ b/modules/core/test/image-with-dataset/perfGaussianFilter.cpp @@ -47,7 +47,7 @@ #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS) && defined(HAVE_OPENCV_IMGPROC) #include -#include +#include #endif static const std::string ipath = vpIoTools::getViSPImagesDataPath(); diff --git a/modules/core/test/image-with-dataset/perfImageResize.cpp b/modules/core/test/image-with-dataset/perfImageResize.cpp index 69cd7d90ca..98fb426a42 100644 --- a/modules/core/test/image-with-dataset/perfImageResize.cpp +++ b/modules/core/test/image-with-dataset/perfImageResize.cpp @@ -48,7 +48,7 @@ #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS) && defined(HAVE_OPENCV_IMGPROC) #include -#include +#include #endif static const std::string ipath = vpIoTools::getViSPImagesDataPath(); diff --git a/modules/core/test/image-with-dataset/testConversion.cpp b/modules/core/test/image-with-dataset/testConversion.cpp index c164315390..5386640292 100644 --- a/modules/core/test/image-with-dataset/testConversion.cpp +++ b/modules/core/test/image-with-dataset/testConversion.cpp @@ -47,7 +47,7 @@ #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS) && defined(HAVE_OPENCV_IMGPROC) #include -#include +#include #endif /*! diff --git a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h index ca9ce797d9..693a9672d2 100644 --- a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h +++ b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h @@ -135,11 +135,18 @@ class VISP_EXPORT vpDisplayOpenCV : public vpDisplay { private: +#if (VISP_HAVE_OPENCV_VERSION < 0x020408) + IplImage *m_background; + CvScalar *col; + CvScalar cvcolor; + CvFont *font; +#else cv::Mat m_background; cv::Scalar *col; cv::Scalar cvcolor; int font; float fontScale; +#endif static std::vector m_listTitles; static unsigned int m_nbWindows; int fontHeight; diff --git a/modules/gui/src/display/vpDisplayOpenCV.cpp b/modules/gui/src/display/vpDisplayOpenCV.cpp index a31918ab57..0ba15d1e68 100644 --- a/modules/gui/src/display/vpDisplayOpenCV.cpp +++ b/modules/gui/src/display/vpDisplayOpenCV.cpp @@ -778,7 +778,7 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpI \warning Display has to be initialized. - \warning suppres the overlay drawing + \warning suppress the overlay drawing \param I : Image to display. @@ -1142,7 +1142,7 @@ void vpDisplayOpenCV::displayText(const vpImagePoint &ip, const std::string &tex if (m_displayHasBeenInitialized) { if (color.id < vpColor::id_unknown) { #if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvPutText(m_background, text, + cvPutText(m_background, text.c_str(), cvPoint(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale + fontHeight)), font, col[color.id]); #else @@ -1154,7 +1154,7 @@ void vpDisplayOpenCV::displayText(const vpImagePoint &ip, const std::string &tex else { cvcolor = CV_RGB(color.R, color.G, color.B); #if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvPutText(m_background, text, + cvPutText(m_background, text.c_str(), cvPoint(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale + fontHeight)), font, cvcolor); #else @@ -1209,11 +1209,10 @@ void vpDisplayOpenCV::displayCircle(const vpImagePoint ¢er, unsigned int rad #else int filled = CV_FILLED; #endif - double opacity = static_cast(color.A) / 255.0; #if VISP_HAVE_OPENCV_VERSION < 0x020408 - overlay([x, y, r, cv_color, filled](cv::Mat image) { cvCircle(image, cvPoint(x, y), r, cv_color, filled); }, - opacity); + cvCircle(m_background, cvPoint(x, y), r, cv_color, filled); #else + double opacity = static_cast(color.A) / 255.0; overlay([x, y, r, cv_color, filled](cv::Mat image) { cv::circle(image, cv::Point(x, y), r, cv_color, filled); }, opacity); #endif @@ -1426,15 +1425,12 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, unsigned int #else int filled = CV_FILLED; #endif - double opacity = static_cast(color.A) / 255.0; #if VISP_HAVE_OPENCV_VERSION < 0x020408 - overlay([left, top, right, bottom, cv_color, filled]( - cv::Mat image) { cvRectangle(image, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); }, - opacity); + cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); #else - overlay( - [left, top, right, bottom, cv_color, filled](cv::Mat image) { - cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); + double opacity = static_cast(color.A) / 255.0; + overlay([left, top, right, bottom, cv_color, filled](cv::Mat image) { + cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); }, opacity); #endif @@ -1488,15 +1484,12 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, const vpImag #else int filled = CV_FILLED; #endif - double opacity = static_cast(color.A) / 255.0; #if VISP_HAVE_OPENCV_VERSION < 0x020408 - overlay([left, top, right, bottom, cv_color, filled]( - cv::Mat image) { cvRectangle(image, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); }, - opacity); + cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); #else - overlay( - [left, top, right, bottom, cv_color, filled](cv::Mat image) { - cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); + double opacity = static_cast(color.A) / 255.0; + overlay([left, top, right, bottom, cv_color, filled](cv::Mat image) { + cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); }, opacity); #endif @@ -1549,15 +1542,12 @@ void vpDisplayOpenCV::displayRectangle(const vpRect &rectangle, const vpColor &c #else int filled = CV_FILLED; #endif - double opacity = static_cast(color.A) / 255.0; #if VISP_HAVE_OPENCV_VERSION < 0x020408 - overlay([left, top, right, bottom, cv_color, filled]( - cv::Mat image) { cvRectangle(image, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); }, - opacity); + cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); #else - overlay( - [left, top, right, bottom, cv_color, filled](cv::Mat image) { - cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); + double opacity = static_cast(color.A) / 255.0; + overlay([left, top, right, bottom, cv_color, filled](cv::Mat image) { + cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); }, opacity); #endif @@ -2147,6 +2137,7 @@ unsigned int vpDisplayOpenCV::getScreenHeight() return height; } +#if VISP_HAVE_OPENCV_VERSION >= 0x020408 /*! * Initialize display overlay layer for transparency. * \param overlay_function : Overlay function @@ -2161,7 +2152,7 @@ void vpDisplayOpenCV::overlay(std::function overlay_function, d overlay = m_background.clone(); } else { - // Shallow copy + // Shallow copy overlay = m_background; } @@ -2172,6 +2163,7 @@ void vpDisplayOpenCV::overlay(std::function overlay_function, d cv::addWeighted(overlay, opacity, m_background, 1.0 - opacity, 0.0, m_background); } } +#endif #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpDisplayOpenCV.cpp.o) has no symbols diff --git a/tutorial/image/tutorial-image-converter.cpp b/tutorial/image/tutorial-image-converter.cpp index 15c96d7037..59e5a9bf9d 100644 --- a/tutorial/image/tutorial-image-converter.cpp +++ b/tutorial/image/tutorial-image-converter.cpp @@ -4,7 +4,7 @@ #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGCODECS) && defined(HAVE_OPENCV_IMGPROC) #include -#include +#include #endif int main() From 0a7d3f3433dfb1339f6e677cabec7d969363a4d1 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Wed, 13 Mar 2024 17:52:33 +0100 Subject: [PATCH 119/164] Changes to set OpenCV 2.4.8 as minimal required version --- CMakeLists.txt | 19 +- ChangeLog.txt | 1 + .../tracking/tutorial-tracking-keypoint.dox | 21 +- .../gui/include/visp3/gui/vpDisplayOpenCV.h | 17 +- modules/gui/src/display/vpDisplayOpenCV.cpp | 406 +----------------- .../keypoint/tutorial-klt-tracker.cpp | 28 +- 6 files changed, 52 insertions(+), 440 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 69baf3046c..696695995d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -628,6 +628,23 @@ if(USE_PCL) vp_find_pcl(PCL_LIBRARIES PCL_DEPS_INCLUDE_DIRS PCL_DEPS_LIBRARIES) endif() +# ---------------------------------------------------------------------------- +# Handle OpenCV 2.4.8 as minimal version +# ---------------------------------------------------------------------------- +if(USE_OPENCV) + if(OpenCV_VERSION) + if(OpenCV_VERSION VERSION_LESS "2.4.8") + message(WARNING "OpenCV 3rd party was detected but its version ${OpenCV_VERSION} is too old. Thus we disable OpenCV usage turning USE_OPENCV=OFF.") + unset(USE_OPENCV) + set(USE_OPENCV OFF CACHE BOOL "Include OpenCV support" FORCE) + endif() + else() + message(WARNING "OpenCV 3rd party was detected but its version cannot be found or is too old. Thus we disable OpenCV usage turning USE_OPENCV=OFF.") + unset(USE_OPENCV) + set(USE_OPENCV OFF CACHE BOOL "Include OpenCV support" FORCE) + endif() +endif() + # ---------------------------------------------------------------------------- # Handle cxx standard depending on specific 3rd parties. Should be before module parsing and VISP3rdParty.cmake include # ---------------------------------------------------------------------------- @@ -642,7 +659,7 @@ endif() if(VISP_CXX_STANDARD LESS VISP_CXX_STANDARD_14) if(USE_FTIITSDK) - message(WARNING "IIT force-torque SDK 3rd party was detected and needs at least c++14 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable IIT force-torque usage turning USE_OPENCV=OFF.") + message(WARNING "IIT force-torque SDK 3rd party was detected and needs at least c++14 standard compiler flag while you have set c++${USE_CXX_STANDARD}. Thus we disable IIT force-torque usage turning USE_FTIITSDK=OFF.") unset(USE_FTIITSDK) set(USE_FTIITSDK OFF CACHE BOOL "Include IIT force-torque SDK support" FORCE) endif() diff --git a/ChangeLog.txt b/ChangeLog.txt index 0962d7d15e..57df379736 100644 --- a/ChangeLog.txt +++ b/ChangeLog.txt @@ -18,6 +18,7 @@ ViSP 3.x.x (Version in development) . End of supporting c++98 standard. As a consequence, ViSP is no more compatible with Ubuntu 12.04 . vpDisplay::displayCharString() is marked deprecated. Use vpDisplay::displayText() instead - New features and improvements + . OpenCV 2.4.8 is the minimal supported version . Introduce applications in apps folder, a collection of useful tools that have a dependency to the install target . Bump minimal c++ standard to c++11 diff --git a/doc/tutorial/tracking/tutorial-tracking-keypoint.dox b/doc/tutorial/tracking/tutorial-tracking-keypoint.dox index 8b8dc838cf..d89aa57098 100644 --- a/doc/tutorial/tracking/tutorial-tracking-keypoint.dox +++ b/doc/tutorial/tracking/tutorial-tracking-keypoint.dox @@ -35,7 +35,7 @@ It can also be run with [--init-by-click] option. In that case, the user can sel $ ./tutorial-klt-tracker --init-by-click \endcode -Here is the line by line explanation of the source : +Here is the line by line explanation of the source : \snippet tutorial-klt-tracker.cpp Include @@ -60,19 +60,19 @@ This image \c I is then converted into \c cvI, an OpenCV image format that will \snippet tutorial-klt-tracker.cpp Convert to OpenCV image -We also create a window associated to \c I, at position (0,0) in the screen, with "Klt tracking" as title, and display image \c I. +We also create a window associated to \c I, at position (0,0) in the screen, with "Klt tracking" as title, and display image \c I. \snippet tutorial-klt-tracker.cpp Init display - + From now we have to create an instance of the tracker and set the parameters of the Harris keypoint detector. \snippet tutorial-klt-tracker.cpp Create tracker - + The tracker is then initialized on \c cvI image. \snippet tutorial-klt-tracker.cpp Init tracker -With the next line the user can know how many keypoints were detected automatically or selected by the user during initialization. +With the next line the user can know how many keypoints were detected automatically or selected by the user during initialization. \snippet tutorial-klt-tracker.cpp How many features @@ -92,7 +92,7 @@ We are waiting for a mouse click event on image \c I to end the program. \section tracking_keypoint_klt_init KLT tracker with re-initialisation -Once initialized, the number of tracked features decreases over the time. Depending on a criteria, it may sense to detect and track new features online. A possible criteria is for example to compare the number of currently tracked features to the initial number of detected features. If less than a given percentage of features are tracked, you can start a new detection. +Once initialized, the number of tracked features decreases over the time. Depending on a criteria, it may sense to detect and track new features online. A possible criteria is for example to compare the number of currently tracked features to the initial number of detected features. If less than a given percentage of features are tracked, you can start a new detection. To get the number of detected or tracked features just call: @@ -107,10 +107,10 @@ The example tutorial-klt-tracker-with-reinit.cpp shows how to do that. In that e \code if (reader.getFrameIndex() == 25) { std::cout << "Re initialize the tracker" << std::endl; -#if (VISP_HAVE_OPENCV_VERSION >= 0x020408) + // Save of previous features std::vector prev_features = tracker.getFeatures(); - + // Start a new feature detection tracker.initTracking(cvI); std::vector new_features = tracker.getFeatures(); @@ -122,7 +122,7 @@ The example tutorial-klt-tracker-with-reinit.cpp shows how to do that. In that e // Test if a previous feature is not redundant with one of the newly detected is_redundant = false; for (size_t j=0; j < new_features.size(); j++){ - distance = sqrt(vpMath::sqr(new_features[j].x-prev_features[i].x) + distance = sqrt(vpMath::sqr(new_features[j].x-prev_features[i].x) + vpMath::sqr(new_features[j].y-prev_features[i].y)); if(distance < minDistance_){ is_redundant = true; @@ -135,9 +135,6 @@ The example tutorial-klt-tracker-with-reinit.cpp shows how to do that. In that e //std::cout << "Add previous feature with index " << i << std::endl; tracker.addFeature(prev_features[i]); } -#else - ... -#endif } // Track the features tracker.track(cvI); diff --git a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h index 693a9672d2..dc1b858583 100644 --- a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h +++ b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h @@ -135,18 +135,11 @@ class VISP_EXPORT vpDisplayOpenCV : public vpDisplay { private: -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - IplImage *m_background; - CvScalar *col; - CvScalar cvcolor; - CvFont *font; -#else cv::Mat m_background; cv::Scalar *col; cv::Scalar cvcolor; int font; float fontScale; -#endif static std::vector m_listTitles; static unsigned int m_nbWindows; int fontHeight; @@ -175,14 +168,8 @@ class VISP_EXPORT vpDisplayOpenCV : public vpDisplay // private: //#ifndef DOXYGEN_SHOULD_SKIP_THIS // vpDisplayOpenCV(const vpDisplayOpenCV &) - // : vpDisplay(), - // #if (VISP_HAVE_OPENCV_VERSION < 0x020408) - // background(nullptr), col(nullptr), cvcolor(), font(nullptr), - // #else - // background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), - // fontScale(0.8f), - // #endif - // fontHeight(10), x_move(0), y_move(0) , move(false), + // : vpDisplay(), background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), + // fontScale(0.8f), fontHeight(10), x_move(0), y_move(0) , move(false), // x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), // x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), // x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), diff --git a/modules/gui/src/display/vpDisplayOpenCV.cpp b/modules/gui/src/display/vpDisplayOpenCV.cpp index 0ba15d1e68..5ab98348dc 100644 --- a/modules/gui/src/display/vpDisplayOpenCV.cpp +++ b/modules/gui/src/display/vpDisplayOpenCV.cpp @@ -101,11 +101,7 @@ unsigned int vpDisplayOpenCV::m_nbWindows = 0; */ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleType) : vpDisplay(), -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), -#else m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), -#endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), @@ -141,11 +137,7 @@ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleTyp vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, int x, int y, const std::string &title, vpScaleType scaleType) : vpDisplay(), -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), -#else m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), -#endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), @@ -175,11 +167,7 @@ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, int x, int y, const */ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleType) : -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), -#else m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), -#endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), @@ -211,11 +199,7 @@ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, vpScaleType scaleType) */ vpDisplayOpenCV::vpDisplayOpenCV(vpImage &I, int x, int y, const std::string &title, vpScaleType scaleType) : -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), -#else m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), -#endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), @@ -249,11 +233,7 @@ int main() */ vpDisplayOpenCV::vpDisplayOpenCV(int x, int y, const std::string &title) : -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), -#else m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), -#endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), @@ -309,11 +289,7 @@ int main() */ vpDisplayOpenCV::vpDisplayOpenCV() : -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - m_background(nullptr), col(nullptr), cvcolor(), font(nullptr), -#else m_background(), col(nullptr), cvcolor(), font(cv::FONT_HERSHEY_PLAIN), fontScale(0.8f), -#endif fontHeight(10), x_move(0), y_move(0), move(false), x_lbuttondown(0), y_lbuttondown(0), lbuttondown(false), x_mbuttondown(0), y_mbuttondown(0), mbuttondown(false), x_rbuttondown(0), y_rbuttondown(0), rbuttondown(false), x_lbuttonup(0), y_lbuttonup(0), lbuttonup(false), x_mbuttonup(0), y_mbuttonup(0), mbuttonup(false), x_rbuttonup(0), @@ -326,9 +302,6 @@ vpDisplayOpenCV::vpDisplayOpenCV() vpDisplayOpenCV::~vpDisplayOpenCV() { closeDisplay(); -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvReleaseImage(&m_background); -#endif } /*! @@ -388,15 +361,13 @@ void vpDisplayOpenCV::init(unsigned int w, unsigned int h, int x, int y, const s this->m_width = w / m_scale; this->m_height = h / m_scale; - if (x != -1) + if (x != -1) { this->m_windowXPosition = x; - if (y != -1) + } + if (y != -1) { this->m_windowYPosition = y; -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - int flags = CV_WINDOW_AUTOSIZE; -#else + } int flags = cv::WINDOW_AUTOSIZE; -#endif if (m_title.empty()) { if (!title.empty()) { @@ -426,19 +397,10 @@ void vpDisplayOpenCV::init(unsigned int w, unsigned int h, int x, int y, const s m_listTitles.push_back(m_title); } -/* Create the window*/ -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - if (cvNamedWindow(this->m_title.c_str(), flags) < 0) { - throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV was not built with a display device")); - } -#else + /* Create the window*/ cv::namedWindow(this->m_title, flags); -#endif -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvMoveWindow(this->m_title.c_str(), this->m_windowXPosition, this->m_windowYPosition); -#else cv::moveWindow(this->m_title.c_str(), this->m_windowXPosition, this->m_windowYPosition); -#endif + move = false; lbuttondown = false; mbuttondown = false; @@ -446,13 +408,9 @@ void vpDisplayOpenCV::init(unsigned int w, unsigned int h, int x, int y, const s lbuttonup = false; mbuttonup = false; rbuttonup = false; -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvSetMouseCallback(this->m_title.c_str(), on_mouse, this); - col = new CvScalar[vpColor::id_unknown]; -#else + cv::setMouseCallback(this->m_title, on_mouse, this); col = new cv::Scalar[vpColor::id_unknown]; -#endif /* Create color */ vpColor pcolor; // Predefined colors @@ -493,18 +451,10 @@ void vpDisplayOpenCV::init(unsigned int w, unsigned int h, int x, int y, const s pcolor = vpColor::darkGray; col[vpColor::id_darkGray] = CV_RGB(pcolor.R, pcolor.G, pcolor.B); -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - font = new CvFont; - cvInitFont(font, CV_FONT_HERSHEY_PLAIN, 0.70f, 0.70f); - CvSize fontSize; - int baseline; - cvGetTextSize("A", font, &fontSize, &baseline); -#else int thickness = 1; cv::Size fontSize; int baseline; fontSize = cv::getTextSize("A", font, fontScale, thickness, &baseline); -#endif fontHeight = fontSize.height + baseline; m_displayHasBeenInitialized = true; @@ -557,11 +507,7 @@ void vpDisplayOpenCV::setWindowPosition(int winx, int winy) if (m_displayHasBeenInitialized) { this->m_windowXPosition = winx; this->m_windowYPosition = winy; -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvMoveWindow(this->m_title.c_str(), winx, winy); -#else cv::moveWindow(this->m_title.c_str(), winx, winy); -#endif } else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); @@ -581,46 +527,6 @@ void vpDisplayOpenCV::setWindowPosition(int winx, int winy) void vpDisplayOpenCV::displayImage(const vpImage &I) { if (m_displayHasBeenInitialized) { -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - int depth = 8; - int channels = 3; - CvSize size = cvSize((int)this->m_width, (int)this->m_height); - if (m_background != nullptr) { - if (m_background->nChannels != channels || m_background->depth != depth || - m_background->height != (int)m_height || m_background->width != (int)m_width) { - if (m_background->nChannels != 0) - cvReleaseImage(&m_background); - m_background = cvCreateImage(size, depth, channels); - } - } - else { - m_background = cvCreateImage(size, depth, channels); - } - - if (m_scale == 1) { - for (unsigned int i = 0; i < m_height; i++) { - unsigned char *dst_24 = (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep); - for (unsigned int j = 0; j < m_width; j++) { - unsigned char val = I[i][j]; - *(dst_24++) = val; - *(dst_24++) = val; - *(dst_24++) = val; - } - } - } - else { - for (unsigned int i = 0; i < m_height; i++) { - unsigned char *dst_24 = (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep); - for (unsigned int j = 0; j < m_width; j++) { - unsigned char val = I[i * m_scale][j * m_scale]; - *(dst_24++) = val; - *(dst_24++) = val; - *(dst_24++) = val; - } - } - } - -#else int depth = CV_8U; int channels = 3; cv::Size size((int)m_width, (int)m_height); @@ -651,8 +557,6 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) } } } -#endif - } else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); @@ -678,56 +582,6 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpI unsigned int h) { if (m_displayHasBeenInitialized) { -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - int depth = 8; - int channels = 3; - CvSize size = cvSize((int)this->m_width, (int)this->m_height); - if (m_background != nullptr) { - if (m_background->nChannels != channels || m_background->depth != depth || - m_background->height != (int)m_height || m_background->width != (int)m_width) { - if (m_background->nChannels != 0) - cvReleaseImage(&m_background); - m_background = cvCreateImage(size, depth, channels); - } - } - else { - m_background = cvCreateImage(size, depth, channels); - } - - if (m_scale == 1) { - unsigned int i_min = (unsigned int)iP.get_i(); - unsigned int j_min = (unsigned int)iP.get_j(); - unsigned int i_max = std::min(i_min + h, m_height); - unsigned int j_max = std::min(j_min + w, m_width); - for (unsigned int i = i_min; i < i_max; i++) { - unsigned char *dst_24 = - (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); - for (unsigned int j = j_min; j < j_max; j++) { - unsigned char val = I[i][j]; - *(dst_24++) = val; - *(dst_24++) = val; - *(dst_24++) = val; - } - } - } - else { - int i_min = std::max((int)ceil(iP.get_i() / m_scale), 0); - int j_min = std::max((int)ceil(iP.get_j() / m_scale), 0); - int i_max = std::min((int)ceil((iP.get_i() + h) / m_scale), (int)m_height); - int j_max = std::min((int)ceil((iP.get_j() + w) / m_scale), (int)m_width); - for (int i = i_min; i < i_max; i++) { - unsigned char *dst_24 = - (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); - for (int j = j_min; j < j_max; j++) { - unsigned char val = I[i * m_scale][j * m_scale]; - *(dst_24++) = val; - *(dst_24++) = val; - *(dst_24++) = val; - } - } - } - -#else int depth = CV_8U; int channels = 3; cv::Size size((int)m_width, (int)m_height); @@ -766,7 +620,6 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpI } } } -#endif } else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); @@ -788,45 +641,6 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) { if (m_displayHasBeenInitialized) { -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - int depth = 8; - int channels = 3; - CvSize size = cvSize((int)this->m_width, (int)this->m_height); - if (m_background != nullptr) { - if (m_background->nChannels != channels || m_background->depth != depth || - m_background->height != (int)m_height || m_background->width != (int)m_width) { - if (m_background->nChannels != 0) - cvReleaseImage(&m_background); - m_background = cvCreateImage(size, depth, channels); - } - } - else { - m_background = cvCreateImage(size, depth, channels); - } - - if (m_scale == 1) { - for (unsigned int i = 0; i < m_height; i++) { - unsigned char *dst_24 = (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep); - for (unsigned int j = 0; j < m_width; j++) { - vpRGBa val = I[i][j]; - *(dst_24++) = val.B; - *(dst_24++) = val.G; - *(dst_24++) = val.R; - } - } - } - else { - for (unsigned int i = 0; i < m_height; i++) { - unsigned char *dst_24 = (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep); - for (unsigned int j = 0; j < m_width; j++) { - vpRGBa val = I[i * m_scale][j * m_scale]; - *(dst_24++) = val.B; - *(dst_24++) = val.G; - *(dst_24++) = val.R; - } - } - } -#else int depth = CV_8U; int channels = 3; cv::Size size((int)this->m_width, (int)this->m_height); @@ -857,7 +671,6 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) } } } -#endif } else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); @@ -882,55 +695,6 @@ void vpDisplayOpenCV::displayImage(const vpImage &I) void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpImagePoint &iP, unsigned int w, unsigned int h) { if (m_displayHasBeenInitialized) { -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - int depth = 8; - int channels = 3; - CvSize size = cvSize((int)this->m_width, (int)this->m_height); - if (m_background != nullptr) { - if (m_background->nChannels != channels || m_background->depth != depth || - m_background->height != (int)m_height || m_background->width != (int)m_width) { - if (m_background->nChannels != 0) - cvReleaseImage(&m_background); - m_background = cvCreateImage(size, depth, channels); - } - } - else { - m_background = cvCreateImage(size, depth, channels); - } - - if (m_scale == 1) { - unsigned int i_min = (unsigned int)iP.get_i(); - unsigned int j_min = (unsigned int)iP.get_j(); - unsigned int i_max = std::min(i_min + h, m_height); - unsigned int j_max = std::min(j_min + w, m_width); - for (unsigned int i = i_min; i < i_max; i++) { - unsigned char *dst_24 = - (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); - for (unsigned int j = j_min; j < j_max; j++) { - vpRGBa val = I[i][j]; - *(dst_24++) = val.B; - *(dst_24++) = val.G; - *(dst_24++) = val.R; - } - } - } - else { - int i_min = std::max((int)ceil(iP.get_i() / m_scale), 0); - int j_min = std::max((int)ceil(iP.get_j() / m_scale), 0); - int i_max = std::min((int)ceil((iP.get_i() + h) / m_scale), (int)m_height); - int j_max = std::min((int)ceil((iP.get_j() + w) / m_scale), (int)m_width); - for (int i = i_min; i < i_max; i++) { - unsigned char *dst_24 = - (unsigned char *)m_background->imageData + (int)(i * m_background->widthStep + j_min * 3); - for (int j = j_min; j < j_max; j++) { - vpRGBa val = I[i * m_scale][j * m_scale]; - *(dst_24++) = val.B; - *(dst_24++) = val.G; - *(dst_24++) = val.R; - } - } - } -#else int depth = CV_8U; int channels = 3; cv::Size size((int)this->m_width, (int)this->m_height); @@ -969,7 +733,6 @@ void vpDisplayOpenCV::displayImageROI(const vpImage &I, const vpImagePoi } } } -#endif } else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); @@ -996,19 +759,8 @@ void vpDisplayOpenCV::closeDisplay() delete[] col; col = nullptr; } -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - if (font != nullptr) { - delete font; - font = nullptr; - } -#endif if (m_displayHasBeenInitialized) { -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvDestroyWindow(this->m_title.c_str()); -#else cv::destroyWindow(this->m_title); -#endif - for (size_t i = 0; i < m_listTitles.size(); i++) { if (m_title == m_listTitles[i]) { m_listTitles.erase(m_listTitles.begin() + (long int)i); @@ -1030,13 +782,8 @@ void vpDisplayOpenCV::closeDisplay() void vpDisplayOpenCV::flushDisplay() { if (m_displayHasBeenInitialized) { -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvShowImage(this->m_title.c_str(), m_background); - cvWaitKey(5); -#else cv::imshow(this->m_title, m_background); cv::waitKey(5); -#endif } else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); @@ -1052,13 +799,8 @@ void vpDisplayOpenCV::flushDisplayROI(const vpImagePoint & /*iP*/, const unsigne const unsigned int /*height*/) { if (m_displayHasBeenInitialized) { -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvShowImage(this->m_title.c_str(), m_background); - cvWaitKey(5); -#else cv::imshow(this->m_title.c_str(), m_background); cv::waitKey(5); -#endif } else { throw(vpDisplayException(vpDisplayException::notInitializedError, "OpenCV not initialized")); @@ -1141,27 +883,15 @@ void vpDisplayOpenCV::displayText(const vpImagePoint &ip, const std::string &tex { if (m_displayHasBeenInitialized) { if (color.id < vpColor::id_unknown) { -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvPutText(m_background, text.c_str(), - cvPoint(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale + fontHeight)), font, - col[color.id]); -#else cv::putText(m_background, text, cv::Point(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale + fontHeight)), font, fontScale, col[color.id]); -#endif } else { cvcolor = CV_RGB(color.R, color.G, color.B); -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvPutText(m_background, text.c_str(), - cvPoint(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale + fontHeight)), font, - cvcolor); -#else cv::putText(m_background, text, cv::Point(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale + fontHeight)), font, fontScale, cvcolor); -#endif } } else { @@ -1197,11 +927,7 @@ void vpDisplayOpenCV::displayCircle(const vpImagePoint ¢er, unsigned int rad if (fill == false) { int cv_thickness = static_cast(thickness); -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvCircle(m_background, cvPoint(x, y), r, cv_color, cv_thickness); -#else cv::circle(m_background, cv::Point(x, y), r, cv_color, cv_thickness); -#endif } else { #if VISP_HAVE_OPENCV_VERSION >= 0x030000 @@ -1209,13 +935,9 @@ void vpDisplayOpenCV::displayCircle(const vpImagePoint ¢er, unsigned int rad #else int filled = CV_FILLED; #endif -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvCircle(m_background, cvPoint(x, y), r, cv_color, filled); -#else double opacity = static_cast(color.A) / 255.0; overlay([x, y, r, cv_color, filled](cv::Mat image) { cv::circle(image, cv::Point(x, y), r, cv_color, filled); }, opacity); -#endif } } else { @@ -1312,27 +1034,15 @@ void vpDisplayOpenCV::displayLine(const vpImagePoint &ip1, const vpImagePoint &i { if (m_displayHasBeenInitialized) { if (color.id < vpColor::id_unknown) { -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvLine(m_background, cvPoint(vpMath::round(ip1.get_u() / m_scale), vpMath::round(ip1.get_v() / m_scale)), - cvPoint(vpMath::round(ip2.get_u() / m_scale), vpMath::round(ip2.get_v() / m_scale)), col[color.id], - (int)thickness); -#else cv::line(m_background, cv::Point(vpMath::round(ip1.get_u() / m_scale), vpMath::round(ip1.get_v() / m_scale)), cv::Point(vpMath::round(ip2.get_u() / m_scale), vpMath::round(ip2.get_v() / m_scale)), col[color.id], (int)thickness); -#endif } else { cvcolor = CV_RGB(color.R, color.G, color.B); -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvLine(m_background, cvPoint(vpMath::round(ip1.get_u() / m_scale), vpMath::round(ip1.get_v() / m_scale)), - cvPoint(vpMath::round(ip2.get_u() / m_scale), vpMath::round(ip2.get_v() / m_scale)), cvcolor, - (int)thickness); -#else cv::line(m_background, cv::Point(vpMath::round(ip1.get_u() / m_scale), vpMath::round(ip1.get_v() / m_scale)), cv::Point(vpMath::round(ip2.get_u() / m_scale), vpMath::round(ip2.get_v() / m_scale)), cvcolor, (int)thickness); -#endif } } else { @@ -1351,27 +1061,15 @@ void vpDisplayOpenCV::displayPoint(const vpImagePoint &ip, const vpColor &color, if (m_displayHasBeenInitialized) { for (unsigned int i = 0; i < thickness; i++) { if (color.id < vpColor::id_unknown) { -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvLine(m_background, cvPoint(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale)), - cvPoint(vpMath::round(ip.get_u() / m_scale + thickness - 1), vpMath::round(ip.get_v() / m_scale)), - col[color.id], (int)thickness); -#else cv::line(m_background, cv::Point(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale)), cv::Point(vpMath::round(ip.get_u() / m_scale + thickness - 1), vpMath::round(ip.get_v() / m_scale)), col[color.id], (int)thickness); -#endif } else { cvcolor = CV_RGB(color.R, color.G, color.B); -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvLine(m_background, cvPoint(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale)), - cvPoint(vpMath::round(ip.get_u() / m_scale + thickness - 1), vpMath::round(ip.get_v() / m_scale)), - cvcolor, (int)thickness); -#else cv::line(m_background, cv::Point(vpMath::round(ip.get_u() / m_scale), vpMath::round(ip.get_v() / m_scale)), cv::Point(vpMath::round(ip.get_u() / m_scale + thickness - 1), vpMath::round(ip.get_v() / m_scale)), cvcolor, (int)thickness); -#endif } } } @@ -1413,11 +1111,7 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, unsigned int if (fill == false) { int cv_thickness = static_cast(thickness); -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, cv_thickness); -#else cv::rectangle(m_background, cv::Point(left, top), cv::Point(right, bottom), cv_color, cv_thickness); -#endif } else { #if VISP_HAVE_OPENCV_VERSION >= 0x030000 @@ -1425,15 +1119,11 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, unsigned int #else int filled = CV_FILLED; #endif -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); -#else double opacity = static_cast(color.A) / 255.0; overlay([left, top, right, bottom, cv_color, filled](cv::Mat image) { cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); }, opacity); -#endif } } else { @@ -1472,11 +1162,7 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, const vpImag if (fill == false) { int cv_thickness = static_cast(thickness); -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, cv_thickness); -#else cv::rectangle(m_background, cv::Point(left, top), cv::Point(right, bottom), cv_color, cv_thickness); -#endif } else { #if VISP_HAVE_OPENCV_VERSION >= 0x030000 @@ -1484,15 +1170,11 @@ void vpDisplayOpenCV::displayRectangle(const vpImagePoint &topLeft, const vpImag #else int filled = CV_FILLED; #endif -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); -#else double opacity = static_cast(color.A) / 255.0; overlay([left, top, right, bottom, cv_color, filled](cv::Mat image) { cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); }, opacity); -#endif } } else { @@ -1530,11 +1212,7 @@ void vpDisplayOpenCV::displayRectangle(const vpRect &rectangle, const vpColor &c if (fill == false) { int cv_thickness = static_cast(thickness); -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, cv_thickness); -#else cv::rectangle(m_background, cv::Point(left, top), cv::Point(right, bottom), cv_color, cv_thickness); -#endif } else { #if VISP_HAVE_OPENCV_VERSION >= 0x030000 @@ -1542,15 +1220,11 @@ void vpDisplayOpenCV::displayRectangle(const vpRect &rectangle, const vpColor &c #else int filled = CV_FILLED; #endif -#if VISP_HAVE_OPENCV_VERSION < 0x020408 - cvRectangle(m_background, cvPoint(left, top), cvPoint(right, bottom), cv_color, filled); -#else double opacity = static_cast(color.A) / 255.0; overlay([left, top, right, bottom, cv_color, filled](cv::Mat image) { cv::rectangle(image, cv::Point(left, top), cv::Point(right, bottom), cv_color, filled); }, opacity); -#endif } } else { @@ -1596,12 +1270,9 @@ bool vpDisplayOpenCV::getClick(bool blocking) ret = true; rbuttondown = false; } - if (blocking) -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvWaitKey(10); -#else + if (blocking) { cv::waitKey(10); -#endif + } } while (ret == false && blocking == true); } else { @@ -1664,12 +1335,9 @@ bool vpDisplayOpenCV::getClick(vpImagePoint &ip, bool blocking) ip.set_v(v); rbuttondown = false; } - if (blocking) -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvWaitKey(10); -#else + if (blocking) { cv::waitKey(10); -#endif + } } while (ret == false && blocking == true); } else { @@ -1736,12 +1404,9 @@ bool vpDisplayOpenCV::getClick(vpImagePoint &ip, vpMouseButton::vpMouseButtonTyp button = vpMouseButton::button3; rbuttondown = false; } - if (blocking) -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvWaitKey(10); -#else + if (blocking) { cv::waitKey(10); -#endif + } } while (ret == false && blocking == true); } else { @@ -1810,12 +1475,9 @@ bool vpDisplayOpenCV::getClickUp(vpImagePoint &ip, vpMouseButton::vpMouseButtonT button = vpMouseButton::button3; rbuttonup = false; } - if (blocking) -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - cvWaitKey(10); -#else + if (blocking) { cv::waitKey(10); -#endif + } } while (ret == false && blocking == true); } else { @@ -1838,77 +1500,49 @@ void vpDisplayOpenCV::on_mouse(int event, int x, int y, int /*flags*/, void *dis { vpDisplayOpenCV *disp = static_cast(display); switch (event) { -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - case CV_EVENT_MOUSEMOVE: -#else case cv::EVENT_MOUSEMOVE: -#endif { disp->move = true; disp->x_move = x; disp->y_move = y; break; } -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - case CV_EVENT_LBUTTONDOWN: -#else case cv::EVENT_LBUTTONDOWN: -#endif { disp->lbuttondown = true; disp->x_lbuttondown = x; disp->y_lbuttondown = y; break; } -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - case CV_EVENT_MBUTTONDOWN: -#else case cv::EVENT_MBUTTONDOWN: -#endif { disp->mbuttondown = true; disp->x_mbuttondown = x; disp->y_mbuttondown = y; break; } -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - case CV_EVENT_RBUTTONDOWN: -#else case cv::EVENT_RBUTTONDOWN: -#endif { disp->rbuttondown = true; disp->x_rbuttondown = x; disp->y_rbuttondown = y; break; } -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - case CV_EVENT_LBUTTONUP: -#else case cv::EVENT_LBUTTONUP: -#endif { disp->lbuttonup = true; disp->x_lbuttonup = x; disp->y_lbuttonup = y; break; } -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - case CV_EVENT_MBUTTONUP: -#else case cv::EVENT_MBUTTONUP: -#endif { disp->mbuttonup = true; disp->x_mbuttonup = x; disp->y_mbuttonup = y; break; } -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - case CV_EVENT_RBUTTONUP: -#else case cv::EVENT_RBUTTONUP: -#endif { disp->rbuttonup = true; disp->x_rbuttonup = x; @@ -1946,11 +1580,7 @@ bool vpDisplayOpenCV::getKeyboardEvent(bool blocking) else delay = 10; -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - int key_pressed = cvWaitKey(delay); -#else int key_pressed = cv::waitKey(delay); -#endif if (key_pressed == -1) return false; @@ -1989,11 +1619,7 @@ bool vpDisplayOpenCV::getKeyboardEvent(std::string &key, bool blocking) else delay = 10; -#if (VISP_HAVE_OPENCV_VERSION < 0x020408) - int key_pressed = cvWaitKey(delay); -#else int key_pressed = cv::waitKey(delay); -#endif if (key_pressed == -1) return false; else { @@ -2137,7 +1763,6 @@ unsigned int vpDisplayOpenCV::getScreenHeight() return height; } -#if VISP_HAVE_OPENCV_VERSION >= 0x020408 /*! * Initialize display overlay layer for transparency. * \param overlay_function : Overlay function @@ -2163,7 +1788,6 @@ void vpDisplayOpenCV::overlay(std::function overlay_function, d cv::addWeighted(overlay, opacity, m_background, 1.0 - opacity, 0.0, m_background); } } -#endif #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpDisplayOpenCV.cpp.o) has no symbols diff --git a/tutorial/tracking/keypoint/tutorial-klt-tracker.cpp b/tutorial/tracking/keypoint/tutorial-klt-tracker.cpp index f3f97493bb..6d7a61fa1d 100644 --- a/tutorial/tracking/keypoint/tutorial-klt-tracker.cpp +++ b/tutorial/tracking/keypoint/tutorial-klt-tracker.cpp @@ -24,8 +24,8 @@ int main(int argc, const char *argv[]) opt_subsample = static_cast(std::atoi(argv[i + 1])); else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") { std::cout << "Usage: " << argv[0] - << " [--videoname

This is a brief description of training process which has been used to get res10_300x300_ssd_iter_140000.caffemodel. -The model was created with SSD framework using ResNet-10 like architecture as a backbone. Channels count in ResNet-10 convolution layers was -significantly dropped (2x- or 4x- fewer channels). The model was trained in Caffe framework on some huge and available online dataset. +The model was created with SSD framework using ResNet-10 like architecture as a backbone. Channels count in ResNet-10 +convolution layers was significantly dropped (2x- or 4x- fewer channels). The model was trained in Caffe framework on +some huge and available online dataset.
-More specifically, the model used (`opencv_face_detector_uint8.pb`) has been quantized (with the TensorFlow library) on 8-bit unsigned int to -reduce the size of the training model (2.7 mo vs 10.7 mo for `res10_300x300_ssd_iter_140000.caffemodel`). +More specifically, the model used (`opencv_face_detector_uint8.pb`) has been quantized (with the TensorFlow library) +on 8-bit unsigned int to reduce the size of the training model (2.7 mo vs 10.7 mo for +`res10_300x300_ssd_iter_140000.caffemodel`). The following lines permit to create the DNN object detector: @@ -179,25 +182,32 @@ The following lines permit to create the DNN object detector: To construct `netConfig` object some configuration parameters of the DNN are required: - `confThresh`, which is the confidence threshold used to filter the detections after inference -- `nmsThresh`, which is the Non-Maximum Threshold used to filter multiple detections that can occur approximatively at the same locations +- `nmsThresh`, which is the Non-Maximum Threshold used to filter multiple detections that can occur approximatively at + the same locations - `labelFile`, which is the path towards the file containing the list of classes the DNN can detect -- `inputWidth` and `inputHeight`, which are the dimensions to resize the input image into the blob that is fed in entry of the network -- `filterThresh`, which is a double that, if greater than 0., indicates that the user wants to perform an additional filtering on the detection outputs based on the - size of these detections +- `inputWidth` and `inputHeight`, which are the dimensions to resize the input image into the blob that is fed in entry + of the network +- `filterThresh`, which is a double that, if greater than 0., indicates that the user wants to perform an additional + filtering on the detection outputs based on the size of these detections - `meanR`, `meanG` and `meanB` are the values used for mean subtraction - `scaleFactor` is used to normalize the data range -- `swapRB` should be set to `true` when the model has been trained on RGB data. Since OpenCV used the BGR convention, R and B channel should be swapped -- `dnn_type` is the type of parsing method to use to parse the DNN raw results. See vpDetectorDNNOpenCV::DNNResultsParsingType to determine - which parsing methods are available -- `model` is the network trained weights, `config` is the network topology description and `framework` is the weights framework. +- `swapRB` should be set to `true` when the model has been trained on RGB data. Since OpenCV used the BGR convention, + R and B channel should be swapped +- `dnn_type` is the type of parsing method to use to parse the DNN raw results. See + vpDetectorDNNOpenCV::DNNResultsParsingType to determine which parsing methods are available +- `model` is the network trained weights, `config` is the network topology description and `framework` is the weights + framework. -Alternatively, if ViSP has been compiled with the NLOHMANN JSON library, one can initialize the `vpDetectorDNNOpenCV` object using the following method: +Alternatively, if ViSP has been compiled with the NLOHMANN JSON library, one can initialize the `vpDetectorDNNOpenCV` +object using the following method: \snippet tutorial-dnn-object-detection-live.cpp DNN json -You can directly refer to the OpenCV model zoo for the parameters values. +You can directly refer to the OpenCV model zoo +for the parameters values. -After setting the correct parameters, if you want to get the data as a map, where the keys will be the class names (or ID if no label file was given), +After setting the correct parameters, if you want to get the data as a map, where the keys will be the class names +(or ID if no label file was given), you can easily detect object in an image with: \snippet tutorial-dnn-object-detection-live.cpp DNN object detection map mode @@ -218,7 +228,8 @@ or for a non-sorted vector with: \subsection dnn_usecase_general Generic usage -The default behavior is to detect human faces, but you can input another model to detect the objects you want. To see which are the options, run: +The default behavior is to detect human faces, but you can input another model to detect the objects you want. To see +which are the options, run: ``` $ cd $VISP_WS/visp-build/tutorial/detection/dnn $ ./tutorial-dnn-object-detection-live --help @@ -226,7 +237,8 @@ $ ./tutorial-dnn-object-detection-live --help \subsection dnn_usecase_face_detection Face detection -The default behavior is to detect human faces using a model provided by OpenCV and learned over a ResNet 10 network. If you have a laptop, simply run: +The default behavior is to detect human faces using a model provided by OpenCV and learned over a ResNet 10 network. +If you have a laptop, simply run: ``` $ cd $VISP_WS/visp-build/tutorial/detection/dnn $ ./tutorial-dnn-object-detection-live @@ -247,8 +259,10 @@ $ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config \subsection dnn_models_coco COCO dataset objects detection -[COCO](https://cocodataset.org) is a large-scale object detection, segmentation, and captioning dataset. It contains over 330 000 images, each annotated with 80 object categories. -In the following sections, we show how to use the DNN models learned with the different networks, to detect objects among the list of 80 objects in the COCO dataset. +[COCO](https://cocodataset.org) is a large-scale object detection, segmentation, and captioning dataset. It contains +over 330 000 images, each annotated with 80 object categories. +In the following sections, we show how to use the DNN models learned with the different networks, to detect objects +among the list of 80 objects in the COCO dataset. \subsubsection dnn_supported_faster_rcnn Faster-RCNN @@ -425,10 +439,11 @@ If you want to train your own YoloV5 model, please refer to the \subsubsection dnn_supported_yolov7 Yolo v7 -To be able to use `YoloV7` with the class `vpDetectorDNNOpenCV`, you must first download the weights (`yolov7-tiny.pt`) in the Pytorch format from -[here](https://github.com/WongKinYiu/yolov7/releases/download/v0.1/yolov7-tiny.pt). +To be able to use `YoloV7` with the class `vpDetectorDNNOpenCV`, you must first download the weights (`yolov7-tiny.pt`) +in the Pytorch format from [here](https://github.com/WongKinYiu/yolov7/releases/download/v0.1/yolov7-tiny.pt). -Then, convert it in ONNX format using the `export.py` script that you can find on the [YoloV7 repo](https://github.com/WongKinYiu/yolov7) with the following arguments: +Then, convert it in ONNX format using the `export.py` script that you can find on the +[YoloV7 repo](https://github.com/WongKinYiu/yolov7) with the following arguments: ``` $ python3 export.py --weights ../weights/yolov7-tiny.pt --grid --simplify --topk-all 100 --iou-thres 0.65 --conf-thres 0.35 --img-size 640 640 --max-wh 640 ``` diff --git a/doc/tutorial/detection_dnn/tutorial-detection-tensorrt.dox b/doc/tutorial/detection_dnn/tutorial-detection-tensorrt.dox index d669bc8703..aff7c62955 100644 --- a/doc/tutorial/detection_dnn/tutorial-detection-tensorrt.dox +++ b/doc/tutorial/detection_dnn/tutorial-detection-tensorrt.dox @@ -4,16 +4,15 @@ \tableofcontents \section dnn_trt_intro Introduction -This tutorial shows how to run object detection inference using NVIDIA TensorRT inference SDK. +This tutorial shows how to run object detection inference using NVIDIA +TensorRT inference SDK. -For this tutorial, you'll need `ssd_mobilenet.onnx` pre-trained model, and `pascal-voc-labels.txt` label's file containing the corresponding labels. +For this tutorial, you'll need `ssd_mobilenet.onnx` pre-trained model, and `pascal-voc-labels.txt` label's file +containing the corresponding labels. These files can be found in visp-images dataset. -Note that the source code described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/detection/dnn -\endcode +Note that all the material (source code and network mode) described in this tutorial is part of ViSP source code +(in `tutorial/detection/dnn` folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/detection/dnn. Before running this tutorial, you need to install: - CUDA (version 10.2 or higher) @@ -23,7 +22,8 @@ Before running this tutorial, you need to install: Installation instructions are provided in \ref dnn_trt_prereq section. -The tutorial was tested on multiple hardwares of NVIDIA. The following table details the versions of CUDA and TensorRT used for each GPU: +The tutorial was tested on multiple hardwares of NVIDIA. The following table details the versions of CUDA and TensorRT +used for each GPU: | NVIDIA hardware | OS | CUDA | TensorRT | CuDNN | | ------------- | ------------- | ------------- | ------------- | ------------- | @@ -31,7 +31,8 @@ The tutorial was tested on multiple hardwares of NVIDIA. The following table det | GeForce GTX 1080 | Ubuntu 16.04 | 11.0 | 8.0 GA | 8.0 | | Quadro RTX 6000 | Ubuntu 18.04 | 11.3 | 8.0 GA Update 1 | 8.2 | -\note Issues were encountered when using TensorRT 8.2 EA with CUDA 11.3 on NVIDIA Quadro RTX 6000, the tutorial didn't work as expected. There were plenty of bounding boxes in any given image. +\note Issues were encountered when using TensorRT 8.2 EA with CUDA 11.3 on NVIDIA Quadro RTX 6000, the tutorial didn't +work as expected. There were plenty of bounding boxes in any given image. \section dnn_trt_prereq Prerequisites \subsection dnn_trt_cuda_install Install CUDA @@ -52,7 +53,7 @@ $ cat /usr/local/cuda/version.{txt,json} "version" : "11.3.20210326" }, \endcode -Here it shows that CUDA toolkit 11.3 is installed. +Here it shows that CUDA toolkit 11.3 is installed. \note We recommend that NVidia CUDA Driver and CUDA Toolkit have the same version. - To install NVidia CUDA Driver and Toolkit on your machine, please follow this step-by-step guide. @@ -70,7 +71,8 @@ $ sudo dpkg -i libcudnn8_8.2.0.53-1+cuda11.3_amd64.deb TensorRT is a C++ library that facilitates high-performance inference on NVIDIA GPUs. To download and install TensorRT, please follow this step-by-step guide. -Let us consider the installation of `TensorRT 8.0 GA Update 1 for x86_64 Architecture`. In that case you need to download "TensorRT 8.0 GA Update 1 for Linux x86_64 and CUDA 11.0, CUDA 11.1, CUDA 11.2, 11.3" TAR Package and extract its content in `VISP_WS`. +Let us consider the installation of `TensorRT 8.0 GA Update 1 for x86_64 Architecture`. In that case you need to +download "TensorRT 8.0 GA Update 1 for Linux x86_64 and CUDA 11.0, CUDA 11.1, CUDA 11.2, 11.3" TAR Package and extract its content in `VISP_WS`. ``` $ ls $VISP_WS TensorRT-8.0.3.4 ... @@ -103,7 +105,8 @@ $ python3 -m pip install onnx_graphsurgeon-0.3.10-py2.py3-none-any.whl ``` \subsection dnn_trt_opencv_install Install OpenCV from source -To be able to run the tutorial, you should install OpenCV from source, since some extra modules are required (`cudev`, `cudaarithm` and `cudawarping` are not included in `libopencv-contrib-dev` package). +To be able to run the tutorial, you should install OpenCV from source, since some extra modules are required +(`cudev`, `cudaarithm` and `cudawarping` are not included in `libopencv-contrib-dev` package). To do so, proceed as follows: - In `VISP_WS`, clone `opencv` and `opencv_contrib` repos: @@ -127,7 +130,8 @@ $ cmake -DOPENCV_EXTRA_MODULES_PATH=../../opencv_contrib/modules \ -DBUILD_opencv_cudawarping=ON \ -DCMAKE_INSTALL_PREFIX=$VISP_WS/opencv/install ../ \endcode -Note here that installation folder is set to `$VISP_WS/opencv/install` instead of the default `/usr/local`. This allows to preserve any other existing OpenCV installation on your machine. +Note here that installation folder is set to `$VISP_WS/opencv/install` instead of the default `/usr/local`. +This allows to preserve any other existing OpenCV installation on your machine. - Note that if you want a more advanced way to configure the build process, you can use `ccmake`: \code @@ -143,7 +147,8 @@ $ grep cudaarithm version_string.tmp $ grep cudawarping version_string.tmp " To be built: ... cudawarping ... \endverbatim -If this is not the case, it means that something is wrong, either in CUDA installation, either in OpenCV configuration with `cmake`. +If this is not the case, it means that something is wrong, either in CUDA installation, either in OpenCV configuration +with `cmake`. - Launch build process: \code @@ -158,8 +163,9 @@ export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$VISP_WS/opencv/install/lib \section dnn_trt_visp Build ViSP with TensorRT support -Next step is here to build ViSP from source enabling TensorRT support. -As described in \ref install_ubuntu_visp_get_source, we suppose here that you have ViSP source code in ViSP workspace folder: `$VISP_WS`. +Next step is here to build ViSP from source enabling TensorRT support. +As described in \ref install_ubuntu_visp_get_source, we suppose here that you have ViSP source code in ViSP workspace +folder: `$VISP_WS`. If you follow \ref dnn_trt_prereq, you should also find TensorRT and OpenCV in the same workspace. \code @@ -167,7 +173,8 @@ $ ls $VISP_WS visp opencv TensorRT-8.0.3.4 \endcode -Now to ensure that ViSP is build TensorRT, create and enter build folder before configuring ViSP with TensorRT and OpenCV path +Now to ensure that ViSP is build TensorRT, create and enter build folder before configuring ViSP with TensorRT and +OpenCV path \code $ mkdir visp-build; cd visp-build $ cmake ../visp \ @@ -176,7 +183,8 @@ $ cmake ../visp \ \endcode \section dnn_trt_example Tutorial description -In the following section is a detailed description of the tutorial. The complete source code is available in tutorial-dnn-tensorrt-live.cpp file. +In the following section is a detailed description of the tutorial. The complete source code is available in +tutorial-dnn-tensorrt-live.cpp file. \subsection header_files Include header files Include header files for required extra modules to handle CUDA. @@ -192,7 +200,8 @@ Include TensorRT header files. \subsection preprocessing Pre-processing Prepare input image for inference with OpenCV. -First, upload image to GPU, resize it to match model's input dimensions, normalize with `meanR` `meanG` `meanB` being the values used for mean substraction. +First, upload image to GPU, resize it to match model's input dimensions, normalize with `meanR` `meanG` `meanB` being +the values used for mean substraction. Transform data to tensor (copy data to channel by channel to `gpu_input`). In the case of `ssd_mobilenet.onnx`, the input dimension is 1x3x300x300. \snippet tutorial-dnn-tensorrt-live.cpp Preprocess image @@ -206,9 +215,11 @@ In the case of `ssd_mobilenet.onnx`, there is 2 outputs: In fact, the model will output 3000 guesses of boxes (bounding boxes) with 21 scores each (1 score for each class). The result of the inference being on the GPU, we should first proceed by copying it to the CPU. -Post processing consists of filtering the predictions where we're not sure about the class detected and then merging multiple detections that can occur approximately at the same locations. +Post processing consists of filtering the predictions where we're not sure about the class detected and then merging +multiple detections that can occur approximately at the same locations. `confThresh` is the confidence threshold used to filter the detections after inference. -`nmsThresh` is the Non-Maximum Threshold. It is used to merge multiple detections being in the same location approximately. +`nmsThresh` is the Non-Maximum Threshold. It is used to merge multiple detections being in the same location +approximately. \snippet tutorial-dnn-tensorrt-live.cpp PostProcess results \subsection parseOnnx Parse ONNX Model @@ -221,13 +232,16 @@ Parse ONNX model. `context` is used for executing inference. To parse ONNX model, we should first proceed by initializing TensorRT **Context** and **Engine**. -To do this, we should create an instance of **Builder**. With **Builder**, we can create **Network** that can create the **Parser**. +To do this, we should create an instance of **Builder**. With **Builder**, we can create **Network** that can create +the **Parser**. -If we already have the GPU inference engine loaded once, it will be serialized and saved in a cache file (with .engine extension). In this case, -the engine file will be loaded, then inference runtime created, engine and context loaded. +If we already have the GPU inference engine loaded once, it will be serialized and saved in a cache file +(with .engine extension). In this case, the engine file will be loaded, then inference runtime created, engine and +context loaded. \snippet tutorial-dnn-tensorrt-live.cpp ParseOnnxModel engine exists -Otherwise, we should parse the ONNX model (for the first time only), create an instance of builder. The builder can be configured to select the amount of GPU memory to be used for tactic selection or FP16/INT8 modes. +Otherwise, we should parse the ONNX model (for the first time only), create an instance of builder. The builder can be +configured to select the amount of GPU memory to be used for tactic selection or FP16/INT8 modes. Create **engine** and **context** to be used in the main pipeline, and serialize and save the engine for later use. \snippet tutorial-dnn-tensorrt-live.cpp ParseOnnxModel engine does not exist @@ -250,8 +264,10 @@ Create a grabber to retrieve image from webcam (or external camera) or read imag \snippet tutorial-dnn-tensorrt-live.cpp Main loop \section tutorial_usage Usage -To use this tutorial, you need an USB webcam and you should have downloaded an **onnx** file of a model with its corresponding labels in *txt* file format. -To start, you may download the **ssd_mobilenet.onnx** model and **pascal-voc-labels.txt** file from here or install \ref install_ubuntu_dataset cloning Github repository. +To use this tutorial, you need an USB webcam and you should have downloaded an **onnx** file of a model with its +corresponding labels in *txt* file format. To start, you may download the **ssd_mobilenet.onnx** model and +**pascal-voc-labels.txt** file from here or install +\ref install_ubuntu_dataset cloning Github repository. To see the options, run: \code diff --git a/doc/tutorial/image/tutorial-grabber.dox b/doc/tutorial/image/tutorial-grabber.dox index 42ab0f4bcf..d74ef6b3aa 100644 --- a/doc/tutorial/image/tutorial-grabber.dox +++ b/doc/tutorial/image/tutorial-grabber.dox @@ -8,24 +8,27 @@ In this tutorial you will learn how to grab images with ViSP, either from cameras or from a video stream. -Grabbing images from a real camera is only possible if you have installed the corresponding 3rd party. The complete list of 3rd parties supported by ViSP and dedicated to framegrabbing is given here. From this page you will also found useful information to install these 3rd parties. +Grabbing images from a real camera is only possible if you have installed the corresponding 3rd party. The complete +list of 3rd parties supported by ViSP and dedicated to framegrabbing is given +here. From this page you will also found useful information to +install these 3rd parties. -All the material (source code and videos) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\verbatim -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/grabber -\endverbatim +Note that all the material (source code and videos) described in this tutorial is part of ViSP source code +(in `tutorial/grabber` folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/grabber. \section grabber-camera-flycap Frame grabbing using FlyCapture SDK -After ViSP 3.0.0, we introduce vpFlyCaptureGrabber class, a wrapper over PointGrey FlyCapture SDK that allows to grab images from any PointGrey camera. This grabber was tested under Ubuntu and Windows with the following cameras: +After ViSP 3.0.0, we introduce vpFlyCaptureGrabber class, a wrapper over PointGrey FlyCapture SDK that allows to grab +images from any PointGrey camera. This grabber was tested under Ubuntu and Windows with the following cameras: - Flea3 USB 3.0 cameras (FL3-U3-32S2M-CS, FL3-U3-13E4C-C) - Flea2 firewire camera (FL2-03S2C) - Dragonfly2 firewire camera (DR2-COL) It should also work with GigE PGR cameras. -The following example also available in tutorial-grabber-flycapture.cpp shows how to use vpFlyCaptureGrabber to capture grey level images from a PointGrey camera under Ubuntu or Windows. The following example suppose that a window renderer (libX11 on Ubuntu or GDI on Windows) and FlyCapture SDK 3rd party are available throw VISP. +The following example also available in tutorial-grabber-flycapture.cpp shows how to use vpFlyCaptureGrabber to capture +grey level images from a PointGrey camera under Ubuntu or Windows. The following example suppose that a window renderer +(libX11 on Ubuntu or GDI on Windows) and FlyCapture SDK 3rd party are available throw VISP. \subsection grabber-camera-flycap-src Source code explained \include tutorial-grabber-flycapture.cpp @@ -35,8 +38,9 @@ Here after we explain the source code. First an instance of the frame grabber is created. \snippet tutorial-grabber-flycapture.cpp vpFlyCaptureGrabber construction -Once the grabber is created, we turn auto shutter and auto gain on and set the camera image size, color coding, and framerate. -These settings are enclosed in a try/catch to be able to continue if one of these settings are not supported by the camera. +Once the grabber is created, we turn auto shutter and auto gain on and set the camera image size, color coding, and +framerate. These settings are enclosed in a try/catch to be able to continue if one of these settings are not supported +by the camera. \snippet tutorial-grabber-flycapture.cpp vpFlyCaptureGrabber settings Then the grabber is initialized using: @@ -50,7 +54,8 @@ Then we enter in a while loop where image acquisition is simply done by: This image is then displayed using libX11 or GDI renderer: \snippet tutorial-grabber-flycapture.cpp vpFlyCaptureGrabber display -Depending on the command line options we are recording a sequence of images, or single shot images. We are also waiting for a non blocking mouse event to quit the while loop. +Depending on the command line options we are recording a sequence of images, or single shot images. We are also waiting +for a non blocking mouse event to quit the while loop. \snippet tutorial-grabber-flycapture.cpp vpFlyCaptureGrabber click to exit \subsection grabber-camera-flycap-use How to acquire images @@ -74,7 +79,9 @@ To grab a sequence of images, you may rather use: \section grabber-camera-dc1394 Frame grabbing using libdc1394 SDK -The next example also available in tutorial-grabber-1394.cpp shows how to use a framegrabber to acquire color images from a firewire or USB3 camera under Unix. The following example suppose that libX11 and libdc1394-2 3rd party are available. +The next example also available in tutorial-grabber-1394.cpp shows how to use a framegrabber to acquire color images +from a firewire or USB3 camera under Unix. The following example suppose that libX11 and libdc1394-2 3rd party are +available. \subsection grabber-camera-dc1394-src Source code explained @@ -83,13 +90,15 @@ The source code is the following: Here after we explain the new lines that are introduced. -First an instance of the frame grabber is created. During the creating a bus reset is send. If you don't want to reset the firewire bus, just turn reset to false. +First an instance of the frame grabber is created. During the creating a bus reset is send. If you don't want to reset +the firewire bus, just turn reset to false. \snippet tutorial-grabber-1394.cpp vp1394TwoGrabber construction Once the grabber is created, we set the camera image size, color coding, and framerate. \snippet tutorial-grabber-1394.cpp vp1394TwoGrabber settings -Note that here you can specify some other settings such as the firewire transmission speed. For a more complete list of settings see vp1394TwoGrabber class. +Note that here you can specify some other settings such as the firewire transmission speed. For a more complete list of +settings see vp1394TwoGrabber class. \code g.setIsoTransmissionSpeed(vp1394TwoGrabber::vpISO_SPEED_800); \endcode @@ -102,10 +111,12 @@ From now the color image \c I is also initialized with the size corresponding to Then we enter in a while loop where image acquisition is simply done by: \snippet tutorial-grabber-1394.cpp vp1394TwoGrabber acquire -As in the previous example, depending on the command line options we are recording a sequence of images, or single shot images. We are also waiting for a non blocking mouse event to quit the while loop. +As in the previous example, depending on the command line options we are recording a sequence of images, or single shot +images. We are also waiting for a non blocking mouse event to quit the while loop. \snippet tutorial-grabber-1394.cpp vp1394TwoGrabber click to exit -In the previous example we use vp1394TwoGrabber class that works for firewire cameras under Unix. If you are under Windows, you may use vp1394CMUGrabber class. A similar example is provided in tutorial-grabber-CMU1394.cpp. +In the previous example we use vp1394TwoGrabber class that works for firewire cameras under Unix. If you are under +Windows, you may use vp1394CMUGrabber class. A similar example is provided in tutorial-grabber-CMU1394.cpp. \subsection grabber-camera-dc1394-use How to acquire images @@ -128,7 +139,8 @@ To grab a sequence of images, you may rather use: \section grabber-camera-v4l2 Frame grabbing using libv4l2 SDK -If you want to grab images from an usb camera under Unix, you may use vpV4l2Grabber class that is a wrapper over Video For Linux SDK. To this end libv4l should be installed. An example is provided in tutorial-grabber-v4l2.cpp. +If you want to grab images from an usb camera under Unix, you may use vpV4l2Grabber class that is a wrapper over Video +For Linux SDK. To this end libv4l should be installed. An example is provided in tutorial-grabber-v4l2.cpp. \subsection grabber-camera-v4l2-use How to acquire images @@ -151,7 +163,8 @@ To grab a sequence of images, you may rather use: \section grabber-camera-pylon Frame grabbing using Pylon SDK -It is also possible to grab images using Pylon, the SDK for Basler cameras. You may find an example in tutorial-grabber-basler-pylon.cpp. +It is also possible to grab images using Pylon, the SDK for Basler cameras. You may find an example in +tutorial-grabber-basler-pylon.cpp. \subsection grabber-camera-pylon-use How to acquire images @@ -174,7 +187,8 @@ To grab a sequence of images, you may rather use: \section grabber-camera-realsense Frame grabbing using Realsense SDK -It is also possible to grab images using librealsense, the SDK provided for Intel Realsense RDB-D cameras. You may find an example in tutorial-grabber-realsense.cpp. +It is also possible to grab images using librealsense, the SDK provided for Intel Realsense RDB-D cameras. You may +find an example in tutorial-grabber-realsense.cpp. \subsection grabber-camera-realsense-use How to acquire images @@ -205,12 +219,14 @@ To acquire images from 2 T265 devices with serial numbers 11622110511 and 116221 \code ./tutorial-grabber-multiple-realsense --T265 11622110511 --T265 11622110433 \endcode -To acquire images from 1 T265 device (Serial Number:11622110511) and 1 D435 device (Serial Number: 752112070408), you may use: +To acquire images from 1 T265 device (Serial Number:11622110511) and 1 D435 device (Serial Number: 752112070408), +you may use: \code ./tutorial-grabber-multiple-realsense --T265 11622110511 --D435 752112070408 \endcode -\note There is getRealSense2Info.cpp in `example/device/framegrabber` folder that could be used to get the device serial number. +\note There is getRealSense2Info.cpp in `example/device/framegrabber` folder that could be used to get the device +serial number. \verbatim $ ./getRealSense2Info RealSense characteristics: @@ -227,7 +243,9 @@ Intel RealSense T265 11622110409 0.2.0.951 \section grabber-camera-structure Frame grabbing using Occipital Structure SDK -If you have a Structure Core RGB-D camera, it is also possible to grab images using `libStructure` the cross-platform library that comes with Occipital Structure SDK. You may find an example in tutorial-grabber-structure-core.cpp. It allows to save visible and depth images. +If you have a Structure Core RGB-D camera, it is also possible to grab images using `libStructure` the cross-platform +library that comes with Occipital Structure SDK. You may find an example in tutorial-grabber-structure-core.cpp. It +allows to save visible and depth images. \subsection grabber-camera-structure-use How to acquire images @@ -250,7 +268,8 @@ To grab a sequence of images, you may rather use: \section grabber-rgbd-D435-structurecore RGBD frame grabbing from RealSense D435 and Structure Core -If you have both Intel RealSense D435 and Occipital Structure Core, you can acquire color and depth frames simultaneously from both sensors. +If you have both Intel RealSense D435 and Occipital Structure Core, you can acquire color and depth frames +simultaneously from both sensors. Once tutorial-grabber-rgbd-D435-structurecore.cpp is built, you just need to run: \code @@ -290,7 +309,8 @@ To grab a sequence of images, you may rather use: \section grabber-camera-cmu1394 Frame grabbing using CMU1394 SDK -It is also possible to grab images using CMU1394 SDK if you want to use a firewire camera under Windows. You may find an example in tutorial-grabber-CMU1394.cpp. +It is also possible to grab images using CMU1394 SDK if you want to use a firewire camera under Windows. You may find +an example in tutorial-grabber-CMU1394.cpp. \section grabber-bebop2 Frame grabbing using Parrot Bebop 2 drone @@ -323,7 +343,8 @@ You can chose to record HD 720p pictures from the drone (instead of default 480p \section grabber-video-stream Images from a video stream -With ViSP it also possible to get images from an input video stream. Supported formats are *.avi, *.mp4, *.mov, *.ogv, *.flv and many others... To this end we exploit OpenCV 3rd party. +With ViSP it also possible to get images from an input video stream. Supported formats are *.avi, *.mp4, *.mov, *.ogv, +*.flv and many others... To this end we exploit OpenCV 3rd party. The example below available in tutorial-video-reader.cpp shows how to consider an mpeg video stream. @@ -337,13 +358,15 @@ The source code is the following: We explain now the new lines that were introduced. \snippet tutorial-video-reader.cpp Include -Include the header of the vpTime class that allows to measure time, and of the vpVideoReader class that allows to read a video stream. +Include the header of the vpTime class that allows to measure time, and of the vpVideoReader class that allows to read +a video stream. \snippet tutorial-video-reader.cpp vpVideoReader construction Create an instance of a video reader. \snippet tutorial-video-reader.cpp vpVideoReader setting -Set the name of the video stream. Here \c videoname corresponds to a video file name location. For example we provide the file \c video.mpg located in the same folder than the executable. +Set the name of the video stream. Here \c videoname corresponds to a video file name location. For example we provide +the file \c video.mpg located in the same folder than the executable. The vpVideoReader class can also handle a sequence of images. For example, to read the following images: @@ -362,7 +385,8 @@ you may use the following: \code g.setFileName("./image%04d.png"); \endcode -where you specify that each image number is coded with 4 digits. Here, we will use \c libpng or \c OpenCV to read PNG images. Supported image formats are PPM, PGM, PNG and JPEG. +where you specify that each image number is coded with 4 digits. Here, we will use \c libpng or \c OpenCV to read PNG +images. Supported image formats are PPM, PGM, PNG and JPEG. Then as for any other grabber, you have to initialize the frame grabber using: @@ -378,7 +402,8 @@ To synchronize the video decoding with the video framerate, we measure the begin \snippet tutorial-video-reader.cpp vpVideoReader loop start time -The synchronization is done by waiting from the beginning of the iteration the corresponding time expressed in milliseconds by using: +The synchronization is done by waiting from the beginning of the iteration the corresponding time expressed in +milliseconds by using: \snippet tutorial-video-reader.cpp vpVideoReader loop rate \subsection grabber-video-stream-use How to acquire images @@ -400,5 +425,6 @@ To read an other video, let say my-video.mpg, you may use: You are now ready to see how to continue with: - a simple image processing that shows how to track blobs explained in \ref tutorial-tracking-blob. -- There is also the \ref tutorial-video-manipulation that could be useful when you need to visualize, rename or change the format of a captured video or sequence of successive images, typically for deep learning purpose. +- There is also the \ref tutorial-video-manipulation that could be useful when you need to visualize, rename or change + the format of a captured video or sequence of successive images, typically for deep learning purpose. */ diff --git a/doc/tutorial/image/tutorial-image-display-overlay.dox b/doc/tutorial/image/tutorial-image-display-overlay.dox index 73e4231727..d17fa3e005 100644 --- a/doc/tutorial/image/tutorial-image-display-overlay.dox +++ b/doc/tutorial/image/tutorial-image-display-overlay.dox @@ -4,17 +4,17 @@ \section display_overlay_intro Introduction -In this tutorial you will learn how to display basic drawings with ViSP either on Unix-like systems (including OSX, Fedora, Ubuntu, Debian, ...) or on Windows. +In this tutorial you will learn how to display basic drawings with ViSP either on Unix-like systems (including OSX, +Fedora, Ubuntu, Debian, ...) or on Windows. -Note that all the material (source code and images) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/image -\endcode +Note that all the material (source code and images) described in this tutorial is part of ViSP source code +(in `tutorial/image` folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/image. \section display_overlay_default Load and display an image -ViSP gui module provides Graphical User Interfaces capabilities. To this end you may use several optional third-party libraries which are: X11, GDI, OpenCV, GTK, Direct3D. In the next example, we will use the first 3rd party that is available from the previous list. +ViSP gui module provides Graphical User Interfaces capabilities. To this end +you may use several optional third-party libraries which are: X11, GDI, +OpenCV, GTK, Direct3D. In the next example, we will use the first 3rd party that is available from the previous list. The following example also available in tutorial-viewer.cpp shows how to read and display an image. @@ -32,7 +32,10 @@ It will open a window containing `monkey.png` image: Here is the detailed explanation of the source, line by line : \snippet tutorial-viewer.cpp Include display -Include all the headers for image viewers. The two first one are for Windows systems. They require that Direct 3D or the \e Graphical \e Device \e Interface (\e GDI) coming with the installation of Visual Studio are available. The third one needs GTK that is cross-platform. The fourth is for unix-like systems and requires that \e libX11 is available. The last one is also cross-platform and requires that OpenCV is available. +Include all the headers for image viewers. The two first one are for Windows systems. They require that Direct 3D or +the \e Graphical \e Device \e Interface (\e GDI) coming with the installation of Visual Studio are available. The +third one needs GTK that is cross-platform. The fourth is for unix-like systems and requires that \e libX11 is +available. The last one is also cross-platform and requires that OpenCV is available. \snippet tutorial-viewer.cpp Include io Include the header that allows to read/write PGM, PPM, PNG and JPEG images from the disk using vpImageIo class. @@ -41,10 +44,12 @@ Include the header that allows to read/write PGM, PPM, PNG and JPEG images from Create an instance of a color image where each pixel is coded in RGBa. \snippet tutorial-viewer.cpp vpImage reading -The image \c I is initialized by reading an image file from the disk. If the image format is not supported we throw an exception. +The image \c I is initialized by reading an image file from the disk. If the image format is not supported we throw an +exception. \snippet tutorial-viewer.cpp vpDisplay construction -Create an instance of an image display window for image \c I. The first viewer that is available is used. Here we create the link between the image \c I and the display \c d. Note that an image can only have one display. +Create an instance of an image display window for image \c I. The first viewer that is available is used. Here we +create the link between the image \c I and the display \c d. Note that an image can only have one display. \snippet tutorial-viewer.cpp vpDisplay set title The title of the display is then set to \c "My image". @@ -57,7 +62,8 @@ Here we handle mouse events. We are waiting for a blocking mouse click to end th \section display_overlay_draw Display basic drawings in window overlay -There are a lot of examples in ViSP that show how to display drawings in window overlay. There is testDisplays.cpp that gives an overview. +There are a lot of examples in ViSP that show how to display drawings in window overlay. There is testDisplays.cpp +that gives an overview. If you run the corresponding binary: \code @@ -69,7 +75,9 @@ it will open a window like the following: \subsection display_overlay_point Display a point in overlay -As shown in tutorial-draw-point.cpp which source code is given below we use vpDisplay::displayPoint() function to draw a point in the overlay of a windows that displays a 3840 by 2160 grey image that has all the pixels set to 128 gray level. +As shown in tutorial-draw-point.cpp which source code is given below we use vpDisplay::displayPoint() function to draw +a point in the overlay of a windows that displays a 3840 by 2160 grey image that has all the pixels set to 128 gray +level. \include tutorial-draw-point.cpp @@ -85,7 +93,8 @@ Here we draw a red coloured line segment with the specified initial and final co \subsection display_overlay_circle Display a circle in overlay -As given in tutorial-image-display-scaled-auto.cpp we use vpDisplay::displayCircle() function to draw a circle on the screen. +As given in tutorial-image-display-scaled-auto.cpp we use vpDisplay::displayCircle() function to draw a circle on the +screen. \snippet tutorial-image-display-scaled-auto.cpp Circle @@ -116,13 +125,15 @@ Here `Hello world` is displayed in the middle of the image. \section display_overlay_export Export and save the content of a window as an image -As given in tutorial-export-image.cpp which source code is given below, we use vpDisplay::getImage() function to export the image with the whole drawings in overlay. Then we use vpImageIo::write() to save the image in png format. +As given in tutorial-export-image.cpp which source code is given below, we use vpDisplay::getImage() function to export +the image with the whole drawings in overlay. Then we use vpImageIo::write() to save the image in png format. \include tutorial-export-image.cpp \section display_overlay_event_keyboard Handle keyboard events in a window -As given in tutorial-event-keyboard.cpp which code is given below, we use vpDisplay::getKeyboardEvent() function to get the value of the key pressed. +As given in tutorial-event-keyboard.cpp which code is given below, we use vpDisplay::getKeyboardEvent() function to get +the value of the key pressed. \include tutorial-event-keyboard.cpp diff --git a/doc/tutorial/image/tutorial-image-display.dox b/doc/tutorial/image/tutorial-image-display.dox index ff4770efbd..966b86be08 100644 --- a/doc/tutorial/image/tutorial-image-display.dox +++ b/doc/tutorial/image/tutorial-image-display.dox @@ -5,36 +5,45 @@ \section image_display_intro Introduction -\note We assume in this tutorial that you have successfully build your first project using ViSP as 3rd party as explained in one of the \ref tutorial_started tutorials. +\note We assume in this tutorial that you have successfully build your first project using ViSP as 3rd party as +explained in one of the \ref tutorial_started tutorials. -In this tutorial you will learn how to display an image in a window with ViSP either on Unix-like systems (including OSX, Fedora, Ubuntu, Debian, ...) or on Windows. +In this tutorial you will learn how to display an image in a window with ViSP either on Unix-like systems (including +OSX, Fedora, Ubuntu, Debian, ...) or on Windows. -Note that all the material (source code and images) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/image -\endcode +Note that all the material (source code and images) described in this tutorial is part of ViSP source code +(in `tutorial/image` folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/image. \section image_display_default Create and display an image in a window -ViSP gui module provides Graphical User Interfaces capabilities that allows to display a vpImage in a window. To this end you may use several optional third-party libraries which are: X11, GDI, OpenCV, GTK, Direct3D. We recommend to use X11 on unix-like systems thanks to vpDisplayX class and GDI on Windows thanks to vpDisplayGDI. If none of these classes are available, you may use vpDisplayOpenCV instead. +ViSP gui module provides Graphical User Interfaces capabilities that allows to +display a vpImage in a window. To this end you may use several optional third-party libraries which are: +X11, GDI, OpenCV, GTK, Direct3D. We recommend to use X11 on unix-like +systems thanks to vpDisplayX class and GDI on Windows thanks to vpDisplayGDI. If none of these classes are available, +you may use vpDisplayOpenCV instead. -The following example also available in tutorial-image-display.cpp shows how to create a gray level 3840x2160 image with all the pixels set to 128, and display a red circle with 200 pixel radius in the middle of the image. +The following example also available in tutorial-image-display.cpp shows how to create a gray level 3840x2160 image +with all the pixels set to 128, and display a red circle with 200 pixel radius in the middle of the image. \include tutorial-image-display.cpp -Depending on your screen resolution you may just see a part of the image, and certainly not the full red circle. Next image shows an example of this behavior when screen resolution is less than image size: +Depending on your screen resolution you may just see a part of the image, and certainly not the full red circle. Next +image shows an example of this behavior when screen resolution is less than image size: \image html img-tutorial-display.png -\note A vpImage can only be associated to one display window. In the previous example, image `I` is associated to display `d`. Depending on your platform, object `d` is either a vpDisplayX or a vpDisplayGDI. +\note A vpImage can only be associated to one display window. In the previous example, image `I` is associated to +display `d`. Depending on your platform, object `d` is either a vpDisplayX or a vpDisplayGDI. \section image_display_scaled Display an image that is larger than the screen resolution \subsection image_display_scaled_manu Setting a manual down scaling factor -This other example available in tutorial-image-display-scaled-manu.cpp shows how to modify the previous example in order to introduce a down scaling factor to reduce the size of the display by 5 along the lines and the columns. This feature may be useful to display images that are larger than the screen resolution. +This other example available in tutorial-image-display-scaled-manu.cpp shows how to modify the previous example in +order to introduce a down scaling factor to reduce the size of the display by 5 along the lines and the columns. This +feature may be useful to display images that are larger than the screen resolution. -To down scale the display size, just modify the previous example adding the vpDisplay::vpScaleType parameter to the constructor. +To down scale the display size, just modify the previous example adding the vpDisplay::vpScaleType parameter to the +constructor. \snippet tutorial-image-display-scaled-manu.cpp vpDisplay scale manu @@ -52,9 +61,12 @@ It is also possible to do the same using the default constructor: \subsection image_display_scaled_auto Setting an auto down scaling factor -This other example available in tutorial-image-display-scaled-auto.cpp shows now how to modify the previous example in order to introduce an auto down scaling factor that is automatically computed from the screen resolution in order that two images could be displayed given the screen resolution. +This other example available in tutorial-image-display-scaled-auto.cpp shows now how to modify the previous example in +order to introduce an auto down scaling factor that is automatically computed from the screen resolution in order that +two images could be displayed given the screen resolution. -To consider an auto down scaling factor, modify the previous example adding the vpDisplay::SCALE_AUTO parameter to the constructor. +To consider an auto down scaling factor, modify the previous example adding the vpDisplay::SCALE_AUTO parameter to the +constructor. \snippet tutorial-image-display-scaled-auto.cpp vpDisplay scale auto diff --git a/doc/tutorial/image/tutorial-image-filtering.dox b/doc/tutorial/image/tutorial-image-filtering.dox index 6db477e912..dbf484716f 100644 --- a/doc/tutorial/image/tutorial-image-filtering.dox +++ b/doc/tutorial/image/tutorial-image-filtering.dox @@ -9,17 +9,15 @@ This tutorial supposes that you have followed the \ref tutorial-getting-started. In this tutorial you will learn how to use ViSP filtering functions implemented in vpImageFilter class. -All the material (source code and images) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/image -\endcode +Note that all the material (source code and images) described in this tutorial is part of ViSP source code +(in `tutorial/image` folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/image. Let us consider the following source code that comes from tutorial-image-filter.cpp. \include tutorial-image-filter.cpp -Once build, you should have \c tutorial-image-filter binary. It shows how to apply different filters on an input image. Here we will consider monkey.pgm as input image. +Once build, you should have \c tutorial-image-filter binary. It shows how to apply different filters on an input image. +Here we will consider monkey.pgm as input image. \image html img-monkey-gray.png @@ -37,7 +35,8 @@ Monkey input image is read from disk and is stored in \c I which is a gray leve \snippet tutorial-image-filter.cpp vpImage construction -To apply a Gaussian blur to this image we first have to declare a resulting floating-point image \c F. Then the blurred image could be obtained using the default Gaussian filter: +To apply a Gaussian blur to this image we first have to declare a resulting floating-point image \c F. Then the blurred +image could be obtained using the default Gaussian filter: \snippet tutorial-image-filter.cpp Gaussian blur @@ -79,8 +78,9 @@ After the declaration of a new image container \c C, Canny edge detector is appl Where: - 5: is the size of the Gaussian kernel used to blur the image before applying the Canny edge detector. -- -1.: is the upper threshold set in the program. Setting it to a negative value asks ViSP to compute automatically the lower and upper thresholds. Otherwise, -the lower threshold is set to be equal to one third of the upper threshold, following Canny’s recommendation. +- -1.: is the upper threshold set in the program. Setting it to a negative value asks ViSP to compute automatically the + lower and upper thresholds. Otherwise, the lower threshold is set to be equal to one third of the upper threshold, + following Canny’s recommendation. - 3: is the size of the Sobel kernel used internally. The resulting image \c C is the following: diff --git a/doc/tutorial/image/tutorial-simu-image.dox b/doc/tutorial/image/tutorial-simu-image.dox index a6df4be117..d9fb79d541 100644 --- a/doc/tutorial/image/tutorial-simu-image.dox +++ b/doc/tutorial/image/tutorial-simu-image.dox @@ -5,19 +5,19 @@ \section simu_image_intro Introduction -The aim of this tutorial is to explain how to use vpImageSimulator class to project an image of a planar scene at a given camera position. For example, this capability can then be used during the simulation of a visual-servo as described in \ref tutorial-ibvs to introduce an image processing. +The aim of this tutorial is to explain how to use vpImageSimulator class to project an image of a planar scene at a +given camera position. For example, this capability can then be used during the simulation of a visual-servo as +described in \ref tutorial-ibvs to introduce an image processing. -All the material (source code and images) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/simulator/image -\endcode +Note that all the material (source code and images) described in this tutorial is part of ViSP source code +(in `simulator/image` folder) and could be found in https://github.com/lagadic/visp/tree/master/simulator/image. \section simu_image_projection Image projection -Given the image of a planar 20cm by 20cm square target as the one presented in the next image, we show here after how to project this image at a given camera position, and how to get the resulting image. +Given the image of a planar 20cm by 20cm square target as the one presented in the next image, we show here after how +to project this image at a given camera position, and how to get the resulting image. -\image html img-target-square.png Image of a planar 20cm by 20cm square target. +\image html img-target-square.png Image of a planar 20cm by 20cm square target. This is done by the following code also available in tutorial-image-simulator.cpp: \include tutorial-image-simulator.cpp @@ -31,10 +31,12 @@ The provide hereafter the explanation of the new lines that were introduced. \snippet tutorial-image-simulator.cpp Include Include the header of the vpImageSimulator class that allows to project an image to a given camera position. -Then in the main() function we create an instance of a gray level image that corresponds to the image of the planar target, and then we read the image from the disk. +Then in the main() function we create an instance of a gray level image that corresponds to the image of the planar +target, and then we read the image from the disk. \snippet tutorial-image-simulator.cpp Read image -Since the previous image corresponds to a 20cm by 20cm target, we initialize the 3D coordinates of each corner in the plane Z=0. Each +Since the previous image corresponds to a 20cm by 20cm target, we initialize the 3D coordinates of each corner in the +plane Z=0. Each \snippet tutorial-image-simulator.cpp Set model Then we create an instance of the image \c I that will contain the rendered image from a given camera position. @@ -43,20 +45,25 @@ Then we create an instance of the image \c I that will contain the rendered imag Since the projection depends on the camera, we set its intrinsic parameters. \snippet tutorial-image-simulator.cpp Camera parameters -We also set the render position of the camera as an homogeneous transformation between the camera frame and the target frame. +We also set the render position of the camera as an homogeneous transformation between the camera frame and the target +frame. \snippet tutorial-image-simulator.cpp Set cMo -We create here an instance of the planar image projector, set the interpolation to bilinear and initialize the projector with the image of the target and the coordinates of its corners. +We create here an instance of the planar image projector, set the interpolation to bilinear and initialize the +projector with the image of the target and the coordinates of its corners. \snippet tutorial-image-simulator.cpp Create simulator -Now to retrieve the rendered image we first clean the content of the image to render, set the camera position, and finally get the image using the camera parameters. +Now to retrieve the rendered image we first clean the content of the image to render, set the camera position, and +finally get the image using the camera parameters. \snippet tutorial-image-simulator.cpp Render image -Then, if \c libjpeg is available, the rendered image is saved in the same directory then the executable. +Then, if \c libjpeg is available, the rendered image is saved in the same directory then the executable. \snippet tutorial-image-simulator.cpp Write image Finally, as in \ref tutorial-getting-started we open a window to display the rendered image. -Note that this planar image projection capability has been also introduced in vpVirtualGrabber class exploited in tutorial-ibvs-4pts-image-tracking.cpp. Thus the next \ref tutorial-ibvs shows how to use it in order to introduce an image processing that does the tracking of the target during a visual-servo simulation. +Note that this planar image projection capability has been also introduced in vpVirtualGrabber class exploited in +tutorial-ibvs-4pts-image-tracking.cpp. Thus the next \ref tutorial-ibvs shows how to use it in order to introduce an +image processing that does the tracking of the target during a visual-servo simulation. */ diff --git a/doc/tutorial/image/tutorial-video-manipulation.dox b/doc/tutorial/image/tutorial-video-manipulation.dox index cadacfaaa7..13844fb751 100644 --- a/doc/tutorial/image/tutorial-video-manipulation.dox +++ b/doc/tutorial/image/tutorial-video-manipulation.dox @@ -4,13 +4,11 @@ \section img_manip_seq_intro Introduction -In this tutorial you will learn how to manipulate a video or a sequence of successives images in order to rename the images, convert images format, or select some images that will constitute a dataset typically for deep learning purpose. +In this tutorial you will learn how to manipulate a video or a sequence of successives images in order to rename the +images, convert images format, or select some images that will constitute a dataset typically for deep learning purpose. -Note that all the material (source code and images) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/image -\endcode +Note that all the material (source code and images) described in this tutorial is part of ViSP source code +(in `tutorial/image` folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/image. \section img_manip_seq_prereq Prerequisites @@ -87,7 +85,8 @@ $ cd $VISP_WS/visp-build/tutorial/image $ ./tutorial-video-manipulation --in ${VISP_INPUT_IMAGE_PATH}/video/cube.mpeg \endverbatim -- To visualize a sequence of successive images, like the one acquired in \ref img_manip_seq_create section, you may rather run: +- To visualize a sequence of successive images, like the one acquired in \ref img_manip_seq_create section, you may + rather run: \verbatim $ cd $VISP_WS/visp-build/tutorial/image ./tutorial-video-manipulation --in /tmp/myseq/png/I%04d.png @@ -177,24 +176,26 @@ image-0120.jpeg Moreover, there is also an other extra option `--out-gray` that allows to save output images in Y8 gray level images. -- For example, considering that `/tmp/myseq/png/I%04d.png` input images are color images, if you want to convert them in Y8 gray, you may run: +- For example, considering that `/tmp/myseq/png/I%04d.png` input images are color images, if you want to convert them + in Y8 gray, you may run: \verbatim $ ./tutorial-video-manipulation --in /tmp/myseq/png/I%04d.png --out /tmp/myseq/gray-jpeg/gray-image-%04d.jpg --out-gray \endverbatim -- Finally, there is also the `--out-stride` option that allows to keep one image over n in the resulting output video. - For example, if your input image sequence has 40 images and you want to create a new image sequence temporally subsampled - with only 20 images, you can use this option like: +- Finally, there is also the `--out-stride` option that allows to keep one image over n in the resulting output video. + For example, if your input image sequence has 40 images and you want to create a new image sequence temporally + subsampled with only 20 images, you can use this option like: \verbatim $ ./tutorial-video-manipulation --in /tmp/myseq/png/I%04d.png --out /tmp/myseq/png-stride-2/I%04d.png --out-stride 2 \endverbatim - - + + \subsection img_manip_seq_extract Images extraction from a video The tutorial tutorial-image-manipulation.cpp allows also to extract images from a video file. -- For example to extract the images from an `mpeg` video part of ViSP data set and create a sequence of successive images, you may run: +- For example to extract the images from an `mpeg` video part of ViSP data set and create a sequence of successive + images, you may run: \verbatim $ ./tutorial-video-manipulation --in ${VISP_INPUT_IMAGE_PATH}/video/cube.mpeg --out /tmp/cube/jpeg/image-%04d.jpeg \endverbatim @@ -211,7 +212,7 @@ image-0008.jpeg image-0009.jpeg image-0010.jpeg ... -\endverbatim +\endverbatim - You can then replay the image sequence using: \verbatim ./tutorial-video-manipulation --in /tmp/cube/jpeg/image-%04d.jpeg @@ -219,15 +220,17 @@ image-0010.jpeg \subsection img_manip_seq_select Images selection to create a new video or sequence -The tutorial tutorial-image-manipulation.cpp allows also to extract some images selected by the user during visualisation by user click. This feature could be useful to extract the images that will be part of a deep leaning data set. +The tutorial tutorial-image-manipulation.cpp allows also to extract some images selected by the user during +visualisation by user click. This feature could be useful to extract the images that will be part of a deep +leaning data set. - To create a new video from selected images you may add `--select` option, like: \verbatim $ ./tutorial-video-manipulation --in ${VISP_INPUT_IMAGE_PATH}/video/cube.mpeg --out /tmp/cube/jpeg/image-%04d.jpeg --select \endverbatim -- Here if the user click four times in the video, you will get a new sequence with 4 successive images +- Here if the user click four times in the video, you will get a new sequence with 4 successive images \verbatim -$ ls -1 /tmp/cube/jpeg +$ ls -1 /tmp/cube/jpeg image-0001.jpeg image-0002.jpeg image-0003.jpeg diff --git a/doc/tutorial/ios/tutorial-detection-apriltag-ios-realtime.dox b/doc/tutorial/ios/tutorial-detection-apriltag-ios-realtime.dox index 5f2d854986..a675381106 100644 --- a/doc/tutorial/ios/tutorial-detection-apriltag-ios-realtime.dox +++ b/doc/tutorial/ios/tutorial-detection-apriltag-ios-realtime.dox @@ -9,11 +9,9 @@ This tutorial follows \ref tutorial-detection-apriltag-ios and shows how to dete In this tutorial, you will be able to learn how to detect with Swift 4 and get camera intrinsic parameters. -All the material (Xcode project) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\verbatim -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/ios/AprilTagLiveCamera -\endverbatim +Note that all the material (Xcode project) described in this tutorial is part of ViSP source code +(in `tutorial/ios/AprilTagLiveCamera` folder) and could be found in +https://github.com/lagadic/visp/tree/master/tutorial/ios/AprilTagLiveCamera. Once downloaded, you have just to drag & drop ViSP and OpenCV frameworks available following \ref tutorial-install-ios-package. @@ -35,18 +33,21 @@ The camera’s intrinsic parameters can be acquired from each captured image by Note: intrinsic parameters are only supported on some iOS devices with iOS11. -The intrinsic parameters that represent camera features can generally be represented by a matrix of pixel-based focal lengths and principal points (axis centers) in the image. -The documentation for Swift is [here](https://developer.apple.com/documentation/avfoundation/avcameracalibrationdata/2881135-intrinsicmatrix). +The intrinsic parameters that represent camera features can generally be represented by a matrix of pixel-based focal lengths and principal points (axis centers) in the image. +The documentation for Swift is [here](https://developer.apple.com/documentation/avfoundation/avcameracalibrationdata/2881135-intrinsicmatrix). Since the principal point almost coincides with the image center, this tutorial uses only the focal length. \section call_objectivec_swift Call Objective-C class from Swift -Let us consider the Xcode project named `AprilTagLiveCamera` that is part of ViSP source code and located in `$VISP_WS/tutorial/ios/AprilTagLiveCamera`. +Let us consider the Xcode project named `AprilTagLiveCamera` that is part of ViSP source code and located in `$VISP_WS/tutorial/ios/AprilTagLiveCamera`. To open this application, if you followed \ref tutorial-install-ios-package simply run: \verbatim $ cd $HOME/framework -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/ios/AprilTagLiveCamera +\endverbatim +Donwload the content of https://github.com/lagadic/visp/tree/master/tutorial/ios/AprilTagLiveCamera +anr run +\verbatim $ open AprilTagLiveCamera -a Xcode \endverbatim @@ -73,8 +74,8 @@ and in `ViewController.swift` you have the following code: Detection and drawing processing is processed in `VispDetector.mm`. For details on the detection process, see \ref tutorial-detection-apriltag and on how to draw the pose of a tag, see the previous \ref tutorial-detection-apriltag-ios. -The distance from the iOS device to the marker can be accurately detected if the tag size is properly set. -The distance can be obtained using the getTranslationVector() method from the homogeneous transformation matrix (`cMo_vec`) representing the pose with rotation (R) and position (t) of the marker in camera coordinates. +The distance from the iOS device to the marker can be accurately detected if the tag size is properly set. +The distance can be obtained using the getTranslationVector() method from the homogeneous transformation matrix (`cMo_vec`) representing the pose with rotation (R) and position (t) of the marker in camera coordinates. See here for more information vpHomogeneousMatrix class This is achieved in `VispDetector.mm`: diff --git a/doc/tutorial/ios/tutorial-detection-apriltag-ios.dox b/doc/tutorial/ios/tutorial-detection-apriltag-ios.dox index 6c49239ee3..eee437ecac 100644 --- a/doc/tutorial/ios/tutorial-detection-apriltag-ios.dox +++ b/doc/tutorial/ios/tutorial-detection-apriltag-ios.dox @@ -9,11 +9,9 @@ This tutorial follows the \ref tutorial-detection-apriltag and shows how AprilTa In the next section you will find an example that show how to detect tags in a single image. To know how to print an AprilTag marker, see \ref apriltag_detection_print. -Note that all the material (Xcode project and image) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\verbatim -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/ios/StartedAprilTag -\endverbatim +Note that all the material (Xcode project and image) described in this tutorial is part of ViSP source code +(in `tutorial/ios/StartedAprilTag` folder) and could be found in +https://github.com/lagadic/visp/tree/master/tutorial/ios/StartedAprilTag. \section apriltag_detection_basic_ios AprilTag detection and pose estimation (single image) @@ -22,7 +20,10 @@ Let us consider the Xcode project named `StartedAprilTag` that is part of ViSP s To open this application, if you followed \ref tutorial-install-ios-package simply run: \verbatim $ cd $HOME/framework -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/ios/StartedAprilTag +\endverbatim +download the content of https://github.com/lagadic/visp/tree/master/tutorial/ios/StartedAprilTag +and run +\verbatim $ open StartedAprilTag -a Xcode \endverbatim @@ -48,19 +49,19 @@ The Xcode project `StartedAprilTag` contains `ImageDisplay.h` and `ImageDisplay. \subsection apriltag_detection_display_line Display a line -The following function implemented in `ImageDisplay.mm` show how to display a line. +The following function implemented in `ImageDisplay.mm` show how to display a line. \snippet StartedAprilTag/ImageDisplay.mm display line \subsection apriltag_detection_display_frame Display a 3D frame -The following function implemented in `ImageDisplay.mm` show how to display a 3D frame; red line for x, green for y and blue for z axis. +The following function implemented in `ImageDisplay.mm` show how to display a 3D frame; red line for x, green for y and blue for z axis. \snippet StartedAprilTag/ImageDisplay.mm display frame \section apriltag_detection_basic_output Application output -- Now we are ready to build `StartedAprilTag` application using Xcode `"Product > Build"` menu. +- Now we are ready to build `StartedAprilTag` application using Xcode `"Product > Build"` menu. - Once build, if you run `StartedAprilTag` application on your device, you should be able to see the following screen shot: \image html img-detection-apriltag-ios-output.jpg diff --git a/doc/tutorial/ios/tutorial-getting-started-iOS.dox b/doc/tutorial/ios/tutorial-getting-started-iOS.dox index cfc45b8b25..00ecd8756f 100644 --- a/doc/tutorial/ios/tutorial-getting-started-iOS.dox +++ b/doc/tutorial/ios/tutorial-getting-started-iOS.dox @@ -1,21 +1,22 @@ /** - \page tutorial-getting-started-iOS Tutorial: How to create a basic iOS application that uses ViSP + \page tutorial-getting-started-iOS Tutorial: How to create a basic iOS application that uses ViSP \tableofcontents - \note We assume that you have `"ViSP for iOS"` either after following \ref tutorial-install-ios-package or \ref tutorial-install-iOS. Following one of these tutorials allows to exploit `visp3.framework` and `opencv2.framework` to build an application for iOS devices. + \note We assume that you have `"ViSP for iOS"` either after following \ref tutorial-install-ios-package or + \ref tutorial-install-iOS. Following one of these tutorials allows to exploit `visp3.framework` and + `opencv2.framework` to build an application for iOS devices. -In this tutorial we suppose that you install `visp3.framework` in a folder named `/ios`. If `` corresponds to `$HOME/framework`, you should get the following: +In this tutorial we suppose that you install `visp3.framework` in a folder named `/ios`. If +`` corresponds to `$HOME/framework`, you should get the following: \verbatim $ ls $HOME/framework/ios opencv2.framework visp3.framework \endverbatim -Note also that all the material (source code and Xcode project) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\verbatim -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/ios/GettingStarted -\endverbatim +Note that all the material (source code and Xcode project) described in this tutorial is part of ViSP source code +(in `tutorial/ios/GettingStarted` folder) and could be found in +https://github.com/lagadic/visp/tree/master/tutorial/ios/GettingStarted. \section getting-started-iOS-create Create a new Xcode project @@ -28,11 +29,12 @@ $ svn export https://github.com/lagadic/visp.git/trunk/tutorial/ios/GettingStart \image html img-getting-started-iOS-options.jpg -- Click on `"Next"` button and select the folder where the new project will be saved. Once done click on `"Create"`. Now you should have something similar to: +- Click on `"Next"` button and select the folder where the new project will be saved. Once done click on `"Create"`. +Now you should have something similar to: \image html img-getting-started-iOS-new.jpg -\section getting-started-iOS-link-visp Linking ViSP framework +\section getting-started-iOS-link-visp Linking ViSP framework Now we need to link `visp3.framework` with the Xcode project. @@ -40,10 +42,12 @@ Now we need to link `visp3.framework` with the Xcode project. \image html img-getting-started-iOS-navigator.jpg -- Use the Finder to drag & drop ViSP and OpenCV frameworks located in `/ios` folder in the left hand panel containing all the project files. +- Use the Finder to drag & drop ViSP and OpenCV frameworks located in `/ios` folder in the left hand +panel containing all the project files. \image html img-getting-started-iOS-drag-drop.jpg -- In the dialog box, enable check box `"Copy item if needed"` to ease `visp3.framework` and `opencv2.framework` headers location addition to the build options +- In the dialog box, enable check box `"Copy item if needed"` to ease `visp3.framework` and `opencv2.framework` +headers location addition to the build options \image html img-getting-started-iOS-drag-drop-dialog.jpg @@ -55,19 +59,24 @@ Now we need to link `visp3.framework` with the Xcode project. - Because we will mix Objective-C and ViSP C++ Code, rename `ViewController.m` file into `ViewController.mm` \image html img-getting-started-iOS-rename.jpg -- Now copy/paste `$VISP_WS/visp/tutorial/ios/GettingStarted/GettingStarted/ViewController.mm` file content into `ViewController.mm`. Note that this Objective-C code is inspired from tutorial-homography-from-points.cpp. +- Now copy/paste `$VISP_WS/visp/tutorial/ios/GettingStarted/GettingStarted/ViewController.mm` file content into +`ViewController.mm`. Note that this Objective-C code is inspired from tutorial-homography-from-points.cpp. \include GettingStarted/ViewController.mm -In this sample, we first import the headers to use vpHomography class. Then we create a new function called \c processViSPHomography(). This function is finally called in `viewDibLoad()`. +In this sample, we first import the headers to use vpHomography class. Then we create a new function called +\c processViSPHomography(). This function is finally called in `viewDibLoad()`. - After the previous copy/paste, you should have something similar to \image html img-getting-started-iOS-code.jpg - Now we are ready to build this simple `"Getting Started"` application using Xcode `"Product > Build"` menu. -\note Here it may be possible that you get a build issue \ref getting-started-ios-issue-libxml. Just follow the link to see how to fix this issue. +\note Here it may be possible that you get a build issue \ref getting-started-ios-issue-libxml. Just follow the link +to see how to fix this issue. -- You can now run your code using `"Product > Run"` menu (Simulator or device does not bother because we are just executing code). You should obtain these logs showing that visp code was correctly executed by your iOS project. +- You can now run your code using `"Product > Run"` menu (Simulator or device does not bother because we are just +executing code). You should obtain these logs showing that visp code was correctly executed by your iOS project. \image html img-getting-started-iOS-log.jpg -- if you don't see the output (1) presented in the red rectangle in the previous image, you may click on icon (2) to display `All Output`. +- if you don't see the output (1) presented in the red rectangle in the previous image, you may click on icon (2) to +display `All Output`. \section getting-started-ios-issues Known issues \subsection getting-started-ios-issue-libxml iOS error: libxml/parser.h not found diff --git a/doc/tutorial/ios/tutorial-image-ios.dox b/doc/tutorial/ios/tutorial-image-ios.dox index 30b4df2f8e..21dcf37ba2 100644 --- a/doc/tutorial/ios/tutorial-image-ios.dox +++ b/doc/tutorial/ios/tutorial-image-ios.dox @@ -7,24 +7,35 @@ This tutorial supposes that you have followed the \ref tutorial-getting-started- \section image_ios_intro Introduction -In this tutorial you will learn how to do simple image processing on iOS devices with ViSP. This application loads a color image (monkey.png) and allows the user to visualize either this image in grey level, either the image gradients, or either canny edges on iOS simulator or devices. +In this tutorial you will learn how to do simple image processing on iOS devices with ViSP. This application loads a +color image +(monkey.png) +and allows the user to visualize either this image in grey level, either the image gradients, or either canny edges on +iOS simulator or devices. -In ViSP images are carried out using vpImage class. However in iOS, image rendering has to be done using UIImage class that is part of the Core Graphics framework available in iOS. In this tutorial we provide the functions that allow to convert a vpImage to an UIImage and \e vice \e versa. +In ViSP images are carried out using vpImage class. However in iOS, image rendering has to be done using UIImage class +that is part of the Core Graphics framework available in iOS. In this tutorial we provide the functions that allow to +convert a vpImage to an UIImage and \e vice \e versa. -Note that all the material (source code and image) used in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\verbatim -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/ios/StartedImageProc -\endverbatim +Note that all the material (source code and image) described in this tutorial is part of ViSP source code +(in `tutorial/ios/StartedImageProc` folder) and could be found in +https://github.com/lagadic/visp/tree/master/tutorial/ios/StartedImageProc. \section image_ios_app StartedImageProc application -Let us consider the Xcode project named `StartedImageProc` that is part of ViSP source code and located in `$VISP_WS/tutorial/ios/StartedImageProc`. This project is a Xcode `"Single view application"` where we renamed `ViewController.m` into `ViewController.mm`, introduced minor modifications in `ViewController.h` and add monkey.png image. +Let us consider the Xcode project named `StartedImageProc` that is part of ViSP source code and located in +`$VISP_WS/tutorial/ios/StartedImageProc`. This project is a Xcode `"Single view application"` where we renamed +`ViewController.m` into `ViewController.mm`, introduced minor modifications in `ViewController.h` and add +monkey.png +image. To open this application, if you followed \ref tutorial-install-ios-package simply run: \verbatim $ cd $HOME/framework -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/ios/StartedImageProc +\endverbatim +download the content of https://github.com/lagadic/visp/tree/master/tutorial/ios/StartedImageProc +and run +\verbatim $ open StartedImageProc -a Xcode \endverbatim @@ -36,32 +47,38 @@ $ open ~/framework/visp/tutorial/ios/StartedImageProc -a Xcode Here you should see something similar to: \image html img-started-imgproc-ios.jpg -Once opened, you have just to drag & drop ViSP and OpenCV frameworks available in `$HOME/framework/ios` if you followed \ref tutorial-install-ios-package. +Once opened, you have just to drag & drop ViSP and OpenCV frameworks available in `$HOME/framework/ios` if you +followed \ref tutorial-install-ios-package. \image html img-started-imgproc-ios-drag-drop.jpg -In the dialog box, enable check box `"Copy item if needed"` to add `visp3.framework` and `opencv2.framework` to the project. +In the dialog box, enable check box `"Copy item if needed"` to add `visp3.framework` and `opencv2.framework` to the +project. \image html img-started-imgproc-ios-drag-drop-dialog.jpg Now you should be able to build and run your application. \section image_ios_convert Image conversion functions -The Xcode project `StartedImageProc` contains `ImageConversion.h` and `ImageConversion.mm` files that implement the functions to convert UIImage to ViSP vpImage and vice versa. +The Xcode project `StartedImageProc` contains `ImageConversion.h` and `ImageConversion.mm` files that implement the +functions to convert UIImage to ViSP vpImage and vice versa. \subsection image_ios_convert_uiimage_vpimage_color UIImage to color vpImage -The following function implemented in \c ImageConversion.mm show how to convert an `UIImage` into a `vpImage` instantiated as a color image. +The following function implemented in \c ImageConversion.mm show how to convert an `UIImage` into a `vpImage` +instantiated as a color image. \snippet tutorial/ios/StartedImageProc/StartedImageProc/ImageConversion.mm vpImageColorFromUIImage \subsection image_ios_convert_uiimage_vpimage_gray UIImage to gray vpImage -The following function implemented in `ImageConversion.mm` show how to convert an `UIImage` into a `vpImage` instantiated as a grey level image. +The following function implemented in `ImageConversion.mm` show how to convert an `UIImage` into a +`vpImage` instantiated as a grey level image. \snippet tutorial/ios/StartedImageProc/StartedImageProc/ImageConversion.mm vpImageGrayFromUIImage \subsection image_ios_convert_vpimage_color_uiimage Color vpImage to UIImage -The following function implemented in `ImageConversion.mm` show how to convert a gray level `vpImage` into an UIImage. +The following function implemented in `ImageConversion.mm` show how to convert a gray level `vpImage` +into an UIImage. \snippet tutorial/ios/StartedImageProc/StartedImageProc/ImageConversion.mm UIImageFromVpImageColor @@ -74,9 +91,11 @@ The following function implemented in `ImageConversion.mm` show how to convert a \section image_ios_output Application output - Now we are ready to build `"StartedImageProc"` application using Xcode `"Product > Build"` menu. -\note Here it may be possible that you get a build issue \ref image_ios-issue-libxml. Just follow the link to see how to fix this issue. +\note Here it may be possible that you get a build issue \ref image_ios-issue-libxml. Just follow the link to see how +to fix this issue. -- Once build, if you run `StartedImageProc` application on your device, you should be able to see the following screen shots. +- Once build, if you run `StartedImageProc` application on your device, you should be able to see the following screen + shots. - Pressing `"load image"` button gives the following result: \image html img-started-imgproc-ios-output-color.jpg diff --git a/doc/tutorial/misc/tutorial-plotter.dox b/doc/tutorial/misc/tutorial-plotter.dox index 3b244410a8..f52439e907 100644 --- a/doc/tutorial/misc/tutorial-plotter.dox +++ b/doc/tutorial/misc/tutorial-plotter.dox @@ -3,17 +3,15 @@ \page tutorial-plotter Tutorial: Real-time curves plotter tool \tableofcontents -This tutorial focuses on real-time curves drawing. It shows how to modify tutorial-ibvs-4pts.cpp introduced in \ref tutorial-ibvs to draw the evolution of the visual features error and the camera velocity skew vector during an image-based visual servoing. +This tutorial focuses on real-time curves drawing. It shows how to modify tutorial-ibvs-4pts.cpp introduced in +\ref tutorial-ibvs to draw the evolution of the visual features error and the camera velocity skew vector during an +image-based visual servoing. -Note that all the material (source code and image) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/visual-servoing/ibvs -\endcode +Note that all the material (source code and images) described in this tutorial is part of ViSP source code +(in `tutorial/visual-servoing/ibvs` folder) and could be found in +https://github.com/lagadic/visp/tree/master/tutorial/visual-servoing/ibvs. The modified code also available in tutorial-ibvs-4pts-plotter.cpp is the following. - - \include tutorial-ibvs-4pts-plotter.cpp The last image of the drawing is the following: @@ -33,21 +31,28 @@ Include the header of the vpPlot class that allows curves drawing. vpPlot plotter(2, 250*2, 500, 100, 200, "Real time curves plotter"); \endcode -Since the plotter opens a windows to display the graphics, the usage of vpPlot class is only possible if ViSP is build with a 3rd party that allows display capabilities; either libx11, GDI, OpenCV or GTK. If this is the case, we create an instance of the vpPlot class. The window that is created will contain two graphics. The windows size will be 500 by 500 pixels. The window position will be (100, 200), and the title "Real time curves plotter". +Since the plotter opens a windows to display the graphics, the usage of vpPlot class is only possible if ViSP is build +with a 3rd party that allows display capabilities; either libx11, GDI, OpenCV or GTK. If this is the case, we create an +instance of the vpPlot class. The window that is created will contain two graphics. The windows size will be 500 by 500 +pixels. The window position will be (100, 200), and the title "Real time curves plotter". \code plotter.setTitle(0, "Visual features error"); plotter.setTitle(1, "Camera velocities"); \endcode -To differentiate the graphics we associate a title to each of them. The first graphic (the one with index 0) will be designed to draw the evolution of the visual features error, while the second (index 1) will be designed to draw the camera velocities. +To differentiate the graphics we associate a title to each of them. The first graphic (the one with index 0) will be +designed to draw the evolution of the visual features error, while the second (index 1) will be designed to draw the +camera velocities. \code plotter.initGraph(0, 8); plotter.initGraph(1, 6); \endcode -Here we initialize the first graphic to be able to plot 8 curves. We recall that we have 4 points, each point has 2 visual features (x and y), that is why there are 8 curves to plot. The second graphic is designed to plot 6 curves corresponding to the camera velocities (3 translation velocities in m/s and 3 rotation velocities in rad/s). +Here we initialize the first graphic to be able to plot 8 curves. We recall that we have 4 points, each point has 2 +visual features (x and y), that is why there are 8 curves to plot. The second graphic is designed to plot 6 curves +corresponding to the camera velocities (3 translation velocities in m/s and 3 rotation velocities in rad/s). \code plotter.setLegend(0, 0, "x1"); @@ -69,7 +74,7 @@ Here we initialize the first graphic to be able to plot 8 curves. We recall that \endcode The previous lines allow to associate a legend to each curve. - + \code #ifdef VISP_HAVE_DISPLAY plotter.plot(0, iter, task.getError()); @@ -77,7 +82,8 @@ The previous lines allow to associate a legend to each curve. #endif \endcode -Once the plotter is initialized, in the servo loop we add at each iteration the corresponding values of the visual features error \f${\bf e}(t) = {\bf s}-{\bf s}^*\f$, and the camera velocities \f${\bf v}_c\f$. +Once the plotter is initialized, in the servo loop we add at each iteration the corresponding values of the visual +features error \f${\bf e}(t) = {\bf s}-{\bf s}^*\f$, and the camera velocities \f${\bf v}_c\f$. \code #ifdef VISP_HAVE_DISPLAY @@ -86,12 +92,14 @@ Once the plotter is initialized, in the servo loop we add at each iteration the #endif \endcode -At the end of the servo loop, we save the data that were plotted in two separate files, one for each graphic. The first line of each text file is the graphic title. Then the coordinates along x,y and z are given in separated columns for each data. +At the end of the servo loop, we save the data that were plotted in two separate files, one for each graphic. The first +line of each text file is the graphic title. Then the coordinates along x,y and z are given in separated columns for +each data. \code vpDisplay::getClick(plotter.I); \endcode Before exiting the program we wait for a human mouse click in the plotter window. - + */ diff --git a/doc/tutorial/misc/tutorial-trace.dox b/doc/tutorial/misc/tutorial-trace.dox index 59e2241a01..f0484cdfb7 100644 --- a/doc/tutorial/misc/tutorial-trace.dox +++ b/doc/tutorial/misc/tutorial-trace.dox @@ -1,12 +1,14 @@ /** -\page tutorial-trace Tutorial: Debug and trace printings +\page tutorial-trace Tutorial: Debug and trace printings \tableofcontents \section intro_trace Introduction -ViSP allows to introduce trace and debug printings that may help debugging. To this end ViSP provides C or C++ macros that allows to print messages to the standard output std::cout or to std::cerr. The following table summarizes the macro defined in visp3/code/vpDebug.h header. +ViSP allows to introduce trace and debug printings that may help debugging. To this end ViSP provides C or C++ macros +that allows to print messages to the standard output std::cout or to std::cerr. The following table summarizes the +macro defined in visp3/code/vpDebug.h header. ~~~ |----------|-------|-------------------------------------|---------------------------------------| @@ -23,67 +25,76 @@ ViSP allows to introduce trace and debug printings that may help debugging. To t \subsection trace_macro Macros for trace -Macro for tracing vpTRACE(), vpTRACE(level), vpERROR_TRACE(), vpERROR_TRACE(level), -vpIN_FCT() and vpOUT_FCT() -work like printf with carrier return at the end of the string, while -vpCTRACE() and vpCERROR() work like the C++ output streams std::cout -and std::cerr. All these macro print messages only if VP_TRACE macro is defined. Macro that has \e level as parameter like vpTRACE(level) or vpERROR_TRACE(level) use an additional define named VP_DEBUG_MODE. They print only messages if VP_DEBUG_MODE >= \e level. +Macro for tracing vpTRACE(), vpTRACE(level), vpERROR_TRACE(), vpERROR_TRACE(level), +vpIN_FCT() and vpOUT_FCT() +work like printf with carrier return at the end of the string, while +vpCTRACE() and vpCERROR() work like the C++ output streams std::cout +and std::cerr. All these macro print messages only if VP_TRACE macro is defined. Macro that has \e level as parameter +like vpTRACE(level) or vpERROR_TRACE(level) use an additional define named VP_DEBUG_MODE. They print only messages if +VP_DEBUG_MODE >= \e level. \subsection debug_macro Macros for debug Macros for debug vpDEBUG_TRACE(), vpDEBUG_TRACE(level), vpDERROR_TRACE() and vpDERROR_TRACE(level) -work like printf while vpCDEBUG(level) works like the C++ output stream std::cout. -These macro print messages only if VP_DEBUG macro is defined. Macro that has \e level as parameter like vpDEBUG_TRACE(level) or vpDERROR_TRACE(level) use an additional define named VP_DEBUG_MODE. They print only messages if VP_DEBUG_MODE >= \e level. +work like printf while vpCDEBUG(level) works like the C++ output stream std::cout. +These macro print messages only if VP_DEBUG macro is defined. Macro that has \e level as parameter like +vpDEBUG_TRACE(level) or vpDERROR_TRACE(level) use an additional define named VP_DEBUG_MODE. They print only messages +if VP_DEBUG_MODE >= \e level. Moreover vpDEBUG_ENABLE(level) can be used to check if a given debug level is active; vpDEBUG_ENABLE(level) is equal to 1 if VP_DEBUG_MODE >= \e level, otherwise vpDEBUG_ENABLE(level) is equal to 0. \section debug_trace_usage Debug and trace usage in ViSP library -In ViSP, before an exception is thrown, trace macro are widely used to inform the user that an error occur. This is redundant, since the same trace message in generally associated to the exception that is thrown. Since ViSP 3.1.0, during CMake configuration it is possible to tune debug and trace printings by setting \c ENABLE_DEBUG_LEVEL cmake variable. +In ViSP, before an exception is thrown, trace macro are widely used to inform the user that an error occur. This is +redundant, since the same trace message in generally associated to the exception that is thrown. Since ViSP 3.1.0, +during CMake configuration it is possible to tune debug and trace printings by setting \c ENABLE_DEBUG_LEVEL cmake +variable. -- To turn off debug and trace printings (this is the default), using cmake command just run : -\code +- To turn off debug and trace printings (this is the default), using cmake command just run : +\code %cmake -DENABLE_DEBUG_LEVEL=0 -\endcode +\endcode -- To turn on debug and trace printings with a debug level of 3, using cmake command just run : -\code +- To turn on debug and trace printings with a debug level of 3, using cmake command just run : +\code %cmake -DENABLE_DEBUG_LEVEL=3 -\endcode +\endcode - or using ccmake GUI as shown in the next snapshot: \image html img-cmake-debug-trace.jpg -\note When \c ENABLE_DEBUG_LEVEL is set to 0 (this is the default behavior in ViSP), we don't define VP_TRACE and VP_DEBUG macro. - -\section example Debug and trace usage in your own project +\note When \c ENABLE_DEBUG_LEVEL is set to 0 (this is the default behavior in ViSP), we don't define VP_TRACE and +VP_DEBUG macro. -Note that all the material (source code) described in this section is part of ViSP source code and could be downloaded using the following command: +\section example Debug and trace usage in your own project -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/trace -\endcode +Note that all the material (source code) described in this tutorial is part of ViSP source code +(in `tutorial/trace` folder) and could be found in +https://github.com/lagadic/visp/tree/master/tutorial/visual-servoing/trace. -If you develop a project that uses ViSP library as a 3rd party, there are different ways to benefit from debug and trace macro described previously. +If you develop a project that uses ViSP library as a 3rd party, there are different ways to benefit from debug and +trace macro described previously. -- If ViSP was build with debug and trace enabled using \c cmake \c ENABLE_DEBUG_LEVEL=\, debug and trace are also enabled in your development. -- If debug and trace were disabled in ViSP (\c ENABLE_DEBUG_LEVEL=0), you can enable debug and trace in your own development either by defining \c VP_DEBUG and/or \c VP_TRACE macro in your code using -\code +- If ViSP was build with debug and trace enabled using \c cmake \c ENABLE_DEBUG_LEVEL=\, debug and trace are + also enabled in your development. +- If debug and trace were disabled in ViSP (\c ENABLE_DEBUG_LEVEL=0), you can enable debug and trace in your own + development either by defining \c VP_DEBUG and/or \c VP_TRACE macro in your code using +\code #define VP_TRACE #define VP_DEBUG #include -\endcode +\endcode either by modifying your \c CMakeLists.txt file by adding an option like: -\code +\code option(ENABLE_DEBUG_MODE "Enable debug and trace printings" ON) if(ENABLE_DEBUG_MODE) add_definitions("-DVP_DEBUG -DVP_TRACE") endif() -\endcode +\endcode The following example also available in tutorial-trace.cpp shows how to use the previous macro. @@ -91,31 +102,33 @@ The following example also available in tutorial-trace.cpp shows how to use the \includelineno tutorial-trace.cpp -\note In the previous example it is important to notice that the following lines have to be put prior to any other ViSP includes: +\note In the previous example it is important to notice that the following lines have to be put prior to any other +ViSP includes: \code #define VP_DEBUG_MODE 2 // Activate debug level 1 and 2 #include \endcode -For example, if you modify the previous example just by including on the top of the file, you will get the following warnings: -\code +For example, if you modify the previous example just by including on the top of the file, you +will get the following warnings: +\code Building CXX object tutorial/trace/CMakeFiles/tutorial-trace.dir/tutorial-trace.cpp.o .../ViSP-code/tutorial/trace/tutorial-trace.cpp:5:1: warning: "VP_DEBUG_MODE" redefined In file included from .../ViSP-build-debug/include/visp3/core/vpImage.h:52, from .../ViSP-code/tutorial/trace/tutorial-trace.cpp:2: .../ViSP-build-debug/include/visp3/core/vpDebug.h:67:1: warning: this is the location of the previous definition -\endcode +\endcode When ViSP library was built without debug and trace the previous example produces the output: -\code +\code %./tutorial-trace Debug level 1 active: 0 Debug level 2 active: 0 Debug level 3 active: 0 -\endcode +\endcode When ViSP is rather build with debug and trace the previous example produces the output: -\code +\code %./tutorial-trace (L0) begin /tmp/tutorial-trace.cpp: main(#9) : main() Debug level 1 active: 1 @@ -133,10 +146,11 @@ Debug level 3 active: 0 (L0) !! /tmp/tutorial-trace.cpp: main(#32) : C++-like error trace (L2) /tmp/tutorial-trace.cpp: main(#35) : C++-like debug trace level 2 (L0) end /tmp/tutorial-trace.cpp: main(#37) : main() -\endcode +\endcode In the previous printings: - the number after "L" indicates the debug or trace level; example (L2) is for level 2. -- the number after "#" indicates the line of the code that produce the printing; example main(#37) means in function main() at line 37. +- the number after "#" indicates the line of the code that produce the printing; example main(#37) means in + function main() at line 37. - the "!!" indicate that the printing is on std::cerr. Others are on std::cout. */ diff --git a/doc/tutorial/started/tutorial-getting-started-naoqi.dox b/doc/tutorial/started/tutorial-getting-started-naoqi.dox index db6d4a5c14..81e531168c 100644 --- a/doc/tutorial/started/tutorial-getting-started-naoqi.dox +++ b/doc/tutorial/started/tutorial-getting-started-naoqi.dox @@ -1,21 +1,25 @@  /** - \page tutorial-getting-started-naoqi Tutorial: How to create an application that uses ViSP on NAOqi OS + \page tutorial-getting-started-naoqi Tutorial: How to create an application that uses ViSP on NAOqi OS \tableofcontents -We assume in this tutorial that you have successfully cross-compiled ViSP following \ref tutorial-install-crosscompiling-naoqi. -The aim of this tutorial is to explain how to create an application that uses ViSP cross-build for NAOqi OS as third-party and how to run this application on Nao, Romeo or Pepper robots. +We assume in this tutorial that you have successfully cross-compiled ViSP following +\ref tutorial-install-crosscompiling-naoqi. +The aim of this tutorial is to explain how to create an application that uses ViSP cross-build for NAOqi OS as +third-party and how to run this application on Nao, Romeo or Pepper robots. -To illustrate this tutorial, we will consider all the examples that are provided in the tutorial dedicated to images (ie. the one located in \c visp/tutorial/image folder). If you are not familiar with ViSP read first \ref tutorial-getting-started. +To illustrate this tutorial, we will consider all the examples that are provided in the tutorial dedicated to images +(ie. the one located in \c visp/tutorial/image folder). If you are not familiar with ViSP read first +\ref tutorial-getting-started. This tutorial was tested on an Ubuntu 14.04 LTS host computer with: -- Cross Toolchain 2.3.1 Linux 64 (\c ctc-linux32-atom-2.3.1.23) on Romeo robot +- Cross Toolchain 2.3.1 Linux 64 (\c ctc-linux32-atom-2.3.1.23) on Romeo robot - Cross Toolchain 2.4.3 Linux 64 (\c ctc-linux64-atom-2.4.3.28) on Pepper robot - \section started_naoqi_code Create a workspace for your project -We assume that as described in \ref tutorial-install-crosscompiling-naoqi, your workspace dedicated to visp contains the following folders: +We assume that as described in \ref tutorial-install-crosscompiling-naoqi, your workspace dedicated to visp contains +the following folders: \code $ ls $HOME/soft visp @@ -27,11 +31,20 @@ Create a new folder to host the project you want to run on NAOqi OS $ mkdir $HOME/soft/tutorial \endcode -Get existing tutorial/image folder from ViSP source code +Copy existing `tutorial/image` folder from ViSP source code or download it from here +https://github.com/lagadic/visp/tree/master/tutorial/image. \code -$ cd $HOME/soft/tutorial -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/image +$ ls $HOME/soft/tutorial/image +CMakeLists.txt monkey.png tutorial-draw-text.cpp tutorial-image-manipulation.cpp +camera.xml monkey.ppm tutorial-event-keyboard.cpp tutorial-image-reader.cpp +chessboard.jpg tutorial-canny.cpp tutorial-export-image.cpp tutorial-image-viewer.cpp +drawingHelpers.cpp tutorial-draw-circle.cpp tutorial-image-colormap.cpp tutorial-undistort.cpp +drawingHelpers.h tutorial-draw-cross.cpp tutorial-image-converter.cpp tutorial-video-manipulation.cpp +memorial.pfm tutorial-draw-frame.cpp tutorial-image-display-scaled-auto.cpp tutorial-viewer.cpp +monkey.bmp tutorial-draw-line.cpp tutorial-image-display-scaled-manu.cpp +monkey.jpeg tutorial-draw-point.cpp tutorial-image-display.cpp +monkey.pgm tutorial-draw-rectangle.cpp tutorial-image-filter.cpp \endcode \section started_naoqi_build Cross-build your project @@ -40,7 +53,7 @@ Create first a build folder associated to your Cross Toolchain like: \code $ cd $HOME/soft/tutorial $ mkdir image-build-ctc-linux64-atom-2.4.3.28 -\endcode +\endcode Configure your project setting \c VISP_DIR and \c CMAKE_TOOLCHAIN_FILE respectively to ViSP and Cross Toolchain location: \code diff --git a/doc/tutorial/started/tutorial-getting-started.dox b/doc/tutorial/started/tutorial-getting-started.dox index a91ea3f6d0..023ef4c227 100644 --- a/doc/tutorial/started/tutorial-getting-started.dox +++ b/doc/tutorial/started/tutorial-getting-started.dox @@ -3,25 +3,29 @@ \page tutorial-getting-started Tutorial: How to create and build a project that uses ViSP and CMake on Unix or Windows \tableofcontents -\note We assume in this tutorial that you have successfully installed ViSP either with an \ref tutorial_install_pkg or with an \ref tutorial_install_src. +\note We assume in this tutorial that you have successfully installed ViSP either with an \ref tutorial_install_pkg or +with an \ref tutorial_install_src. -In this tutorial you will learn how to use ViSP either on unix-like operating system (including OSX, Fedora, Ubuntu, Debian, ...) or on Windows. +In this tutorial you will learn how to use ViSP either on unix-like operating system (including OSX, Fedora, Ubuntu, +Debian, ...) or on Windows. -The easiest way of using ViSP in your project is to use CMake. If you are not familiar with CMake, you can check the tutorial. +The easiest way of using ViSP in your project is to use CMake. If you are not +familiar with CMake, you can check the tutorial. -Note also that all the material (source code and images) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\verbatim -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/image -\endverbatim +Note that all the material (source code and images) described in this tutorial is part of ViSP source code +(in `tutorial/image` folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/image. \section started_quick Quick getting started -In this section we show how to build an existing project that uses ViSP as third-party and CMake for the build mechanism. As a use case we will use the `image` project that is part of ViSP tutorials. The source code comes from https://github.com/lagadic/visp/tutorial/image. It contains a set of source files `tutorial-viewer.cpp`, `tutorial-image-viewer.cpp` and a `CMakeLists.txt` file. We show here how to get these files and build them. +In this section we show how to build an existing project that uses ViSP as third-party and CMake for the build +mechanism. As a use case we will use the `image` project that is part of ViSP tutorials. The source code comes from +https://github.com/lagadic/visp/tutorial/image. It contains a set of source files `tutorial-viewer.cpp`, +`tutorial-image-viewer.cpp` and a `CMakeLists.txt` file. We show here how to get these files and build them. \subsection started_quick_unix On unix-like operating system -1. If you did \ref tutorial_install_pkg you have to create a workspace. If you did \ref tutorial_install_src jump to point 2. since your workspace should be already created.
+1. If you did \ref tutorial_install_pkg you have to create a workspace. If you did \ref tutorial_install_src jump to +point 2. since your workspace should be already existing.
Check if `VISP_WS` environment var exists: \verbatim $ env | grep VISP_WS @@ -33,12 +37,12 @@ $ source ~/.bashrc $ mkdir -p $VISP_WS \endverbatim -2. Get the source code using Subversion (`svn`): +2. Copy the source code from `tutorial/image` ViSP folder \verbatim -$ sudo apt-get install subversion $ cd $VISP_WS -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/image +$ cp -p -r visp/tutorial/image . \endverbatim +or donwload it from https://github.com/lagadic/visp/tree/master/tutorial/image. 3. Create a build folder \verbatim @@ -80,15 +84,13 @@ C:\> setx VISP_WS=C:\visp-ws C:\> exit \endverbatim -2. Get the source code in your workspace either using Subversion (`svn`), either copying the source code from `%%VISP_WS%/tutorial/image` folder if you follow one of the \ref tutorial_install_src tutorials, or downloading the source from https://github.com/lagadic/visp/tutorial/image:
-With Subversion: -\verbatim -C:\> svn export https://github.com/lagadic/visp.git/trunk/tutorial/image -\endverbatim -Or by copy from ViSP source code +2. Get the source code in your workspace
+You can either copy the source code from `%%VISP_WS%/tutorial/image` folder if you follow one of the +\ref tutorial_install_src tutorials \verbatim C:\> xcopy /E /I %VISP_WS%\visp\tutorial\image %VISP_WS%\image \endverbatim +or downloading it from https://github.com/lagadic/visp/tutorial/image. 3. Create a build folder \verbatim @@ -161,7 +163,8 @@ C:\> setx VISP_WS=C:\visp-ws C:\> exit \endverbatim -Enter `VISP_WS` folder and create a new folder let say `started` that will contain your first project that uses ViSP as third-party: +Enter `VISP_WS` folder and create a new folder let say `started` that will contain your first project that uses ViSP +as third-party: - On unix-like operating system
\verbatim @@ -177,9 +180,11 @@ C:\> mkdir started \subsection image_code Get tutorial-viewer.cpp file -Let's start to write our first C++ example to see how to read an image and open a window to display the image with ViSP. This example is provided in tutorial-viewer.cpp example and given below. +Let's start to write our first C++ example to see how to read an image and open a window to display the image with ViSP. +This example is provided in tutorial-viewer.cpp example and given below. -Open your favorite editor and copy/paste the content of this example in `VISP_WS/started/tutorial-viewer.cpp` source file. +Open your favorite editor and copy/paste the content of this example in `VISP_WS/started/tutorial-viewer.cpp` source +file. The code to copy/paste is the following: @@ -188,7 +193,10 @@ The code to copy/paste is the following: Here is the detailed explanation of the source, line by line: \snippet tutorial-viewer.cpp Include display -Include all the headers for image viewers. The two first one are for Windows systems. They require that Direct 3D or the \e Graphical \e Device \e Interface (\e GDI) coming with the installation of Visual Studio are available. The third one needs GTK that is cross-platform. The fourth is for unix-like systems and requires that \e libX11 is available. The last one is also cross-platform and requires that OpenCV is available. +Include all the headers for image viewers. The two first one are for Windows systems. They require that Direct 3D or +the \e Graphical \e Device \e Interface (\e GDI) coming with the installation of Visual Studio are available. The +third one needs GTK that is cross-platform. The fourth is for unix-like systems and requires that \e libX11 is +available. The last one is also cross-platform and requires that OpenCV is available. \snippet tutorial-viewer.cpp Include io Include the header that allows to read/write PGM, PPM, PNG and JPEG images from the disk using vpImageIo class. @@ -197,10 +205,12 @@ Include the header that allows to read/write PGM, PPM, PNG and JPEG images from Create an instance of a color image where each pixel is coded in RGBa. \snippet tutorial-viewer.cpp vpImage reading -The image `I` is initialized by reading an image file from the disk. If the image format is not supported we throw an exception. +The image `I` is initialized by reading an image file from the disk. If the image format is not supported we throw an +exception. \snippet tutorial-viewer.cpp vpDisplay construction -Create an instance of an image display window for image `I`. The first viewer that is available is used. Here we create the link between the image `I` and the display `d`. Note that an image can only have one display. +Create an instance of an image display window for image `I`. The first viewer that is available is used. Here we create +the link between the image `I` and the display `d`. Note that an image can only have one display. \snippet tutorial-viewer.cpp vpDisplay set title The title of the display is then set to "My image". @@ -213,7 +223,8 @@ Here we handle mouse events. We are waiting for a blocking mouse click to end th \subsection image_cmake Get CMakeLists.txt file -Now you have to create a `CMakeLists.txt` file that gives the instructions on how to build `tutorial-viewer.cpp` example. A minimalistic `CMakeLists.txt` should contain the following lines. +Now you have to create a `CMakeLists.txt` file that gives the instructions on how to build `tutorial-viewer.cpp` +example. A minimalistic `CMakeLists.txt` should contain the following lines. Open your editor and copy/paste the following lines in `VISP_WS/started/CMakeLists.txt` file. \code @@ -249,7 +260,8 @@ endif(VISP_FOUND) add_executable(tutorial-viewer tutorial-viewer.cpp) \endcode -where `VISP_USE_FILE` variable is set to the full path to `VISPUse.cmake` file that contains all the CMake material that allow to build your project with ViSP. In other terms, the line +where `VISP_USE_FILE` variable is set to the full path to `VISPUse.cmake` file that contains all the CMake material +that allow to build your project with ViSP. In other terms, the line \code include(${VISP_USE_FILE}) \endcode @@ -263,16 +275,15 @@ will include the following lines to your `CMakeFile.txt` Get `monkey.ppm` image and copy it to `VISP_WS/started` either: - copying it from ViSP source code; the file is in `VISP_WS/tutorial/image/monkey.ppm` -- using Subversion: -\verbatim -svn export https://github.com/lagadic/visp.git/trunk/tutorial/image/monkey.ppm -\endverbatim -- by copy/paste from GitHub using the Raw button +- using download it from https://github.com/lagadic/visp/blob/master/tutorial/image/ + by copy/paste from GitHub using + the Raw button \subsection image_unix On unix-like operating system -In this section we supppose that you have created a folder `$VISP_WS/started` that contains `CMakeLists.txt`, `tutorial-viewer.cpp` and `monkey.ppm` files. +In this section we supppose that you have created a folder `$VISP_WS/started` that contains `CMakeLists.txt`, +`tutorial-viewer.cpp` and `monkey.ppm` files. \subsubsection image_unix_build_folder Create a build folder diff --git a/doc/tutorial/tracking/tutorial-tracking-blob.dox b/doc/tutorial/tracking/tutorial-tracking-blob.dox index 496de1e08c..98103cdf0c 100644 --- a/doc/tutorial/tracking/tutorial-tracking-blob.dox +++ b/doc/tutorial/tracking/tutorial-tracking-blob.dox @@ -5,9 +5,12 @@ \section tracking_blob_intro Introduction -With ViSP you can track a blob using either vpDot or vpDot2 classes. By blob we mean a region of the image that has the same gray level. The blob can be white on a black background, or black on a white background. +With ViSP you can track a blob using either vpDot or vpDot2 classes. By blob we mean a region of the image that has the +same gray level. The blob can be white on a black background, or black on a white background. -In this tutorial we focus on vpDot2 class that provides more functionalities than vpDot class. As presented in section \ref tracking_blob_auto, it allows especially to automize the detection of blobs that have the same characteristics than a reference blob. +In this tutorial we focus on vpDot2 class that provides more functionalities than vpDot class. As presented in section +\ref tracking_blob_auto, it allows especially to automize the detection of blobs that have the same characteristics +than a reference blob. The next videos show the result of ViSP blob tracker on two different objects: @@ -19,21 +22,22 @@ The next videos show the result of ViSP blob tracker on two different objects: \endhtmlonly -All the material (source code and images) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/tracking/blob -\endcode +Note that all the material (source code and images) described in this tutorial is part of ViSP source code +(in `tutorial/tracking/blob` folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/tracking/blob. \section tracking_blob_tracking Blob tracking -In the next subsections we explain how to achieve this kind of tracking, first using a firewire live camera, then using a v4l2 live camera that can be an usb camera, or a Raspberry Pi camera module. +In the next subsections we explain how to achieve this kind of tracking, first using a firewire live camera, then using +a v4l2 live camera that can be an usb camera, or a Raspberry Pi camera module. \subsection live-firewire From a firewire live camera -The following code also available in tutorial-blob-tracker-live-firewire.cpp file provided in ViSP source code tree allows to grab images from a firewire camera and track a blob. The initialisation is done with a user mouse click on a pixel that belongs to the blob. - -To acquire images from a firewire camera we use vp1394TwoGrabber class on unix-like systems or vp1394CMUGrabber class under Windows. These classes are described in the \ref tutorial-grabber. +The following code also available in tutorial-blob-tracker-live-firewire.cpp file provided in ViSP source code tree +allows to grab images from a firewire camera and track a blob. The initialisation is done with a user mouse click on +a pixel that belongs to the blob. + +To acquire images from a firewire camera we use vp1394TwoGrabber class on unix-like systems or vp1394CMUGrabber class +under Windows. These classes are described in the \ref tutorial-grabber. \include tutorial-blob-tracker-live-firewire.cpp @@ -42,10 +46,11 @@ Here after we explain the new lines that are introduced. \snippet tutorial-blob-tracker-live-firewire.cpp Construction -Then we are modifying some default settings to allow drawings in overlay the contours pixels and the position of the center of gravity with a thickness of 2 pixels. +Then we are modifying some default settings to allow drawings in overlay the contours pixels and the position of the +center of gravity with a thickness of 2 pixels. \snippet tutorial-blob-tracker-live-firewire.cpp Setting -Then we are waiting for a user initialization throw a mouse click event in the blob to track. +Then we are waiting for a user initialization throw a mouse click event in the blob to track. \snippet tutorial-blob-tracker-live-firewire.cpp Init The tracker is now initialized. The tracking can be performed on new images: @@ -53,25 +58,33 @@ The tracker is now initialized. The tracking can be performed on new images: \subsection live-v4l2 From a v4l2 live camera -The following code also available in tutorial-blob-tracker-live-v4l2.cpp file provided in ViSP source code tree allows to grab images from a camera compatible with video for linux two driver (v4l2) and track a blob. Webcams or more generally USB cameras, but also the Raspberry Pi Camera Module can be considered. +The following code also available in tutorial-blob-tracker-live-v4l2.cpp file provided in ViSP source code tree allows +to grab images from a camera compatible with video for linux two driver (v4l2) and track a blob. Webcams or more +generally USB cameras, but also the Raspberry Pi Camera Module can be considered. -To acquire images from a v4l2 camera we use vpV4l2Grabber class on unix-like systems. This class is described in the \ref tutorial-grabber. +To acquire images from a v4l2 camera we use vpV4l2Grabber class on unix-like systems. This class is described in the +\ref tutorial-grabber. \include tutorial-blob-tracker-live-v4l2.cpp -The code is the same than the one presented in the previous subsection, except that here we use the vpV4l2Grabber class to grab images from usb cameras. Here we have also modified the while loop in order to catch an exception when the tracker fail: +The code is the same than the one presented in the previous subsection, except that here we use the vpV4l2Grabber +class to grab images from usb cameras. Here we have also modified the while loop in order to catch an exception when +the tracker fail: \code try { blob.track(I); } catch(...) { } \endcode -If possible, it allows the tracker to overcome a previous tracking failure (due to blur, blob outside the image,...) on the next available images. +If possible, it allows the tracker to overcome a previous tracking failure (due to blur, blob outside the image,...) +on the next available images. \section tracking_blob_auto Blob auto detection and tracking -The following example also available in tutorial-blob-auto-tracker.cpp file provided in ViSP source code tree shows how to detect blobs in the first image and then track all the detected blobs. This functionality is only available with vpDot2 class. Here we consider an image that is provided in ViSP source tree. +The following example also available in tutorial-blob-auto-tracker.cpp file provided in ViSP source code tree shows +how to detect blobs in the first image and then track all the detected blobs. This functionality is only available +with vpDot2 class. Here we consider an image that is provided in ViSP source tree. \include tutorial-blob-auto-tracker.cpp @@ -84,17 +97,21 @@ And here is the detailed explanation of the source : First we create an instance of the tracker. \snippet tutorial-blob-auto-tracker.cpp Construction -Then, two cases are handled. The first case, when \c learn is set to \c true, consists in learning the blob characteristics. The user has to click in a blob that serves as reference blob. The size, area, gray level min and max, and some precision parameters will than be used to search similar blobs in the whole image. +Then, two cases are handled. The first case, when \c learn is set to \c true, consists in learning the blob +characteristics. The user has to click in a blob that serves as reference blob. The size, area, gray level min +and max, and some precision parameters will than be used to search similar blobs in the whole image. \snippet tutorial-blob-auto-tracker.cpp Learn -If you have an precise idea of the dimensions of the blob to search, the second case consists is settings the reference characteristics directly. +If you have an precise idea of the dimensions of the blob to search, the second case consists is settings the +reference characteristics directly. \snippet tutorial-blob-auto-tracker.cpp Setting Once the blob characteristics are known, to search similar blobs in the image is simply done by: \snippet tutorial-blob-auto-tracker.cpp Search -Here \c blob_list contains the list of the blobs that are detected in the image \c I. When learning is enabled, the blob that is tracked is not in the list of auto detected blobs. We add it to the end of the list: +Here \c blob_list contains the list of the blobs that are detected in the image \c I. When learning is enabled, +the blob that is tracked is not in the list of auto detected blobs. We add it to the end of the list: \snippet tutorial-blob-auto-tracker.cpp Add learned dot diff --git a/doc/tutorial/tracking/tutorial-tracking-keypoint.dox b/doc/tutorial/tracking/tutorial-tracking-keypoint.dox index d89aa57098..d898ab3bc5 100644 --- a/doc/tutorial/tracking/tutorial-tracking-keypoint.dox +++ b/doc/tutorial/tracking/tutorial-tracking-keypoint.dox @@ -5,17 +5,17 @@ \section tracking_keypoint_intro Introduction -With ViSP it is possible to track keypoints using OpenCV KLT tracker, an implementation of the Kanade-Lucas-Tomasi feature tracker. +With ViSP it is possible to track keypoints using OpenCV KLT tracker, an implementation of the Kanade-Lucas-Tomasi +feature tracker. -All the material (source code and video) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/tracking/keypoint -\endcode +Note that all the material (source code and videos) described in this tutorial is part of ViSP source code +(in `tutorial/tracking/keypoint` folder) and could be found in +https://github.com/lagadic/visp/tree/master/tutorial/tracking/keypoint. \section tracking_keypoint_klt KLT tracker -The following example code available in tutorial-klt-tracker.cpp shows how to use ViSP vpKltOpencv class to track KLT keypoints. This class is a wrapper over the OpenCV KLT tracker implementation. +The following example code available in tutorial-klt-tracker.cpp shows how to use ViSP vpKltOpencv class to track KLT +keypoints. This class is a wrapper over the OpenCV KLT tracker implementation. \include tutorial-klt-tracker.cpp @@ -25,12 +25,14 @@ The video shows the result of the tracking: \endhtmlonly -The previous example can be run without command line options. In that case, keypoints are automatically detected before tracking. +The previous example can be run without command line options. In that case, keypoints are automatically detected before +tracking. \code $ ./tutorial-klt-tracker \endcode -It can also be run with [--init-by-click] option. In that case, the user can select a set of keypoints to track with a left mouse click. A right mouse click stops the keypoints selection and allows to start the tracking. +It can also be run with [--init-by-click] option. In that case, the user can select a set of keypoints to track with a +left mouse click. A right mouse click stops the keypoints selection and allows to start the tracking. \code $ ./tutorial-klt-tracker --init-by-click \endcode @@ -39,16 +41,22 @@ Here is the line by line explanation of the source : \snippet tutorial-klt-tracker.cpp Include -We include here the headers that define the corresponding classes. vpImageConvert class will be used to convert ViSP images implemented in vpImage class into OpenCV -cv::Mat structures used as an entry by the KLT tracker. Then we include the header of vpKltOpencv class which is the wrapper over OpenCV KLT tracker implementation. +We include here the headers that define the corresponding classes. vpImageConvert class will be used to convert ViSP +images implemented in vpImage class into OpenCV +cv::Mat structures used as an entry by the KLT tracker. Then we include the header of vpKltOpencv class which is the +wrapper over OpenCV KLT tracker implementation. -We need also to include a device to display the images. We retain vpDisplayOpenCV that works on Unix and Windows since OpenCV is mandatory by the tracker. Finally we include vpVideoReader header that will be used to read an mpeg input stream. +We need also to include a device to display the images. We retain vpDisplayOpenCV that works on Unix and Windows since +OpenCV is mandatory by the tracker. Finally we include vpVideoReader header that will be used to read an mpeg input +stream. -At the beginning of the main() function, we use the following macro to ensure that OpenCV requested by the tracker is available. Note that OpenCV will also be used to render the images and read the input video stream. +At the beginning of the main() function, we use the following macro to ensure that OpenCV requested by the tracker is +available. Note that OpenCV will also be used to render the images and read the input video stream. \snippet tutorial-klt-tracker.cpp Check 3rd party -The program starts by the creation of a vpVideoReader instance able to extract all the images of the video file \c video-postcard.mpeg. Here, the video should be in the same folder than the binary. +The program starts by the creation of a vpVideoReader instance able to extract all the images of the video file +\c video-postcard.mpeg. Here, the video should be in the same folder than the binary. \snippet tutorial-klt-tracker.cpp Create reader @@ -60,7 +68,8 @@ This image \c I is then converted into \c cvI, an OpenCV image format that will \snippet tutorial-klt-tracker.cpp Convert to OpenCV image -We also create a window associated to \c I, at position (0,0) in the screen, with "Klt tracking" as title, and display image \c I. +We also create a window associated to \c I, at position (0,0) in the screen, with "Klt tracking" as title, and display +image \c I. \snippet tutorial-klt-tracker.cpp Init display @@ -72,7 +81,8 @@ The tracker is then initialized on \c cvI image. \snippet tutorial-klt-tracker.cpp Init tracker -With the next line the user can know how many keypoints were detected automatically or selected by the user during initialization. +With the next line the user can know how many keypoints were detected automatically or selected by the user during +initialization. \snippet tutorial-klt-tracker.cpp How many features @@ -82,7 +92,8 @@ To detect more keypoints, you may decrease the quality parameter set with the fo \snippet tutorial-klt-tracker.cpp Quality -Until the end of the video, we get \c I the next image in ViSP format, display and convert it in OpenCV format. Then we track the Harris keypoints using KLT tracker before displaying the keypoints that are tracked with a red cross. +Until the end of the video, we get \c I the next image in ViSP format, display and convert it in OpenCV format. +Then we track the Harris keypoints using KLT tracker before displaying the keypoints that are tracked with a red cross. \snippet tutorial-klt-tracker.cpp While loop @@ -92,7 +103,10 @@ We are waiting for a mouse click event on image \c I to end the program. \section tracking_keypoint_klt_init KLT tracker with re-initialisation -Once initialized, the number of tracked features decreases over the time. Depending on a criteria, it may sense to detect and track new features online. A possible criteria is for example to compare the number of currently tracked features to the initial number of detected features. If less than a given percentage of features are tracked, you can start a new detection. +Once initialized, the number of tracked features decreases over the time. Depending on a criteria, it may sense to +detect and track new features online. A possible criteria is for example to compare the number of currently tracked +features to the initial number of detected features. If less than a given percentage of features are tracked, +you can start a new detection. To get the number of detected or tracked features just call: @@ -102,7 +116,8 @@ To get the number of detected or tracked features just call: Then the idea is to add the previously tracked features to the list of features that are detected. -The example tutorial-klt-tracker-with-reinit.cpp shows how to do that. In that example we start a new detection on frame 25. Compared to the previous code available in tutorial-klt-tracker.cpp we add the following lines: +The example tutorial-klt-tracker-with-reinit.cpp shows how to do that. In that example we start a new detection on +frame 25. Compared to the previous code available in tutorial-klt-tracker.cpp we add the following lines: \code if (reader.getFrameIndex() == 25) { @@ -143,7 +158,9 @@ The example tutorial-klt-tracker-with-reinit.cpp shows how to do that. In that e In this code we do the following: - save the features that are tracked until now - initialize the tracker to detect new features -- parse all the saved features and compare them to the newly detected features. If a previous feature is close in terms of geometric distance to a newly detected one, it is rejected (in our case less than 2 pixels). If not, it is added to the list of detected features. +- parse all the saved features and compare them to the newly detected features. If a previous feature is close in + terms of geometric distance to a newly detected one, it is rejected (in our case less than 2 pixels). If not, it is + added to the list of detected features. \section tracking_keypoint_next Next tutorial You are now ready to see the next \ref tutorial-tracking-me. diff --git a/doc/tutorial/tracking/tutorial-tracking-mb-deprected.dox b/doc/tutorial/tracking/tutorial-tracking-mb-deprected.dox index 087ac77a88..438082764d 100644 --- a/doc/tutorial/tracking/tutorial-tracking-mb-deprected.dox +++ b/doc/tutorial/tracking/tutorial-tracking-mb-deprected.dox @@ -6,46 +6,69 @@ \section mbdep_intro Introduction \warning -This tutorial can be considered obsolete since ViSP 3.1.0 version as we have introduced a generic tracker (vpMbGenericTracker) that can replace the vpMbEdgeTracker, vpMbKltTracker and vpMbEdgeKltTracker classes that are used in this tutorial. Thus we recommend rather to follow \ref tutorial-tracking-mb-generic. - -ViSP allows simultaneously the tracking of a markerless object using the knowledge of its CAD model while providing its 3D localization (i.e., the object pose expressed in the camera frame) when a calibrated camera is used \cite Comport06b. Considered objects should be modeled by lines, circles or cylinders. The CAD model of the object could be defined in vrml format (except for circles), or in cao format. - -To follow this tutorial depending on your interest you should be sure that ViSP was build with the following third-parties: -- \c OpenCV: Useful if you want to investigate the KLT keypoint tracker implemented in vpMbKltTracker or its hybrid version vpMbEdgeKltTracker. We recommend to install \c OpenCV. This 3rd party may be also useful to consider input videos (mpeg, png, jpeg...). -- \c Ogre \c 3D: This 3rd party is optional and could be difficult to instal on OSX and Windows. To begin with the tracker we don't recommend to install it. \c Ogre \c 3D allows to enable \ref mbdep_settings_visibility_ogre. -- \c Coin \c 3D: This 3rd party is also optional and difficult to install. That's why we don't recommend to install \c Coin \c 3D to begin with the tracker. \c Coin \c 3D allows only to consider \ref mbdep_advanced_wrml instead of the home-made \ref mbdep_advanced_cao. - -Next sections highlight how to use the differents versions of the markerless model-based trackers that are implemented in ViSP. - -Note that all the material (source code and video) described in this tutorial is part of ViSP source code and could be downloaded using the following command: - -\code -$ svn export https://github.com/lagadic/visp.git/trunk/tutorial/tracking/model-based/old/generic -\endcode +This tutorial can be considered obsolete since ViSP 3.1.0 version as we have introduced a generic tracker +(vpMbGenericTracker) that can replace the vpMbEdgeTracker, vpMbKltTracker and vpMbEdgeKltTracker classes that are used +in this tutorial. Thus we recommend rather to follow \ref tutorial-tracking-mb-generic. + +ViSP allows simultaneously the tracking of a markerless object using the knowledge of its CAD model while providing its +3D localization (i.e., the object pose expressed in the camera frame) when a calibrated camera is used \cite Comport06b. +Considered objects should be modeled by lines, circles or cylinders. The CAD model of the object could be defined in +vrml format (except for circles), or in cao format. + +To follow this tutorial depending on your interest you should be sure that ViSP was build with the following +third-parties: +- \c OpenCV: Useful if you want to investigate the KLT keypoint tracker implemented in vpMbKltTracker or its hybrid + version vpMbEdgeKltTracker. We recommend to install \c OpenCV. This 3rd party may be also useful to consider input + videos (mpeg, png, jpeg...). +- \c Ogre \c 3D: This 3rd party is optional and could be difficult to instal on OSX and Windows. To begin with the + tracker we don't recommend to install it. \c Ogre \c 3D allows to enable \ref mbdep_settings_visibility_ogre. +- \c Coin \c 3D: This 3rd party is also optional and difficult to install. That's why we don't recommend to install + \c Coin \c 3D to begin with the tracker. \c Coin \c 3D allows only to consider \ref mbdep_advanced_wrml instead of + the home-made \ref mbdep_advanced_cao. + +Next sections highlight how to use the differents versions of the markerless model-based trackers that are +implemented in ViSP. + +Note that all the material (source code and videos) described in this tutorial is part of ViSP source code +(in `tutorial/tracking/model-based/old/generic` folder) and could be found in +https://github.com/lagadic/visp/tree/master/tutorial/tracking/model-based/old/generic. \section mbdep_started Getting started In ViSP, depending on the visual features that are used three trackers are available: -- a tracker implemented in vpMbEdgeTracker that consider moving-edges behind the visible lines of the model. This tracker is appropriate to track texture less objects. -- an other tracker implemented in vpMbKltTracker that consider KLT keypoints that are detected and tracked on each visible face of the model. This tracker is more designed to track textured objects with edges that are not really visible. -- an hybrid version implemented in vpMbEdgeKltTracker that is able to consider moving-edges and KLT keypoints. This tracker is appropriate to track textured objects with visible edges. +- a tracker implemented in vpMbEdgeTracker that consider moving-edges behind the visible lines of the model. +This tracker is appropriate to track texture less objects. +- an other tracker implemented in vpMbKltTracker that consider KLT keypoints that are detected and tracked on each + visible face of the model. This tracker is more designed to track textured objects with edges that are not really + visible. +- an hybrid version implemented in vpMbEdgeKltTracker that is able to consider moving-edges and KLT keypoints. + This tracker is appropriate to track textured objects with visible edges. \subsection mbdep_started_src Example source code -The following example that comes from tutorial-mb-tracker.cpp allows to track a tea box modeled in cao format using one of the markerless model-based tracker implemented in ViSP. +The following example that comes from tutorial-mb-tracker.cpp allows to track a tea box modeled in cao format using +one of the markerless model-based tracker implemented in ViSP. \include tutorial-mb-tracker.cpp -\note An extension of the previous getting started example is proposed in tutorial-mb-tracker-full.cpp where advanced functionalities such as reading tracker settings from an XML file or visibility computation are implemented. +\note An extension of the previous getting started example is proposed in tutorial-mb-tracker-full.cpp where advanced +functionalities such as reading tracker settings from an XML file or visibility computation are implemented. -\note Other tutorials that are specific to a given tracker are provided in tutorial-mb-edge-tracker.cpp, tutorial-mb-klt-tracker.cpp and tutorial-mb-hybrid-tracker.cpp. +\note Other tutorials that are specific to a given tracker are provided in tutorial-mb-edge-tracker.cpp, +tutorial-mb-klt-tracker.cpp and tutorial-mb-hybrid-tracker.cpp. \subsection mbdep_started_input Example input data The previous example uses the following data as input: - a video file; "teabox.mpg" is the default video. -- a cad model that describes the object to track. In our case the file \c "teabox.cao" is the default one. See \ref mbdep_model section to learn how the teabox is modelled and section \ref mbdep_advanced_cao to learn how to model an other object. -- a file with extension "*.init" that contains the 3D coordinates of some points used to compute an initial pose which serves to initialize the tracker. The user has than to click in the image on the corresponding 2D points. The default file is named `teabox.init`. The content of this file is detailed in \ref mbdep_started_src_explained section. -- an optional image with extension "*.ppm" that may help the user to remember the location of the corresponding 3D points specified in "*.init" file. +- a cad model that describes the object to track. In our case the file \c "teabox.cao" is the default one. See + \ref mbdep_model section to learn how the teabox is modelled and section \ref mbdep_advanced_cao to learn how to + model an other object. +- a file with extension "*.init" that contains the 3D coordinates of some points used to compute an initial pose + which serves to initialize the tracker. The user has than to click in the image on the corresponding 2D points. + The default file is named `teabox.init`. The content of this file is detailed in \ref mbdep_started_src_explained + section. +- an optional image with extension "*.ppm" that may help the user to remember the location of the corresponding 3D + points specified in "*.init" file. \subsection mbdep_started_exe Running the example @@ -55,7 +78,8 @@ Once build, to see the options that are available in the previous source code, j $ ./tutorial-mb-tracker --help Usage: ./tutorial-mb-tracker-full [--video